From edfc9753e3028aaec525e31f412d18ce01399078 Mon Sep 17 00:00:00 2001 From: Dazhen Chen Date: Fri, 7 Feb 2025 01:19:26 +0000 Subject: [PATCH 1/3] hw1.3 --- .../knowledge/defaults/computation_graph.yaml | 3 +++ homework/blink.py | 16 ++++++++-------- homework/blink_launch.yaml | 4 ++-- 3 files changed, 13 insertions(+), 10 deletions(-) diff --git a/GEMstack/knowledge/defaults/computation_graph.yaml b/GEMstack/knowledge/defaults/computation_graph.yaml index d7a606326..b6d5c92f7 100644 --- a/GEMstack/knowledge/defaults/computation_graph.yaml +++ b/GEMstack/knowledge/defaults/computation_graph.yaml @@ -52,3 +52,6 @@ components: - trajectory_tracking: inputs: [vehicle, trajectory] outputs: + - signaling: + inputs: [intent] + outputs: diff --git a/homework/blink.py b/homework/blink.py index 0ea73aa2c..b8b07c697 100644 --- a/homework/blink.py +++ b/homework/blink.py @@ -6,7 +6,6 @@ TURN_NONE = 1 TURN_LEFT = 2 TURN_HAZARD = 3 -TURN_AROUND = 4 # For message format, see # https://github.com/astuff/astuff_sensor_msgs/blob/3.3.0/pacmod_msgs/msg/PacmodCmd.msg @@ -48,19 +47,20 @@ def cleanup(self): def get_dir_distress(self): pass - def update(self): + def update(self, inputs): """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 + if inputs.intent.intent == "HALTING": + 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 diff --git a/homework/blink_launch.yaml b/homework/blink_launch.yaml index 41174f692..0b17ac054 100644 --- a/homework/blink_launch.yaml +++ b/homework/blink_launch.yaml @@ -9,14 +9,14 @@ recovery: state_estimation : GNSSStateEstimator perception_normalization : StandardPerceptionNormalizer planning: - trajectory_tracking : blink_component.BlinkDistress + 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: - trajectory_tracking : blink_component.BlinkDistress + signaling: blink_component.BlinkDistress log: # Specify the top-level folder to save the log files. Default is 'logs' folder : 'logs' From dfbafe25b991993ea9cf9dd286ca5e088009f81b Mon Sep 17 00:00:00 2001 From: Dazhen Chen Date: Wed, 12 Feb 2025 22:10:58 +0000 Subject: [PATCH 2/3] finalize hw1.3 --- GEMstack/onboard/planning/blink_component.py | 3 +++ homework/blink.py | 8 ++++---- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/GEMstack/onboard/planning/blink_component.py b/GEMstack/onboard/planning/blink_component.py index 4415c0c82..9ee6a9164 100644 --- a/GEMstack/onboard/planning/blink_component.py +++ b/GEMstack/onboard/planning/blink_component.py @@ -38,6 +38,9 @@ def update(self): # 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. + + #if Allstate.intent.intent == "HALTING" : + #return current_time = time.time() if current_time - self.last_update_time >= 2: # Change signal every 2 seconds if self.turn_state == TURN_OFF: diff --git a/homework/blink.py b/homework/blink.py index b8b07c697..89de04639 100644 --- a/homework/blink.py +++ b/homework/blink.py @@ -47,14 +47,14 @@ def cleanup(self): def get_dir_distress(self): pass - def update(self, inputs): + def update(self, Allstate): """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 inputs.intent.intent == "HALTING": + if Allstate.intent.intent == "HALTING": if self.turn_cmd.ui16_cmd == TURN_NONE: self.turn_cmd.ui16_cmd = TURN_LEFT elif self.turn_cmd.ui16_cmd == TURN_LEFT: @@ -97,7 +97,7 @@ def accel_callback(self, msg): rospy.loginfo(f"Output: {msg.output} (Final Output to Vehicle)") rospy.loginfo("---------------------------\n") -def run_ros_loop(node): +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. @@ -111,7 +111,7 @@ def run_ros_loop(node): termination_reason = "undetermined" try: while not rospy.is_shutdown() and not node.done() and node.healthy(): - node.update() + node.update(node, Allstate) rate.sleep() if node.done(): termination_reason = "Node done" From 67eab1649b2d479d9bfdb9459de373f25c02c9c3 Mon Sep 17 00:00:00 2001 From: Mikayel Aramyan <115953604+mikayel2@users.noreply.github.com> Date: Thu, 13 Feb 2025 21:23:00 -0600 Subject: [PATCH 3/3] Fine tuning tracking and comfort level, comfort index added as a metric --- GEMstack/knowledge/defaults/current.yaml | 4 +- GEMstack/onboard/planning/pure_pursuit.py | 2 +- .../PurePursuitTrajectoryTracker_debug.csv | 3242 ++++++++ .../behavior.json | 6605 +++++++++++++++++ .../meta.yaml | 19 + .../plots/accel.png | Bin 0 -> 256695 bytes .../plots/cte.png | Bin 0 -> 256033 bytes .../plots/error_v.png | Bin 0 -> 247998 bytes .../plots/error_x.png | Bin 0 -> 229730 bytes .../plots/error_y.png | Bin 0 -> 209620 bytes .../plots/front_wheel_angle.png | Bin 0 -> 229255 bytes .../plots/v_vs_vd.png | Bin 0 -> 385738 bytes .../plots/x_vs_xd.png | Bin 0 -> 344059 bytes .../plots/y_vs_yd.png | Bin 0 -> 309408 bytes .../settings.yaml | 325 + tuning logs/Parameter Tuning.xlsx | Bin 0 -> 37174 bytes tuning logs/log_plot.py | 26 +- 17 files changed, 10219 insertions(+), 4 deletions(-) create mode 100644 tuning logs/2025-02-13_21-10-39 (fine tuning)/PurePursuitTrajectoryTracker_debug.csv create mode 100644 tuning logs/2025-02-13_21-10-39 (fine tuning)/behavior.json create mode 100644 tuning logs/2025-02-13_21-10-39 (fine tuning)/meta.yaml create mode 100644 tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/accel.png create mode 100644 tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/cte.png create mode 100644 tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_v.png create mode 100644 tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_x.png create mode 100644 tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_y.png create mode 100644 tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/front_wheel_angle.png create mode 100644 tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/v_vs_vd.png create mode 100644 tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/x_vs_xd.png create mode 100644 tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/y_vs_yd.png create mode 100644 tuning logs/2025-02-13_21-10-39 (fine tuning)/settings.yaml create mode 100644 tuning logs/Parameter Tuning.xlsx diff --git a/GEMstack/knowledge/defaults/current.yaml b/GEMstack/knowledge/defaults/current.yaml index 149080f58..12a9f55c5 100644 --- a/GEMstack/knowledge/defaults/current.yaml +++ b/GEMstack/knowledge/defaults/current.yaml @@ -13,12 +13,12 @@ control: brake_speed : 2.0 pure_pursuit: lookahead: 2.0 - lookahead_scale: 3.0 + lookahead_scale: 2.0 crosstrack_gain: 0.5 desired_speed: trajectory longitudinal_control: pid_p: 1.0 - pid_i: 0.1 + pid_i: 0.05 pid_d: 0.0 #configure the simulator, if using diff --git a/GEMstack/onboard/planning/pure_pursuit.py b/GEMstack/onboard/planning/pure_pursuit.py index 48c0b7dfd..37ee25c39 100644 --- a/GEMstack/onboard/planning/pure_pursuit.py +++ b/GEMstack/onboard/planning/pure_pursuit.py @@ -164,7 +164,7 @@ def compute(self, state : VehicleState, component : Component = None): print("Feedforward accel: " + str(feedforward_accel) + " m/s^2") else: #decay speed when crosstrack error is high - desired_speed *= np.exp(-abs(ct_error)*1.0) + desired_speed *= np.exp(-abs(ct_error)*0.8) if desired_speed > self.speed_limit: desired_speed = self.speed_limit output_accel = self.pid_speed.advance(e = desired_speed - speed, t = t, feedforward_term=feedforward_accel) diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/PurePursuitTrajectoryTracker_debug.csv b/tuning logs/2025-02-13_21-10-39 (fine tuning)/PurePursuitTrajectoryTracker_debug.csv new file mode 100644 index 000000000..e39604776 --- /dev/null +++ b/tuning logs/2025-02-13_21-10-39 (fine tuning)/PurePursuitTrajectoryTracker_debug.csv @@ -0,0 +1,3242 @@ +curr pt[0] time,curr pt[0] vehicle time,curr pt[0],curr pt[1] time,curr pt[1] vehicle time,curr pt[1],curr param time,curr param vehicle time,curr param,desired pt[0] time,desired pt[0] vehicle time,desired pt[0],desired pt[1] time,desired pt[1] vehicle time,desired pt[1],desired yaw (rad) time,desired yaw (rad) vehicle time,desired yaw (rad),crosstrack error time,crosstrack error vehicle time,crosstrack error,front wheel angle (rad) time,front wheel angle (rad) vehicle time,front wheel angle (rad),desired speed (m/s) time,desired speed (m/s) vehicle time,desired speed (m/s),feedforward accel (m/s^2) time,feedforward accel (m/s^2) vehicle time,feedforward accel (m/s^2),output accel (m/s^2) time,output accel (m/s^2) vehicle time,output accel (m/s^2),current yaw (rad) time,current yaw (rad) vehicle time,current yaw (rad),current speed (m/s) time,current speed (m/s) vehicle time,current speed (m/s) +1739502639.5794408,0.029999971389770508,0.0,1739502639.5794437,0.029999971389770508,0.0,1739502639.5794468,0.029999971389770508,2e-06,1739502639.5794497,0.029999971389770508,1.9947503416207786,1739502639.579451,0.029999971389770508,-0.06638719928805828,1739502639.579453,0.029999971389770508,-0.03326867705567338,1739502639.579455,0.029999971389770508,-0.06638719928805828,1739502639.5794566,0.029999971389770508,-0.1279158618748393,1739502639.579458,0.029999971389770508,2.370689811361755,1739502639.57946,0.029999971389770508,0.0,1739502639.5794618,0.029999971389770508,2.370689811361755,1739502639.5794635,0.029999971389770508,0.0,1739502639.579465,0.029999971389770508,0.0 +1739502639.5991945,0.04999995231628418,0.0,1739502639.5991986,0.04999995231628418,0.0,1739502639.5992029,0.04999995231628418,2e-06,1739502639.599206,0.04999995231628418,1.9947503416207786,1739502639.5992079,0.04999995231628418,-0.06638719928805828,1739502639.5992103,0.04999995231628418,-0.03326867705567338,1739502639.599213,0.04999995231628418,-0.06638719928805828,1739502639.5992148,0.04999995231628418,-0.1279158618748393,1739502639.5992165,0.04999995231628418,2.370689811361755,1739502639.5992181,0.04999995231628418,0.0,1739502639.5992198,0.04999995231628418,2.370689811361755,1739502639.5992215,0.04999995231628418,0.0,1739502639.5992231,0.04999995231628418,0.0 +1739502639.6183183,0.06999993324279785,0.00047983963609077307,1739502639.6183212,0.06999993324279785,-6.804403263060976e-09,1739502639.618324,0.06999993324279785,1.520160363909227e-06,1739502639.618327,0.06999993324279785,2.05869696822515,1739502639.6183283,0.06999993324279785,-0.06716502371355604,1739502639.61833,0.06999993324279785,-0.03262104377967774,1739502639.6183317,0.06999993324279785,-0.06706948465977582,1739502639.6183329,0.06999993324279785,-0.12139602026825669,1739502639.6183345,0.06999993324279785,2.369396174862239,1739502639.618336,0.06999993324279785,0.0,1739502639.6183374,0.06999993324279785,2.322297716956859,1739502639.6183388,0.06999993324279785,6.283138892165478,1739502639.61834,0.06999993324279785,0.03197591848874033 +1739502639.6381671,0.08999991416931152,0.00047983963609077307,1739502639.6381693,0.08999991416931152,-6.804403263060976e-09,1739502639.6381721,0.08999991416931152,1.520160363909227e-06,1739502639.638175,0.08999991416931152,2.05869696822515,1739502639.6381764,0.08999991416931152,-0.06716502371355604,1739502639.638178,0.08999991416931152,-0.03262104377967774,1739502639.6381795,0.08999991416931152,-0.06706948465977582,1739502639.638181,0.08999991416931152,-0.12139602026825669,1739502639.6381822,0.08999991416931152,2.369396174862239,1739502639.6381836,0.08999991416931152,0.0,1739502639.6381853,0.08999991416931152,2.3374202563734987,1739502639.6381865,0.08999991416931152,6.283138892165478,1739502639.6381881,0.08999991416931152,0.03197591848874033 +1739502639.6776097,0.1099998950958252,0.00047983963609077307,1739502639.6776133,0.1099998950958252,-6.804403263060976e-09,1739502639.6776173,0.1099998950958252,1.520160363909227e-06,1739502639.6776206,0.1099998950958252,2.05869696822515,1739502639.6776223,0.1099998950958252,-0.06716502371355604,1739502639.6776242,0.1099998950958252,-0.03262104377967774,1739502639.677626,0.1099998950958252,-0.06706948465977582,1739502639.6776278,0.1099998950958252,-0.12139602026825669,1739502639.6776292,0.1099998950958252,2.369396174862239,1739502639.6776314,0.1099998950958252,0.0,1739502639.677633,0.1099998950958252,2.3374202563734987,1739502639.6776345,0.1099998950958252,6.283138892165478,1739502639.6776361,0.1099998950958252,0.03197591848874033 +1739502639.7040946,0.14999985694885254,0.00047983963609077307,1739502639.7041,0.14999985694885254,-6.804403263060976e-09,1739502639.704105,0.14999985694885254,1.520160363909227e-06,1739502639.704109,0.14999985694885254,2.05869696822515,1739502639.7041109,0.14999985694885254,-0.06716502371355604,1739502639.7041135,0.14999985694885254,-0.03262104377967774,1739502639.7041175,0.14999985694885254,-0.06706948465977582,1739502639.7041202,0.14999985694885254,-0.12139602026825669,1739502639.704122,0.14999985694885254,2.369396174862239,1739502639.7041247,0.14999985694885254,0.0,1739502639.7041268,0.14999985694885254,2.3374202563734987,1739502639.704129,0.14999985694885254,6.283138892165478,1739502639.7041314,0.14999985694885254,0.03197591848874033 +1739502639.7231534,0.1699998378753662,0.00047983963609077307,1739502639.7231562,0.1699998378753662,-6.804403263060976e-09,1739502639.7231596,0.1699998378753662,1.520160363909227e-06,1739502639.7231624,0.1699998378753662,2.05869696822515,1739502639.7231636,0.1699998378753662,-0.06716502371355604,1739502639.7231655,0.1699998378753662,-0.03262104377967774,1739502639.7231672,0.1699998378753662,-0.06706948465977582,1739502639.7231688,0.1699998378753662,-0.12139602026825669,1739502639.7231703,0.1699998378753662,2.369396174862239,1739502639.723172,0.1699998378753662,0.0,1739502639.7231734,0.1699998378753662,2.3374202563734987,1739502639.7231746,0.1699998378753662,6.283138892165478,1739502639.7231762,0.1699998378753662,0.03197591848874033 +1739502639.8222353,0.19999980926513672,0.009488760476915381,1739502639.82224,0.19999980926513672,-3.58028625679907e-06,1739502639.8222456,0.19999980926513672,0.0,1739502639.822252,0.19999980926513672,2.2781082034004916,1739502639.8222554,0.19999980926513672,-0.06986746817333699,1739502639.8222601,0.19999980926513672,-0.030786042513801123,1739502639.8222644,0.19999980926513672,-0.0680247658429978,1739502639.8222685,0.19999980926513672,-0.1013743189631224,1739502639.8222723,0.19999980926513672,2.3675861149316564,1739502639.8222764,0.19999980926513672,0.0,1739502639.8222804,0.19999980926513672,2.175197469240814,1739502639.8222847,0.19999980926513672,6.282374638252922,1739502639.8222892,0.19999980926513672,0.1416939914738729 +1739502639.8888443,0.2799997329711914,0.009488760476915381,1739502639.888847,0.2799997329711914,-3.58028625679907e-06,1739502639.8888502,0.2799997329711914,0.0,1739502639.888853,0.2799997329711914,2.2781082034004916,1739502639.8888547,0.2799997329711914,-0.06986746817333699,1739502639.8888566,0.2799997329711914,-0.030786042513801123,1739502639.8888578,0.2799997329711914,-0.0680247658429978,1739502639.8888595,0.2799997329711914,-0.1013743189631224,1739502639.8888607,0.2799997329711914,2.3675861149316564,1739502639.8888621,0.2799997329711914,0.0,1739502639.8888636,0.2799997329711914,2.2258921234577835,1739502639.888865,0.2799997329711914,6.282374638252922,1739502639.8888662,0.2799997329711914,0.1416939914738729 +1739502639.907965,0.3099997043609619,0.030547019841669965,1739502639.9079678,0.3099997043609619,-3.691379956194396e-05,1739502639.907971,0.3099997043609619,0.0215519580373643,1739502639.907974,0.3099997043609619,2.518590721821713,1739502639.9079752,0.3099997043609619,-0.073,1739502639.907978,0.3099997043609619,-0.02931708202390329,1739502639.9079828,0.3099997043609619,-0.06672760156828361,1739502639.9079869,0.3099997043609619,-0.08269274153147879,1739502639.9079907,0.3099997043609619,2.370044308683982,1739502639.9079928,0.3099997043609619,0.0,1739502639.9079943,0.3099997043609619,2.070223958273649,1739502639.907996,0.3099997043609619,6.280679216940032,1739502639.9079976,0.3099997043609619,0.2511740168952693 +1739502639.928167,0.3299996852874756,0.030547019841669965,1739502639.9281712,0.3299996852874756,-3.691379956194396e-05,1739502639.9281745,0.3299996852874756,0.0215519580373643,1739502639.9281778,0.3299996852874756,2.518590721821713,1739502639.9281797,0.3299996852874756,-0.073,1739502639.9281816,0.3299996852874756,-0.02931708202390329,1739502639.9281845,0.3299996852874756,-0.06672760156828361,1739502639.928187,0.3299996852874756,-0.08269274153147879,1739502639.9281883,0.3299996852874756,2.370044308683982,1739502639.9281912,0.3299996852874756,0.0,1739502639.9281933,0.3299996852874756,2.1188702917887126,1739502639.9281952,0.3299996852874756,6.280679216940032,1739502639.9281976,0.3299996852874756,0.2511740168952693 +1739502639.9489899,0.34999966621398926,0.030547019841669965,1739502639.9489946,0.34999966621398926,-3.691379956194396e-05,1739502639.9490004,0.34999966621398926,0.0215519580373643,1739502639.9490056,0.34999966621398926,2.518590721821713,1739502639.9490082,0.34999966621398926,-0.073,1739502639.9490116,0.34999966621398926,-0.02931708202390329,1739502639.949014,0.34999966621398926,-0.06672760156828361,1739502639.949017,0.34999966621398926,-0.08269274153147879,1739502639.9490197,0.34999966621398926,2.370044308683982,1739502639.9490228,0.34999966621398926,0.0,1739502639.9490256,0.34999966621398926,2.1188702917887126,1739502639.949028,0.34999966621398926,6.280679216940032,1739502639.9490314,0.34999966621398926,0.2511740168952693 +1739502639.9683585,0.36999964714050293,0.030547019841669965,1739502639.9683614,0.36999964714050293,-3.691379956194396e-05,1739502639.9683654,0.36999964714050293,0.0215519580373643,1739502639.9683683,0.36999964714050293,2.518590721821713,1739502639.96837,0.36999964714050293,-0.073,1739502639.9683716,0.36999964714050293,-0.02931708202390329,1739502639.9683733,0.36999964714050293,-0.06672760156828361,1739502639.968375,0.36999964714050293,-0.08269274153147879,1739502639.9683766,0.36999964714050293,2.370044308683982,1739502639.9683783,0.36999964714050293,0.0,1739502639.9683797,0.36999964714050293,2.1188702917887126,1739502639.9683812,0.36999964714050293,6.280679216940032,1739502639.9683828,0.36999964714050293,0.2511740168952693 +1739502639.9880989,0.3899996280670166,0.030547019841669965,1739502639.9881015,0.3899996280670166,-3.691379956194396e-05,1739502639.9881043,0.3899996280670166,0.0215519580373643,1739502639.9881072,0.3899996280670166,2.518590721821713,1739502639.9881089,0.3899996280670166,-0.073,1739502639.9881105,0.3899996280670166,-0.02931708202390329,1739502639.9881122,0.3899996280670166,-0.06672760156828361,1739502639.9881136,0.3899996280670166,-0.08269274153147879,1739502639.9881148,0.3899996280670166,2.370044308683982,1739502639.9881165,0.3899996280670166,0.0,1739502639.988118,0.3899996280670166,2.1188702917887126,1739502639.9881196,0.3899996280670166,6.280679216940032,1739502639.9881208,0.3899996280670166,0.2511740168952693 +1739502640.0080516,0.4099996089935303,0.06365559344657257,1739502640.0080543,0.4099996089935303,-0.00015719778843248378,1739502640.008057,0.4099996089935303,0.021883043773413324,1739502640.00806,0.4099996089935303,2.738058327968718,1739502640.0080612,0.4099996089935303,-0.07506884463600816,1739502640.008063,0.4099996089935303,-0.02800328587449252,1739502640.0080645,0.4099996089935303,-0.06193778715602109,1739502640.008066,0.4099996089935303,-0.06644337125463601,1739502640.0080674,0.4099996089935303,2.3791433886220754,1739502640.0080688,0.4099996089935303,0.0,1739502640.0080705,0.4099996089935303,1.9727211494889747,1739502640.008072,0.4099996089935303,6.278334493555943,1739502640.0080736,0.4099996089935303,0.36075060221977395 +1739502640.0279503,0.42999958992004395,0.06365559344657257,1739502640.0279531,0.42999958992004395,-0.00015719778843248378,1739502640.0279562,0.42999958992004395,0.021883043773413324,1739502640.0279593,0.42999958992004395,2.738058327968718,1739502640.0279605,0.42999958992004395,-0.07506884463600816,1739502640.0279624,0.42999958992004395,-0.02800328587449252,1739502640.027964,0.42999958992004395,-0.06193778715602109,1739502640.0279658,0.42999958992004395,-0.06644337125463601,1739502640.027967,0.42999958992004395,2.3791433886220754,1739502640.027969,0.42999958992004395,0.0,1739502640.0279703,0.42999958992004395,2.0183927864023015,1739502640.0279717,0.42999958992004395,6.278334493555943,1739502640.0279734,0.42999958992004395,0.36075060221977395 +1739502640.0479147,0.4499995708465576,0.06365559344657257,1739502640.0479176,0.4499995708465576,-0.00015719778843248378,1739502640.0479207,0.4499995708465576,0.021883043773413324,1739502640.0479238,0.4499995708465576,2.738058327968718,1739502640.0479252,0.4499995708465576,-0.07506884463600816,1739502640.0479271,0.4499995708465576,-0.02800328587449252,1739502640.0479286,0.4499995708465576,-0.06193778715602109,1739502640.04793,0.4499995708465576,-0.06644337125463601,1739502640.0479317,0.4499995708465576,2.3791433886220754,1739502640.0479333,0.4499995708465576,0.0,1739502640.047935,0.4499995708465576,2.0183927864023015,1739502640.0479364,0.4499995708465576,6.278334493555943,1739502640.047938,0.4499995708465576,0.36075060221977395 +1739502640.06786,0.4699995517730713,0.06365559344657257,1739502640.0678627,0.4699995517730713,-0.00015719778843248378,1739502640.067866,0.4699995517730713,0.021883043773413324,1739502640.0678692,0.4699995517730713,2.738058327968718,1739502640.0678706,0.4699995517730713,-0.07506884463600816,1739502640.0678728,0.4699995517730713,-0.02800328587449252,1739502640.0678742,0.4699995517730713,-0.06193778715602109,1739502640.0678759,0.4699995517730713,-0.06644337125463601,1739502640.0678773,0.4699995517730713,2.3791433886220754,1739502640.0678794,0.4699995517730713,0.0,1739502640.0678806,0.4699995517730713,2.0183927864023015,1739502640.0678823,0.4699995517730713,6.278334493555943,1739502640.0678837,0.4699995517730713,0.36075060221977395 +1739502640.0878034,0.48999953269958496,0.06365559344657257,1739502640.0878057,0.48999953269958496,-0.00015719778843248378,1739502640.0878086,0.48999953269958496,0.021883043773413324,1739502640.0878115,0.48999953269958496,2.738058327968718,1739502640.087813,0.48999953269958496,-0.07506884463600816,1739502640.0878146,0.48999953269958496,-0.02800328587449252,1739502640.0878162,0.48999953269958496,-0.06193778715602109,1739502640.0878177,0.48999953269958496,-0.06644337125463601,1739502640.0878193,0.48999953269958496,2.3791433886220754,1739502640.0878208,0.48999953269958496,0.0,1739502640.0878222,0.48999953269958496,2.0183927864023015,1739502640.0878236,0.48999953269958496,6.278334493555943,1739502640.087825,0.48999953269958496,0.36075060221977395 +1739502640.10837,0.5099995136260986,0.10882169667425678,1739502640.108373,0.5099995136260986,-0.0004272615560179105,1739502640.1083765,0.5099995136260986,0.022334704805690164,1739502640.1083803,0.5099995136260986,2.957740733492,1739502640.1083822,0.5099995136260986,-0.077,1739502640.1083844,0.5099995136260986,-0.02687135235706951,1739502640.108386,0.5099995136260986,-0.056006179090768306,1739502640.108388,0.5099995136260986,-0.052951494053988635,1739502640.1083894,0.5099995136260986,2.3904599344023905,1739502640.1083915,0.5099995136260986,0.0,1739502640.108393,0.5099995136260986,1.8754046053508828,1739502640.1083949,0.5099995136260986,6.275966870030994,1739502640.1083968,0.5099995136260986,0.47037149317593346 +1739502640.1363766,0.5299994945526123,0.10882169667425678,1739502640.136391,0.5299994945526123,-0.0004272615560179105,1739502640.1364095,0.5299994945526123,0.022334704805690164,1739502640.1364307,0.5299994945526123,2.957740733492,1739502640.136443,0.5299994945526123,-0.077,1739502640.136458,0.5299994945526123,-0.02687135235706951,1739502640.1364715,0.5299994945526123,-0.056006179090768306,1739502640.136485,0.5299994945526123,-0.052951494053988635,1739502640.1364987,0.5299994945526123,2.3904599344023905,1739502640.1365128,0.5299994945526123,0.0,1739502640.1365266,0.5299994945526123,1.920088441226457,1739502640.1365407,0.5299994945526123,6.275966870030994,1739502640.1365545,0.5299994945526123,0.47037149317593346 +1739502640.1559532,0.549999475479126,0.10882169667425678,1739502640.1559675,0.549999475479126,-0.0004272615560179105,1739502640.1559856,0.549999475479126,0.022334704805690164,1739502640.1560068,0.549999475479126,2.957740733492,1739502640.1560187,0.549999475479126,-0.077,1739502640.156034,0.549999475479126,-0.02687135235706951,1739502640.1560476,0.549999475479126,-0.056006179090768306,1739502640.1560612,0.549999475479126,-0.052951494053988635,1739502640.1560748,0.549999475479126,2.3904599344023905,1739502640.1560888,0.549999475479126,0.0,1739502640.1561024,0.549999475479126,1.920088441226457,1739502640.1561165,0.549999475479126,6.275966870030994,1739502640.1561303,0.549999475479126,0.47037149317593346 +1739502640.1753914,0.5699994564056396,0.10882169667425678,1739502640.1753974,0.5699994564056396,-0.0004272615560179105,1739502640.1754055,0.5699994564056396,0.022334704805690164,1739502640.1754148,0.5699994564056396,2.957740733492,1739502640.1754198,0.5699994564056396,-0.077,1739502640.1754262,0.5699994564056396,-0.02687135235706951,1739502640.1754322,0.5699994564056396,-0.056006179090768306,1739502640.1754382,0.5699994564056396,-0.052951494053988635,1739502640.175444,0.5699994564056396,2.3904599344023905,1739502640.17545,0.5699994564056396,0.0,1739502640.175456,0.5699994564056396,1.920088441226457,1739502640.1754618,0.5699994564056396,6.275966870030994,1739502640.175468,0.5699994564056396,0.47037149317593346 +1739502640.194292,0.5899994373321533,0.10882169667425678,1739502640.1942956,0.5899994373321533,-0.0004272615560179105,1739502640.1943002,0.5899994373321533,0.022334704805690164,1739502640.1943054,0.5899994373321533,2.957740733492,1739502640.1943085,0.5899994373321533,-0.077,1739502640.1943128,0.5899994373321533,-0.02687135235706951,1739502640.1943164,0.5899994373321533,-0.056006179090768306,1739502640.19432,0.5899994373321533,-0.052951494053988635,1739502640.1943235,0.5899994373321533,2.3904599344023905,1739502640.194327,0.5899994373321533,0.0,1739502640.1943305,0.5899994373321533,1.920088441226457,1739502640.194334,0.5899994373321533,6.275966870030994,1739502640.1943378,0.5899994373321533,0.47037149317593346 +1739502640.2141337,0.609999418258667,0.10882169667425678,1739502640.2141373,0.609999418258667,-0.0004272615560179105,1739502640.2141418,0.609999418258667,0.022334704805690164,1739502640.2141476,0.609999418258667,2.957740733492,1739502640.2141504,0.609999418258667,-0.077,1739502640.2141542,0.609999418258667,-0.02687135235706951,1739502640.2141578,0.609999418258667,-0.056006179090768306,1739502640.2141614,0.609999418258667,-0.052951494053988635,1739502640.2141647,0.609999418258667,2.3904599344023905,1739502640.2141683,0.609999418258667,0.0,1739502640.214172,0.609999418258667,1.920088441226457,1739502640.2141755,0.609999418258667,6.275966870030994,1739502640.214179,0.609999418258667,0.47037149317593346 +1739502640.2347357,0.6299993991851807,0.16605068655188848,1739502640.2347395,0.6299993991851807,-0.0009043270420709959,1739502640.23475,0.6299993991851807,0.02290699470446648,1739502640.2347555,0.6299993991851807,3.17762407557747,1739502640.2347586,0.6299993991851807,-0.08008663722247125,1739502640.2347627,0.6299993991851807,-0.026286615384780634,1739502640.234766,0.6299993991851807,-0.05030998898661317,1739502640.2347696,0.6299993991851807,-0.04256957009120678,1739502640.2347732,0.6299993991851807,2.4013780034457635,1739502640.2347767,0.6299993991851807,0.0,1739502640.2347803,0.6299993991851807,1.7764492094825028,1739502640.234784,0.6299993991851807,6.273599246506047,1739502640.2347872,0.6299993991851807,0.5800415046128746 +1739502640.2544994,0.6499993801116943,0.16605068655188848,1739502640.2545033,0.6499993801116943,-0.0009043270420709959,1739502640.2545078,0.6499993801116943,0.02290699470446648,1739502640.2545135,0.6499993801116943,3.17762407557747,1739502640.2545164,0.6499993801116943,-0.08008663722247125,1739502640.2545204,0.6499993801116943,-0.026286615384780634,1739502640.254524,0.6499993801116943,-0.05030998898661317,1739502640.2545276,0.6499993801116943,-0.04256957009120678,1739502640.2545311,0.6499993801116943,2.4013780034457635,1739502640.2545347,0.6499993801116943,0.0,1739502640.254538,0.6499993801116943,1.8213364988328888,1739502640.2545416,0.6499993801116943,6.273599246506047,1739502640.2545455,0.6499993801116943,0.5800415046128746 +1739502640.274287,0.669999361038208,0.16605068655188848,1739502640.2742908,0.669999361038208,-0.0009043270420709959,1739502640.274295,0.669999361038208,0.02290699470446648,1739502640.2743,0.669999361038208,3.17762407557747,1739502640.274303,0.669999361038208,-0.08008663722247125,1739502640.2743065,0.669999361038208,-0.026286615384780634,1739502640.2743099,0.669999361038208,-0.05030998898661317,1739502640.2743132,0.669999361038208,-0.04256957009120678,1739502640.2743163,0.669999361038208,2.4013780034457635,1739502640.27432,0.669999361038208,0.0,1739502640.274323,0.669999361038208,1.8213364988328888,1739502640.2743266,0.669999361038208,6.273599246506047,1739502640.27433,0.669999361038208,0.5800415046128746 +1739502640.294291,0.6899993419647217,0.16605068655188848,1739502640.2942934,0.6899993419647217,-0.0009043270420709959,1739502640.2942963,0.6899993419647217,0.02290699470446648,1739502640.2942991,0.6899993419647217,3.17762407557747,1739502640.2943003,0.6899993419647217,-0.08008663722247125,1739502640.2943022,0.6899993419647217,-0.026286615384780634,1739502640.2943034,0.6899993419647217,-0.05030998898661317,1739502640.2943048,0.6899993419647217,-0.04256957009120678,1739502640.294306,0.6899993419647217,2.4013780034457635,1739502640.2943075,0.6899993419647217,0.0,1739502640.2943091,0.6899993419647217,1.8213364988328888,1739502640.2943103,0.6899993419647217,6.273599246506047,1739502640.294312,0.6899993419647217,0.5800415046128746 +1739502640.3135154,0.7099993228912354,0.16605068655188848,1739502640.313518,0.7099993228912354,-0.0009043270420709959,1739502640.313521,0.7099993228912354,0.02290699470446648,1739502640.3135238,0.7099993228912354,3.17762407557747,1739502640.3135252,0.7099993228912354,-0.08008663722247125,1739502640.313527,0.7099993228912354,-0.026286615384780634,1739502640.3135285,0.7099993228912354,-0.05030998898661317,1739502640.3135302,0.7099993228912354,-0.04256957009120678,1739502640.3135314,0.7099993228912354,2.4013780034457635,1739502640.313533,0.7099993228912354,0.0,1739502640.3135345,0.7099993228912354,1.8213364988328888,1739502640.313536,0.7099993228912354,6.273599246506047,1739502640.3135376,0.7099993228912354,0.5800415046128746 +1739502640.333441,0.729999303817749,0.2353344217403004,1739502640.3334439,0.729999303817749,-0.0016454362006603773,1739502640.3334472,0.729999303817749,0.023599832056350602,1739502640.3334506,0.729999303817749,3.397459815032914,1739502640.333452,0.729999303817749,-0.08416954125074805,1739502640.3334541,0.729999303817749,-0.02609174749193811,1739502640.3334558,0.729999303817749,-0.04472006099628646,1739502640.3334575,0.729999303817749,-0.034323438540162184,1739502640.333459,0.729999303817749,2.4121408750736038,1739502640.3334608,0.729999303817749,0.0,1739502640.3334625,0.729999303817749,1.677584920641746,1739502640.3334644,0.729999303817749,6.271231622981098,1739502640.3334658,0.729999303817749,0.6896335567937066 +1739502640.3568933,0.7499992847442627,0.2353344217403004,1739502640.3569028,0.7499992847442627,-0.0016454362006603773,1739502640.3569148,0.7499992847442627,0.023599832056350602,1739502640.3569255,0.7499992847442627,3.397459815032914,1739502640.3569312,0.7499992847442627,-0.08416954125074805,1739502640.3569381,0.7499992847442627,-0.02609174749193811,1739502640.3569438,0.7499992847442627,-0.04472006099628646,1739502640.3569493,0.7499992847442627,-0.034323438540162184,1739502640.3569543,0.7499992847442627,2.4121408750736038,1739502640.3569608,0.7499992847442627,0.0,1739502640.3569658,0.7499992847442627,1.7225073182798971,1739502640.3569717,0.7499992847442627,6.271231622981098,1739502640.3569775,0.7499992847442627,0.6896335567937066 +1739502640.3850803,0.7699992656707764,0.2353344217403004,1739502640.385095,0.7699992656707764,-0.0016454362006603773,1739502640.3851132,0.7699992656707764,0.023599832056350602,1739502640.3851342,0.7699992656707764,3.397459815032914,1739502640.3851469,0.7699992656707764,-0.08416954125074805,1739502640.3851619,0.7699992656707764,-0.02609174749193811,1739502640.3851755,0.7699992656707764,-0.04472006099628646,1739502640.385189,0.7699992656707764,-0.034323438540162184,1739502640.3852026,0.7699992656707764,2.4121408750736038,1739502640.385217,0.7699992656707764,0.0,1739502640.3852313,0.7699992656707764,1.7225073182798971,1739502640.385245,0.7699992656707764,6.271231622981098,1739502640.385259,0.7699992656707764,0.6896335567937066 +1739502640.3975549,0.78999924659729,0.2353344217403004,1739502640.39756,0.78999924659729,-0.0016454362006603773,1739502640.3975656,0.78999924659729,0.023599832056350602,1739502640.3975716,0.78999924659729,3.397459815032914,1739502640.3975747,0.78999924659729,-0.08416954125074805,1739502640.397578,0.78999924659729,-0.02609174749193811,1739502640.397581,0.78999924659729,-0.04472006099628646,1739502640.397584,0.78999924659729,-0.034323438540162184,1739502640.3975866,0.78999924659729,2.4121408750736038,1739502640.3975902,0.78999924659729,0.0,1739502640.397593,0.78999924659729,1.7225073182798971,1739502640.3975961,0.78999924659729,6.271231622981098,1739502640.397599,0.78999924659729,0.6896335567937066 +1739502640.41485,0.8099992275238037,0.2353344217403004,1739502640.414855,0.8099992275238037,-0.0016454362006603773,1739502640.4148607,0.8099992275238037,0.023599832056350602,1739502640.4148676,0.8099992275238037,3.397459815032914,1739502640.4148715,0.8099992275238037,-0.08416954125074805,1739502640.4148762,0.8099992275238037,-0.02609174749193811,1739502640.4148808,0.8099992275238037,-0.04472006099628646,1739502640.414885,0.8099992275238037,-0.034323438540162184,1739502640.4148896,0.8099992275238037,2.4121408750736038,1739502640.414894,0.8099992275238037,0.0,1739502640.4148986,0.8099992275238037,1.7225073182798971,1739502640.4149034,0.8099992275238037,6.271231622981098,1739502640.4149082,0.8099992275238037,0.6896335567937066 +1739502640.434772,0.8299992084503174,0.2353344217403004,1739502640.4347758,0.8299992084503174,-0.0016454362006603773,1739502640.4347808,0.8299992084503174,0.023599832056350602,1739502640.4347866,0.8299992084503174,3.397459815032914,1739502640.4347897,0.8299992084503174,-0.08416954125074805,1739502640.4347937,0.8299992084503174,-0.02609174749193811,1739502640.434797,0.8299992084503174,-0.04472006099628646,1739502640.4348006,0.8299992084503174,-0.034323438540162184,1739502640.4348042,0.8299992084503174,2.4121408750736038,1739502640.434808,0.8299992084503174,0.0,1739502640.4348116,0.8299992084503174,1.7225073182798971,1739502640.4348152,0.8299992084503174,6.271231622981098,1739502640.4348187,0.8299992084503174,0.6896335567937066 +1739502640.4545758,0.849999189376831,0.3166765633221438,1739502640.4545803,0.849999189376831,-0.002707735237910569,1739502640.4545853,0.849999189376831,0.024413253472169036,1739502640.454591,0.849999189376831,3.617526599584563,1739502640.4545944,0.849999189376831,-0.08810172133897894,1739502640.4545984,0.849999189376831,-0.02586453252762726,1739502640.4546022,0.849999189376831,-0.038114355898973114,1739502640.4546058,0.849999189376831,-0.026847018324658536,1739502640.4546092,0.849999189376831,2.4249217289696032,1739502640.4546132,0.849999189376831,0.0,1739502640.4546168,0.849999189376831,1.5816125429031744,1739502640.4546206,0.849999189376831,6.26886399945615,1739502640.4546242,0.849999189376831,0.7992795398931174 +1739502640.4740784,0.8699991703033447,0.3166765633221438,1739502640.4740825,0.8699991703033447,-0.002707735237910569,1739502640.4740882,0.8699991703033447,0.024413253472169036,1739502640.4740937,0.8699991703033447,3.617526599584563,1739502640.4740965,0.8699991703033447,-0.08810172133897894,1739502640.4741008,0.8699991703033447,-0.02586453252762726,1739502640.4741044,0.8699991703033447,-0.038114355898973114,1739502640.4741082,0.8699991703033447,-0.026847018324658536,1739502640.474112,0.8699991703033447,2.4249217289696032,1739502640.4741156,0.8699991703033447,0.0,1739502640.4741194,0.8699991703033447,1.6256421890764858,1739502640.474123,0.8699991703033447,6.26886399945615,1739502640.4741268,0.8699991703033447,0.7992795398931174 +1739502640.502023,0.8899991512298584,0.3166765633221438,1739502640.5020378,0.8899991512298584,-0.002707735237910569,1739502640.5020564,0.8899991512298584,0.024413253472169036,1739502640.5020776,0.8899991512298584,3.617526599584563,1739502640.5020895,0.8899991512298584,-0.08810172133897894,1739502640.5021048,0.8899991512298584,-0.02586453252762726,1739502640.5021186,0.8899991512298584,-0.038114355898973114,1739502640.5021322,0.8899991512298584,-0.026847018324658536,1739502640.502146,0.8899991512298584,2.4249217289696032,1739502640.50216,0.8899991512298584,0.0,1739502640.502174,0.8899991512298584,1.6256421890764858,1739502640.502188,0.8899991512298584,6.26886399945615,1739502640.5022023,0.8899991512298584,0.7992795398931174 +1739502640.5192823,0.9099991321563721,0.3166765633221438,1739502640.5192907,0.9099991321563721,-0.002707735237910569,1739502640.519299,0.9099991321563721,0.024413253472169036,1739502640.5193076,0.9099991321563721,3.617526599584563,1739502640.519312,0.9099991321563721,-0.08810172133897894,1739502640.5193172,0.9099991321563721,-0.02586453252762726,1739502640.5193214,0.9099991321563721,-0.038114355898973114,1739502640.5193253,0.9099991321563721,-0.026847018324658536,1739502640.519329,0.9099991321563721,2.4249217289696032,1739502640.5193338,0.9099991321563721,0.0,1739502640.519338,0.9099991321563721,1.6256421890764858,1739502640.5193422,0.9099991321563721,6.26886399945615,1739502640.5193465,0.9099991321563721,0.7992795398931174 +1739502640.5347235,0.9299991130828857,0.3166765633221438,1739502640.5347276,0.9299991130828857,-0.002707735237910569,1739502640.534732,0.9299991130828857,0.024413253472169036,1739502640.534736,0.9299991130828857,3.617526599584563,1739502640.5347378,0.9299991130828857,-0.08810172133897894,1739502640.5347404,0.9299991130828857,-0.02586453252762726,1739502640.5347428,0.9299991130828857,-0.038114355898973114,1739502640.5347447,0.9299991130828857,-0.026847018324658536,1739502640.5347466,0.9299991130828857,2.4249217289696032,1739502640.534749,0.9299991130828857,0.0,1739502640.5347512,0.9299991130828857,1.6256421890764858,1739502640.5347533,0.9299991130828857,6.26886399945615,1739502640.5347552,0.9299991130828857,0.7992795398931174 +1739502640.555539,0.9499990940093994,0.4100681339427581,1739502640.5555413,0.9499990940093994,-0.0041482056880957074,1739502640.5555441,0.9499990940093994,0.02534716917837518,1739502640.555547,0.9499990940093994,3.837532068798082,1739502640.5555484,0.9499990940093994,-0.09302319255726027,1739502640.55555,0.9499990940093994,-0.025924437836012997,1739502640.5555515,0.9499990940093994,-0.03166455566573931,1739502640.5555532,0.9499990940093994,-0.020686643758999892,1739502640.5555546,0.9499990940093994,2.4374662736468435,1739502640.5555565,0.9499990940093994,0.0,1739502640.5555582,0.9499990940093994,1.4845239615592318,1739502640.5555596,0.9499990940093994,6.266496375931202,1739502640.555561,0.9499990940093994,0.9088428370746009 +1739502640.575119,0.9699990749359131,0.4100681339427581,1739502640.5751214,0.9699990749359131,-0.0041482056880957074,1739502640.5751243,0.9699990749359131,0.02534716917837518,1739502640.5751274,0.9699990749359131,3.837532068798082,1739502640.5751286,0.9699990749359131,-0.09302319255726027,1739502640.5751305,0.9699990749359131,-0.025924437836012997,1739502640.575132,0.9699990749359131,-0.03166455566573931,1739502640.5751333,0.9699990749359131,-0.020686643758999892,1739502640.5751348,0.9699990749359131,2.4374662736468435,1739502640.5751364,0.9699990749359131,0.0,1739502640.575138,0.9699990749359131,1.5286234365722426,1739502640.5751395,0.9699990749359131,6.266496375931202,1739502640.575141,0.9699990749359131,0.9088428370746009 +1739502640.5953233,0.9899990558624268,0.4100681339427581,1739502640.5953262,0.9899990558624268,-0.0041482056880957074,1739502640.5953293,0.9899990558624268,0.02534716917837518,1739502640.5953321,0.9899990558624268,3.837532068798082,1739502640.5953336,0.9899990558624268,-0.09302319255726027,1739502640.5953355,0.9899990558624268,-0.025924437836012997,1739502640.5953367,0.9899990558624268,-0.03166455566573931,1739502640.5953383,0.9899990558624268,-0.020686643758999892,1739502640.5953395,0.9899990558624268,2.4374662736468435,1739502640.595341,0.9899990558624268,0.0,1739502640.5953424,0.9899990558624268,1.5286234365722426,1739502640.5953438,0.9899990558624268,6.266496375931202,1739502640.5953455,0.9899990558624268,0.9088428370746009 +1739502640.6145818,1.0099990367889404,0.4100681339427581,1739502640.614584,1.0099990367889404,-0.0041482056880957074,1739502640.6145866,1.0099990367889404,0.02534716917837518,1739502640.6145897,1.0099990367889404,3.837532068798082,1739502640.614591,1.0099990367889404,-0.09302319255726027,1739502640.6145928,1.0099990367889404,-0.025924437836012997,1739502640.6145942,1.0099990367889404,-0.03166455566573931,1739502640.6145957,1.0099990367889404,-0.020686643758999892,1739502640.6145968,1.0099990367889404,2.4374662736468435,1739502640.6145985,1.0099990367889404,0.0,1739502640.6145997,1.0099990367889404,1.5286234365722426,1739502640.6146011,1.0099990367889404,6.266496375931202,1739502640.6146026,1.0099990367889404,0.9088428370746009 +1739502640.6344874,1.029999017715454,0.4100681339427581,1739502640.6344895,1.029999017715454,-0.0041482056880957074,1739502640.6344926,1.029999017715454,0.02534716917837518,1739502640.6344955,1.029999017715454,3.837532068798082,1739502640.6344967,1.029999017715454,-0.09302319255726027,1739502640.6344986,1.029999017715454,-0.025924437836012997,1739502640.6344998,1.029999017715454,-0.03166455566573931,1739502640.6345015,1.029999017715454,-0.020686643758999892,1739502640.6345026,1.029999017715454,2.4374662736468435,1739502640.634504,1.029999017715454,0.0,1739502640.6345055,1.029999017715454,1.5286234365722426,1739502640.634507,1.029999017715454,6.266496375931202,1739502640.6345086,1.029999017715454,0.9088428370746009 +1739502640.665321,1.0599989891052246,0.5155128223249328,1739502640.6653266,1.0599989891052246,-0.006024001398603929,1739502640.6653323,1.0599989891052246,0.026401616062196927,1739502640.6653385,1.0599989891052246,4.0578073735183535,1739502640.665342,1.0599989891052246,-0.09596058485825128,1739502640.6653469,1.0599989891052246,-0.025383904323323894,1739502640.6653507,1.0599989891052246,-0.022420409104920064,1739502640.6653545,1.0599989891052246,-0.01371363294952331,1739502640.6653578,1.0599989891052246,2.455558928024578,1739502640.665362,1.0599989891052246,0.0,1739502640.6653655,1.0599989891052246,1.3954898514590925,1739502640.665369,1.0599989891052246,6.264128752406254,1739502640.6653728,1.0599989891052246,1.0184648039397393 +1739502640.6937695,1.0799989700317383,0.5155128223249328,1739502640.693774,1.0799989700317383,-0.006024001398603929,1739502640.6937795,1.0799989700317383,0.026401616062196927,1739502640.6937854,1.0799989700317383,4.0578073735183535,1739502640.6937885,1.0799989700317383,-0.09596058485825128,1739502640.6937923,1.0799989700317383,-0.025383904323323894,1739502640.693796,1.0799989700317383,-0.022420409104920064,1739502640.6937995,1.0799989700317383,-0.01371363294952331,1739502640.6938028,1.0799989700317383,2.455558928024578,1739502640.6938066,1.0799989700317383,0.0,1739502640.69381,1.0799989700317383,1.4370941240848387,1739502640.6938136,1.0799989700317383,6.264128752406254,1739502640.6938174,1.0799989700317383,1.0184648039397393 +1739502640.6997993,1.099998950958252,0.5155128223249328,1739502640.6998043,1.099998950958252,-0.006024001398603929,1739502640.6998112,1.099998950958252,0.026401616062196927,1739502640.699819,1.099998950958252,4.0578073735183535,1739502640.6998234,1.099998950958252,-0.09596058485825128,1739502640.6998284,1.099998950958252,-0.025383904323323894,1739502640.6998305,1.099998950958252,-0.022420409104920064,1739502640.6998534,1.099998950958252,-0.01371363294952331,1739502640.699855,1.099998950958252,2.455558928024578,1739502640.6998587,1.099998950958252,0.0,1739502640.6998658,1.099998950958252,1.4370941240848387,1739502640.6998703,1.099998950958252,6.264128752406254,1739502640.6998754,1.099998950958252,1.0184648039397393 +1739502640.7195532,1.1199989318847656,0.5155128223249328,1739502640.7195568,1.1199989318847656,-0.006024001398603929,1739502640.7195604,1.1199989318847656,0.026401616062196927,1739502640.7195635,1.1199989318847656,4.0578073735183535,1739502640.7195654,1.1199989318847656,-0.09596058485825128,1739502640.7195675,1.1199989318847656,-0.025383904323323894,1739502640.7195694,1.1199989318847656,-0.022420409104920064,1739502640.719571,1.1199989318847656,-0.01371363294952331,1739502640.7195728,1.1199989318847656,2.455558928024578,1739502640.7195745,1.1199989318847656,0.0,1739502640.7195761,1.1199989318847656,1.4370941240848387,1739502640.7195776,1.1199989318847656,6.264128752406254,1739502640.7195795,1.1199989318847656,1.0184648039397393 +1739502640.7412546,1.1399989128112793,0.5155128223249328,1739502640.7412622,1.1399989128112793,-0.006024001398603929,1739502640.741271,1.1399989128112793,0.026401616062196927,1739502640.741279,1.1399989128112793,4.0578073735183535,1739502640.7412827,1.1399989128112793,-0.09596058485825128,1739502640.7412882,1.1399989128112793,-0.025383904323323894,1739502640.7412922,1.1399989128112793,-0.022420409104920064,1739502640.7412963,1.1399989128112793,-0.01371363294952331,1739502640.7413,1.1399989128112793,2.455558928024578,1739502640.7413049,1.1399989128112793,0.0,1739502640.7413087,1.1399989128112793,1.4370941240848387,1739502640.741313,1.1399989128112793,6.264128752406254,1739502640.7413173,1.1399989128112793,1.0184648039397393 +1739502640.7623806,1.159998893737793,0.5155128223249328,1739502640.762388,1.159998893737793,-0.006024001398603929,1739502640.7623968,1.159998893737793,0.026401616062196927,1739502640.7624054,1.159998893737793,4.0578073735183535,1739502640.7624094,1.159998893737793,-0.09596058485825128,1739502640.7624152,1.159998893737793,-0.025383904323323894,1739502640.7624192,1.159998893737793,-0.022420409104920064,1739502640.7624235,1.159998893737793,-0.01371363294952331,1739502640.7624273,1.159998893737793,2.455558928024578,1739502640.762432,1.159998893737793,0.0,1739502640.7624362,1.159998893737793,1.4370941240848387,1739502640.7624407,1.159998893737793,6.264128752406254,1739502640.7624452,1.159998893737793,1.0184648039397393 +1739502640.7894094,1.1799988746643066,0.6330084566019529,1739502640.7894175,1.1799988746643066,-0.008388629592535501,1739502640.789426,1.1799988746643066,0.02757657240496713,1739502640.7894342,1.1799988746643066,4.278170138816449,1739502640.789438,1.1799988746643066,-0.09952495456837804,1739502640.789443,1.1799988746643066,-0.024996790339990207,1739502640.7894478,1.1799988746643066,-0.013291131241874572,1739502640.7894518,1.1799988746643066,-0.007677454177262558,1739502640.7894557,1.1799988746643066,2.473558561288127,1739502640.7894602,1.1799988746643066,0.0,1739502640.7894642,1.1799988746643066,1.3038427011648865,1739502640.7894688,1.1799988746643066,6.2618336249659325,1739502640.789473,1.1799988746643066,1.1280747631587245 +1739502640.8133814,1.2099988460540771,0.6330084566019529,1739502640.8133948,1.2099988460540771,-0.008388629592535501,1739502640.813412,1.2099988460540771,0.02757657240496713,1739502640.8134277,1.2099988460540771,4.278170138816449,1739502640.8134363,1.2099988460540771,-0.09952495456837804,1739502640.8134484,1.2099988460540771,-0.024996790339990207,1739502640.8134606,1.2099988460540771,-0.013291131241874572,1739502640.8134735,1.2099988460540771,-0.007677454177262558,1739502640.8134828,1.2099988460540771,2.473558561288127,1739502640.8134875,1.2099988460540771,0.0,1739502640.8134913,1.2099988460540771,1.3454837981294023,1739502640.813496,1.2099988460540771,6.2618336249659325,1739502640.8135002,1.2099988460540771,1.1280747631587245 +1739502640.835117,1.2299988269805908,0.6330084566019529,1739502640.835128,1.2299988269805908,-0.008388629592535501,1739502640.8351417,1.2299988269805908,0.02757657240496713,1739502640.8351574,1.2299988269805908,4.278170138816449,1739502640.835167,1.2299988269805908,-0.09952495456837804,1739502640.835181,1.2299988269805908,-0.024996790339990207,1739502640.8351943,1.2299988269805908,-0.013291131241874572,1739502640.835205,1.2299988269805908,-0.007677454177262558,1739502640.835215,1.2299988269805908,2.473558561288127,1739502640.8352258,1.2299988269805908,0.0,1739502640.835236,1.2299988269805908,1.3454837981294023,1739502640.8352466,1.2299988269805908,6.2618336249659325,1739502640.8352568,1.2299988269805908,1.1280747631587245 +1739502640.854858,1.2499988079071045,0.6330084566019529,1739502640.854865,1.2499988079071045,-0.008388629592535501,1739502640.8548746,1.2499988079071045,0.02757657240496713,1739502640.854883,1.2499988079071045,4.278170138816449,1739502640.8548877,1.2499988079071045,-0.09952495456837804,1739502640.854893,1.2499988079071045,-0.024996790339990207,1739502640.8548977,1.2499988079071045,-0.013291131241874572,1739502640.8549018,1.2499988079071045,-0.007677454177262558,1739502640.8549056,1.2499988079071045,2.473558561288127,1739502640.8549101,1.2499988079071045,0.0,1739502640.8549142,1.2499988079071045,1.3454837981294023,1739502640.8549192,1.2499988079071045,6.2618336249659325,1739502640.854923,1.2499988079071045,1.1280747631587245 +1739502640.8747249,1.2699987888336182,0.6330084566019529,1739502640.8747323,1.2699987888336182,-0.008388629592535501,1739502640.8747408,1.2699987888336182,0.02757657240496713,1739502640.874749,1.2699987888336182,4.278170138816449,1739502640.8747528,1.2699987888336182,-0.09952495456837804,1739502640.8747582,1.2699987888336182,-0.024996790339990207,1739502640.8747625,1.2699987888336182,-0.013291131241874572,1739502640.8747666,1.2699987888336182,-0.007677454177262558,1739502640.8747706,1.2699987888336182,2.473558561288127,1739502640.8747756,1.2699987888336182,0.0,1739502640.8747797,1.2699987888336182,1.3454837981294023,1739502640.874784,1.2699987888336182,6.2618336249659325,1739502640.874788,1.2699987888336182,1.1280747631587245 +1739502640.8945048,1.2899987697601318,0.7625444461948137,1739502640.894512,1.2899987697601318,-0.011284503608371743,1739502640.89452,1.2899987697601318,0.028871932300895735,1739502640.894528,1.2899987697601318,4.498478494353831,1739502640.8945317,1.2899987697601318,-0.10276618876341846,1739502640.894537,1.2899987697601318,-0.024482072237631287,1739502640.894541,1.2899987697601318,-0.003796239992356659,1739502640.894545,1.2899987697601318,-0.0020876422536527765,1739502640.894549,1.2899987697601318,2.4924190375032937,1739502640.8945537,1.2899987697601318,0.0,1739502640.894558,1.2899987697601318,1.2136150749875065,1739502640.894562,1.2899987697601318,6.259719072741353,1739502640.8945668,1.2899987697601318,1.237594959515217 +1739502640.9148214,1.3099987506866455,0.7625444461948137,1739502640.9148293,1.3099987506866455,-0.011284503608371743,1739502640.9148383,1.3099987506866455,0.028871932300895735,1739502640.9148467,1.3099987506866455,4.498478494353831,1739502640.9148521,1.3099987506866455,-0.10276618876341846,1739502640.9148586,1.3099987506866455,-0.024482072237631287,1739502640.914863,1.3099987506866455,-0.003796239992356659,1739502640.9148674,1.3099987506866455,-0.0020876422536527765,1739502640.9148715,1.3099987506866455,2.4924190375032937,1739502640.9148765,1.3099987506866455,0.0,1739502640.9148805,1.3099987506866455,1.2548240779880768,1739502640.914885,1.3099987506866455,6.259719072741353,1739502640.9148898,1.3099987506866455,1.237594959515217 +1739502640.9547343,1.3499987125396729,0.7625444461948137,1739502640.954738,1.3499987125396729,-0.011284503608371743,1739502640.9547422,1.3499987125396729,0.028871932300895735,1739502640.9547465,1.3499987125396729,4.498478494353831,1739502640.9547484,1.3499987125396729,-0.10276618876341846,1739502640.9547508,1.3499987125396729,-0.024482072237631287,1739502640.954753,1.3499987125396729,-0.003796239992356659,1739502640.954755,1.3499987125396729,-0.0020876422536527765,1739502640.9547572,1.3499987125396729,2.4924190375032937,1739502640.9547594,1.3499987125396729,0.0,1739502640.9547615,1.3499987125396729,1.2548240779880768,1739502640.9547634,1.3499987125396729,6.259719072741353,1739502640.9547656,1.3499987125396729,1.237594959515217 +1739502640.9748285,1.3699986934661865,0.7625444461948137,1739502640.9748309,1.3699986934661865,-0.011284503608371743,1739502640.974834,1.3699986934661865,0.028871932300895735,1739502640.9748368,1.3699986934661865,4.498478494353831,1739502640.974838,1.3699986934661865,-0.10276618876341846,1739502640.97484,1.3699986934661865,-0.024482072237631287,1739502640.9748414,1.3699986934661865,-0.003796239992356659,1739502640.9748428,1.3699986934661865,-0.0020876422536527765,1739502640.9748442,1.3699986934661865,2.4924190375032937,1739502640.974846,1.3699986934661865,0.0,1739502640.9748473,1.3699986934661865,1.2548240779880768,1739502640.9748487,1.3699986934661865,6.259719072741353,1739502640.97485,1.3699986934661865,1.237594959515217 +1739502640.9951413,1.3899986743927002,0.9041174697190657,1739502640.9951444,1.3899986743927002,-0.014731825254432174,1739502640.9951475,1.3899986743927002,0.030287662536138252,1739502640.9951503,1.3899986743927002,4.718890758243079,1739502640.9951518,1.3899986743927002,-0.10530649184882504,1739502640.9951537,1.3899986743927002,-0.02373867211054338,1739502640.9951549,1.3899986743927002,0.005957619212993994,1739502640.9951568,1.3899986743927002,0.0031423284542696586,1739502640.995158,1.3899986743927002,2.4881131110986328,1739502640.9951596,1.3899986743927002,0.0,1739502640.995161,1.3899986743927002,1.08927955105566,1739502640.995163,1.3899986743927002,6.257885351441234,1739502640.9951644,1.3899986743927002,1.347100861457992 +1739502641.0138514,1.4099986553192139,0.9041174697190657,1739502641.0138538,1.4099986553192139,-0.014731825254432174,1739502641.0138562,1.4099986553192139,0.030287662536138252,1739502641.0138588,1.4099986553192139,4.718890758243079,1739502641.01386,1.4099986553192139,-0.10530649184882504,1739502641.0138617,1.4099986553192139,-0.02373867211054338,1739502641.013863,1.4099986553192139,0.005957619212993994,1739502641.0138645,1.4099986553192139,0.0031423284542696586,1739502641.0138657,1.4099986553192139,2.4881131110986328,1739502641.0138674,1.4099986553192139,0.0,1739502641.0138683,1.4099986553192139,1.1410122496406407,1739502641.0138698,1.4099986553192139,6.257885351441234,1739502641.0138714,1.4099986553192139,1.347100861457992 +1739502641.0339303,1.4299986362457275,0.9041174697190657,1739502641.0339324,1.4299986362457275,-0.014731825254432174,1739502641.0339355,1.4299986362457275,0.030287662536138252,1739502641.0339382,1.4299986362457275,4.718890758243079,1739502641.0339396,1.4299986362457275,-0.10530649184882504,1739502641.0339413,1.4299986362457275,-0.02373867211054338,1739502641.0339427,1.4299986362457275,0.005957619212993994,1739502641.0339441,1.4299986362457275,0.0031423284542696586,1739502641.0339458,1.4299986362457275,2.4881131110986328,1739502641.0339477,1.4299986362457275,0.0,1739502641.033949,1.4299986362457275,1.1410122496406407,1739502641.0339506,1.4299986362457275,6.257885351441234,1739502641.033952,1.4299986362457275,1.347100861457992 +1739502641.0538464,1.4499986171722412,0.9041174697190657,1739502641.0538487,1.4499986171722412,-0.014731825254432174,1739502641.0538516,1.4499986171722412,0.030287662536138252,1739502641.0538547,1.4499986171722412,4.718890758243079,1739502641.0538564,1.4499986171722412,-0.10530649184882504,1739502641.0538578,1.4499986171722412,-0.02373867211054338,1739502641.0538595,1.4499986171722412,0.005957619212993994,1739502641.0538611,1.4499986171722412,0.0031423284542696586,1739502641.0538623,1.4499986171722412,2.4881131110986328,1739502641.0538645,1.4499986171722412,0.0,1739502641.0538657,1.4499986171722412,1.1410122496406407,1739502641.0538676,1.4499986171722412,6.257885351441234,1739502641.0538688,1.4499986171722412,1.347100861457992 +1739502641.0780823,1.4699985980987549,0.9041174697190657,1739502641.0780928,1.4699985980987549,-0.014731825254432174,1739502641.078105,1.4699985980987549,0.030287662536138252,1739502641.0781167,1.4699985980987549,4.718890758243079,1739502641.0781221,1.4699985980987549,-0.10530649184882504,1739502641.078129,1.4699985980987549,-0.02373867211054338,1739502641.0781345,1.4699985980987549,0.005957619212993994,1739502641.0781403,1.4699985980987549,0.0031423284542696586,1739502641.0781455,1.4699985980987549,2.4881131110986328,1739502641.0781522,1.4699985980987549,0.0,1739502641.078158,1.4699985980987549,1.1410122496406407,1739502641.0781639,1.4699985980987549,6.257885351441234,1739502641.0781698,1.4699985980987549,1.347100861457992 +1739502641.1015806,1.4899985790252686,0.9041174697190657,1739502641.1015952,1.4899985790252686,-0.014731825254432174,1739502641.1016135,1.4899985790252686,0.030287662536138252,1739502641.101635,1.4899985790252686,4.718890758243079,1739502641.1016467,1.4899985790252686,-0.10530649184882504,1739502641.1016617,1.4899985790252686,-0.02373867211054338,1739502641.1016755,1.4899985790252686,0.005957619212993994,1739502641.1016889,1.4899985790252686,0.0031423284542696586,1739502641.1017025,1.4899985790252686,2.4881131110986328,1739502641.1017165,1.4899985790252686,0.0,1739502641.1017303,1.4899985790252686,1.1410122496406407,1739502641.1017444,1.4899985790252686,6.257885351441234,1739502641.1017585,1.4899985790252686,1.347100861457992 +1739502641.120495,1.5099985599517822,1.057733673796732,1739502641.120505,1.5099985599517822,-0.018733655665641002,1739502641.1205168,1.5099985599517822,0.2371771832263732,1739502641.120528,1.5099985599517822,5.144887836913158,1739502641.1205335,1.5099985599517822,-0.11077973771494862,1739502641.1205406,1.5099985599517822,-0.022517018338008673,1739502641.1205466,1.5099985599517822,0.017902479370068874,1739502641.1205518,1.5099985599517822,0.008226423477328253,1739502641.120557,1.5099985599517822,2.464450220596629,1739502641.1205637,1.5099985599517822,0.0,1739502641.120569,1.5099985599517822,0.9472131207234842,1739502641.120575,1.5099985599517822,6.256289203143346,1739502641.1205807,1.5099985599517822,1.4566748323788168 +1739502641.1419575,1.529998540878296,1.057733673796732,1739502641.141965,1.529998540878296,-0.018733655665641002,1739502641.141977,1.529998540878296,0.2371771832263732,1739502641.1419866,1.529998540878296,5.144887836913158,1739502641.1419911,1.529998540878296,-0.11077973771494862,1739502641.1419976,1.529998540878296,-0.022517018338008673,1739502641.1420033,1.529998540878296,0.017902479370068874,1739502641.1420085,1.529998540878296,0.008226423477328253,1739502641.1420143,1.529998540878296,2.464450220596629,1739502641.14202,1.529998540878296,0.0,1739502641.1420255,1.529998540878296,1.0077753882178124,1739502641.1420312,1.529998540878296,6.256289203143346,1739502641.1420367,1.529998540878296,1.4566748323788168 +1739502641.158897,1.5599985122680664,1.057733673796732,1739502641.1589003,1.5599985122680664,-0.018733655665641002,1739502641.158904,1.5599985122680664,0.2371771832263732,1739502641.1589074,1.5599985122680664,5.144887836913158,1739502641.158909,1.5599985122680664,-0.11077973771494862,1739502641.1589112,1.5599985122680664,-0.022517018338008673,1739502641.1589131,1.5599985122680664,0.017902479370068874,1739502641.1589148,1.5599985122680664,0.008226423477328253,1739502641.1589167,1.5599985122680664,2.464450220596629,1739502641.1589184,1.5599985122680664,0.0,1739502641.15892,1.5599985122680664,1.0077753882178124,1739502641.1589217,1.5599985122680664,6.256289203143346,1739502641.1589239,1.5599985122680664,1.4566748323788168 +1739502641.1777298,1.57999849319458,1.057733673796732,1739502641.1777332,1.57999849319458,-0.018733655665641002,1739502641.177758,1.57999849319458,0.2371771832263732,1739502641.177761,1.57999849319458,5.144887836913158,1739502641.1777625,1.57999849319458,-0.11077973771494862,1739502641.1777642,1.57999849319458,-0.022517018338008673,1739502641.1777656,1.57999849319458,0.017902479370068874,1739502641.1777673,1.57999849319458,0.008226423477328253,1739502641.1777685,1.57999849319458,2.464450220596629,1739502641.1777701,1.57999849319458,0.0,1739502641.1777718,1.57999849319458,1.0077753882178124,1739502641.1777732,1.57999849319458,6.256289203143346,1739502641.177775,1.57999849319458,1.4566748323788168 +1739502641.199941,1.5999984741210938,1.057733673796732,1739502641.1999502,1.5999984741210938,-0.018733655665641002,1739502641.1999593,1.5999984741210938,0.2371771832263732,1739502641.1999662,1.5999984741210938,5.144887836913158,1739502641.1999698,1.5999984741210938,-0.11077973771494862,1739502641.1999755,1.5999984741210938,-0.022517018338008673,1739502641.1999848,1.5999984741210938,0.017902479370068874,1739502641.199994,1.5999984741210938,0.008226423477328253,1739502641.2000022,1.5999984741210938,2.464450220596629,1739502641.2000105,1.5999984741210938,0.0,1739502641.200015,1.5999984741210938,1.0077753882178124,1739502641.2000203,1.5999984741210938,6.256289203143346,1739502641.2000246,1.5999984741210938,1.4566748323788168 +1739502641.2194567,1.6199984550476074,1.2232570224346127,1739502641.2194657,1.6199984550476074,-0.023297337112818894,1739502641.2194726,1.6199984550476074,0.23850137001547628,1739502641.2194786,1.6199984550476074,5.362005910222087,1739502641.2194822,1.6199984550476074,-0.11319797823148008,1739502641.2194865,1.6199984550476074,-0.02171827965964367,1739502641.2194893,1.6199984550476074,0.027235237172512652,1739502641.2194936,1.6199984550476074,0.012205258041634514,1739502641.2194967,1.6199984550476074,2.446118645792294,1739502641.2195003,1.6199984550476074,0.0,1739502641.2195039,1.6199984550476074,0.8241603876901622,1739502641.2195072,1.6199984550476074,6.254887983614709,1739502641.2195106,1.6199984550476074,1.5645785328161617 +1739502641.2387338,1.639998435974121,1.2232570224346127,1739502641.2387385,1.639998435974121,-0.023297337112818894,1739502641.2387435,1.639998435974121,0.23850137001547628,1739502641.2387488,1.639998435974121,5.362005910222087,1739502641.238751,1.639998435974121,-0.11319797823148008,1739502641.2387538,1.639998435974121,-0.02171827965964367,1739502641.2387567,1.639998435974121,0.027235237172512652,1739502641.2387593,1.639998435974121,0.012205258041634514,1739502641.2387612,1.639998435974121,2.446118645792294,1739502641.2387645,1.639998435974121,0.0,1739502641.2387671,1.639998435974121,0.8815401129761324,1739502641.2387693,1.639998435974121,6.254887983614709,1739502641.2387722,1.639998435974121,1.5645785328161617 +1739502641.2580733,1.6599984169006348,1.2232570224346127,1739502641.2580774,1.6599984169006348,-0.023297337112818894,1739502641.2580822,1.6599984169006348,0.23850137001547628,1739502641.2580862,1.6599984169006348,5.362005910222087,1739502641.258088,1.6599984169006348,-0.11319797823148008,1739502641.2580907,1.6599984169006348,-0.02171827965964367,1739502641.2580926,1.6599984169006348,0.027235237172512652,1739502641.2580945,1.6599984169006348,0.012205258041634514,1739502641.2580965,1.6599984169006348,2.446118645792294,1739502641.2580986,1.6599984169006348,0.0,1739502641.2581005,1.6599984169006348,0.8815401129761324,1739502641.258103,1.6599984169006348,6.254887983614709,1739502641.2581048,1.6599984169006348,1.5645785328161617 +1739502641.2776577,1.6799983978271484,1.2232570224346127,1739502641.277664,1.6799983978271484,-0.023297337112818894,1739502641.2776704,1.6799983978271484,0.23850137001547628,1739502641.2776766,1.6799983978271484,5.362005910222087,1739502641.2776806,1.6799983978271484,-0.11319797823148008,1739502641.2776854,1.6799983978271484,-0.02171827965964367,1739502641.27769,1.6799983978271484,0.027235237172512652,1739502641.2776942,1.6799983978271484,0.012205258041634514,1739502641.2776976,1.6799983978271484,2.446118645792294,1739502641.2777011,1.6799983978271484,0.0,1739502641.2777052,1.6799983978271484,0.8815401129761324,1739502641.2777088,1.6799983978271484,6.254887983614709,1739502641.2777126,1.6799983978271484,1.5645785328161617 +1739502641.297352,1.699998378753662,1.2232570224346127,1739502641.2973554,1.699998378753662,-0.023297337112818894,1739502641.29736,1.699998378753662,0.23850137001547628,1739502641.2973647,1.699998378753662,5.362005910222087,1739502641.2973673,1.699998378753662,-0.11319797823148008,1739502641.2973707,1.699998378753662,-0.02171827965964367,1739502641.2973735,1.699998378753662,0.027235237172512652,1739502641.2973762,1.699998378753662,0.012205258041634514,1739502641.2973785,1.699998378753662,2.446118645792294,1739502641.2973814,1.699998378753662,0.0,1739502641.297384,1.699998378753662,0.8815401129761324,1739502641.2973866,1.699998378753662,6.254887983614709,1739502641.2973895,1.699998378753662,1.5645785328161617 +1739502641.3176162,1.7199983596801758,1.4001356780696703,1739502641.3176186,1.7199983596801758,-0.028404985312024067,1739502641.3176217,1.7199983596801758,0.731228953788296,1739502641.3176248,1.7199983596801758,6.047714517682896,1739502641.317626,1.7199983596801758,-0.12151260674766835,1739502641.317628,1.7199983596801758,-0.020030895995679324,1739502641.3176298,1.7199983596801758,0.04406556359172311,1739502641.317631,1.7199983596801758,0.01566133595438605,1739502641.3176322,1.7199983596801758,2.413404197735044,1739502641.3176339,1.7199983596801758,0.0,1739502641.317635,1.7199983596801758,0.6935587115788099,1739502641.3176365,1.7199983596801758,6.253674769223807,1739502641.3176382,1.7199983596801758,1.6611012597038548 +1739502641.337591,1.7399983406066895,1.4001356780696703,1739502641.3375936,1.7399983406066895,-0.028404985312024067,1739502641.3375967,1.7399983406066895,0.731228953788296,1739502641.3375993,1.7399983406066895,6.047714517682896,1739502641.3376005,1.7399983406066895,-0.12151260674766835,1739502641.3376024,1.7399983406066895,-0.020030895995679324,1739502641.3376038,1.7399983406066895,0.04406556359172311,1739502641.3376052,1.7399983406066895,0.01566133595438605,1739502641.3376067,1.7399983406066895,2.413404197735044,1739502641.337608,1.7399983406066895,0.0,1739502641.3376095,1.7399983406066895,0.7523029380311894,1739502641.337611,1.7399983406066895,6.253674769223807,1739502641.3376126,1.7399983406066895,1.6611012597038548 +1739502641.3576992,1.7599983215332031,1.4001356780696703,1739502641.3577015,1.7599983215332031,-0.028404985312024067,1739502641.3577046,1.7599983215332031,0.731228953788296,1739502641.3577073,1.7599983215332031,6.047714517682896,1739502641.3577085,1.7599983215332031,-0.12151260674766835,1739502641.3577106,1.7599983215332031,-0.020030895995679324,1739502641.3577118,1.7599983215332031,0.04406556359172311,1739502641.3577132,1.7599983215332031,0.01566133595438605,1739502641.3577144,1.7599983215332031,2.413404197735044,1739502641.357716,1.7599983215332031,0.0,1739502641.3577175,1.7599983215332031,0.7523029380311894,1739502641.3577187,1.7599983215332031,6.253674769223807,1739502641.3577204,1.7599983215332031,1.6611012597038548 +1739502641.377292,1.7799983024597168,1.4001356780696703,1739502641.3772948,1.7799983024597168,-0.028404985312024067,1739502641.3772979,1.7799983024597168,0.731228953788296,1739502641.377301,1.7799983024597168,6.047714517682896,1739502641.3773022,1.7799983024597168,-0.12151260674766835,1739502641.377304,1.7799983024597168,-0.020030895995679324,1739502641.3773057,1.7799983024597168,0.04406556359172311,1739502641.3773072,1.7799983024597168,0.01566133595438605,1739502641.3773086,1.7799983024597168,2.413404197735044,1739502641.3773103,1.7799983024597168,0.0,1739502641.3773115,1.7799983024597168,0.7523029380311894,1739502641.3773131,1.7799983024597168,6.253674769223807,1739502641.3773146,1.7799983024597168,1.6611012597038548 +1739502641.3976717,1.7999982833862305,1.4001356780696703,1739502641.3976753,1.7999982833862305,-0.028404985312024067,1739502641.397679,1.7999982833862305,0.731228953788296,1739502641.3976827,1.7999982833862305,6.047714517682896,1739502641.3976846,1.7999982833862305,-0.12151260674766835,1739502641.3976867,1.7999982833862305,-0.020030895995679324,1739502641.3976886,1.7999982833862305,0.04406556359172311,1739502641.3976903,1.7999982833862305,0.01566133595438605,1739502641.397692,1.7999982833862305,2.413404197735044,1739502641.3976939,1.7999982833862305,0.0,1739502641.3976958,1.7999982833862305,0.7523029380311894,1739502641.3976974,1.7999982833862305,6.253674769223807,1739502641.3976994,1.7999982833862305,1.6611012597038548 +1739502641.4181209,1.8199982643127441,1.4001356780696703,1739502641.418125,1.8199982643127441,-0.028404985312024067,1739502641.4181297,1.8199982643127441,0.731228953788296,1739502641.418134,1.8199982643127441,6.047714517682896,1739502641.418136,1.8199982643127441,-0.12151260674766835,1739502641.4181383,1.8199982643127441,-0.020030895995679324,1739502641.4181404,1.8199982643127441,0.04406556359172311,1739502641.4181426,1.8199982643127441,0.01566133595438605,1739502641.4181442,1.8199982643127441,2.413404197735044,1739502641.4181466,1.8199982643127441,0.0,1739502641.4181483,1.8199982643127441,0.7523029380311894,1739502641.4181504,1.8199982643127441,6.253674769223807,1739502641.4181523,1.8199982643127441,1.6611012597038548 +1739502641.4382026,1.8399982452392578,1.5867888943064967,1739502641.4382062,1.8399982452392578,-0.03400556592972315,1739502641.4382105,1.8399982452392578,0.7334687923831379,1739502641.4382145,1.8399982452392578,6.212431688643482,1739502641.4382164,1.8399982452392578,-0.123,1739502641.438219,1.8399982452392578,-0.01923699255213611,1739502641.438221,1.8399982452392578,0.05233777000085461,1739502641.4382231,1.8399982452392578,0.018778714182049204,1739502641.4382248,1.8399982452392578,2.3974855865083176,1739502641.4382274,1.8399982452392578,0.0,1739502641.4382293,1.8399982452392578,0.6109781677791652,1739502641.4382312,1.8399982452392578,6.252635464781707,1739502641.4382336,1.8399982452392578,1.742343399069207 +1739502641.4583714,1.8599982261657715,1.5867888943064967,1739502641.4583755,1.8599982261657715,-0.03400556592972315,1739502641.4583802,1.8599982261657715,0.7334687923831379,1739502641.4583852,1.8599982261657715,6.212431688643482,1739502641.4583871,1.8599982261657715,-0.123,1739502641.4583895,1.8599982261657715,-0.01923699255213611,1739502641.4583917,1.8599982261657715,0.05233777000085461,1739502641.4583938,1.8599982261657715,0.018778714182049204,1739502641.4583957,1.8599982261657715,2.3974855865083176,1739502641.4583986,1.8599982261657715,0.0,1739502641.4584002,1.8599982261657715,0.6551421874391106,1739502641.4584026,1.8599982261657715,6.252635464781707,1739502641.4584045,1.8599982261657715,1.742343399069207 +1739502641.4784095,1.8799982070922852,1.5867888943064967,1739502641.478413,1.8799982070922852,-0.03400556592972315,1739502641.4784179,1.8799982070922852,0.7334687923831379,1739502641.478422,1.8799982070922852,6.212431688643482,1739502641.478424,1.8799982070922852,-0.123,1739502641.478427,1.8799982070922852,-0.01923699255213611,1739502641.478429,1.8799982070922852,0.05233777000085461,1739502641.4784312,1.8799982070922852,0.018778714182049204,1739502641.4784336,1.8799982070922852,2.3974855865083176,1739502641.478436,1.8799982070922852,0.0,1739502641.4784384,1.8799982070922852,0.6551421874391106,1739502641.4784408,1.8799982070922852,6.252635464781707,1739502641.4784427,1.8799982070922852,1.742343399069207 +1739502641.4980927,1.8999981880187988,1.5867888943064967,1739502641.4980965,1.8999981880187988,-0.03400556592972315,1739502641.498101,1.8999981880187988,0.7334687923831379,1739502641.498105,1.8999981880187988,6.212431688643482,1739502641.4981074,1.8999981880187988,-0.123,1739502641.49811,1.8999981880187988,-0.01923699255213611,1739502641.4981122,1.8999981880187988,0.05233777000085461,1739502641.4981143,1.8999981880187988,0.018778714182049204,1739502641.4981163,1.8999981880187988,2.3974855865083176,1739502641.4981186,1.8999981880187988,0.0,1739502641.4981208,1.8999981880187988,0.6551421874391106,1739502641.4981227,1.8999981880187988,6.252635464781707,1739502641.4981253,1.8999981880187988,1.742343399069207 +1739502641.5181863,1.9199981689453125,1.5867888943064967,1739502641.51819,1.9199981689453125,-0.03400556592972315,1739502641.5181944,1.9199981689453125,0.7334687923831379,1739502641.5181985,1.9199981689453125,6.212431688643482,1739502641.5182006,1.9199981689453125,-0.123,1739502641.5182028,1.9199981689453125,-0.01923699255213611,1739502641.5182052,1.9199981689453125,0.05233777000085461,1739502641.5182073,1.9199981689453125,0.018778714182049204,1739502641.518209,1.9199981689453125,2.3974855865083176,1739502641.5182118,1.9199981689453125,0.0,1739502641.518214,1.9199981689453125,0.6551421874391106,1739502641.518216,1.9199981689453125,6.252635464781707,1739502641.5182178,1.9199981689453125,1.742343399069207 +1739502641.5389984,1.9399981498718262,1.7819622468259055,1739502641.5390062,1.9399981498718262,-0.04005261744435895,1739502641.5390139,1.9399981498718262,1.0380001494086928,1739502641.5390227,1.9399981498718262,6.660508475842497,1739502641.5390272,1.9399981498718262,-0.125,1739502641.539034,1.9399981498718262,-0.01741067830035398,1739502641.5390394,1.9399981498718262,0.0684701826073158,1739502641.5390449,1.9399981498718262,0.022087285988851978,1739502641.5390503,1.9399981498718262,2.3667426151869067,1739502641.5390558,1.9399981498718262,0.0,1739502641.5390613,1.9399981498718262,0.5060209963558256,1739502641.5390668,1.9399981498718262,6.251741339254254,1739502641.5390723,1.9399981498718262,1.8141212160639495 +1739502641.558917,1.9599981307983398,1.7819622468259055,1739502641.5589225,1.9599981307983398,-0.04005261744435895,1739502641.5589294,1.9599981307983398,1.0380001494086928,1739502641.5589373,1.9599981307983398,6.660508475842497,1739502641.5589416,1.9599981307983398,-0.125,1739502641.5589473,1.9599981307983398,-0.01741067830035398,1739502641.5589786,1.9599981307983398,0.0684701826073158,1739502641.558984,1.9599981307983398,0.022087285988851978,1739502641.5589888,1.9599981307983398,2.3667426151869067,1739502641.5589943,1.9599981307983398,0.0,1739502641.5589993,1.9599981307983398,0.5526213991229572,1739502641.5590043,1.9599981307983398,6.251741339254254,1739502641.5590098,1.9599981307983398,1.8141212160639495 +1739502641.5780814,1.9799981117248535,1.7819622468259055,1739502641.5780857,1.9799981117248535,-0.04005261744435895,1739502641.5780914,1.9799981117248535,1.0380001494086928,1739502641.5780964,1.9799981117248535,6.660508475842497,1739502641.5780993,1.9799981117248535,-0.125,1739502641.578103,1.9799981117248535,-0.01741067830035398,1739502641.5781066,1.9799981117248535,0.0684701826073158,1739502641.5781102,1.9799981117248535,0.022087285988851978,1739502641.5781136,1.9799981117248535,2.3667426151869067,1739502641.5781171,1.9799981117248535,0.0,1739502641.5781205,1.9799981117248535,0.5526213991229572,1739502641.578124,1.9799981117248535,6.251741339254254,1739502641.5781274,1.9799981117248535,1.8141212160639495 +1739502641.5975454,1.9999980926513672,1.7819622468259055,1739502641.5975485,1.9999980926513672,-0.04005261744435895,1739502641.597553,1.9999980926513672,1.0380001494086928,1739502641.5975578,1.9999980926513672,6.660508475842497,1739502641.5975604,1.9999980926513672,-0.125,1739502641.597564,1.9999980926513672,-0.01741067830035398,1739502641.5975673,1.9999980926513672,0.0684701826073158,1739502641.5975704,1.9999980926513672,0.022087285988851978,1739502641.5975733,1.9999980926513672,2.3667426151869067,1739502641.5975773,1.9999980926513672,0.0,1739502641.597581,1.9999980926513672,0.5526213991229572,1739502641.5975838,1.9999980926513672,6.251741339254254,1739502641.5975869,1.9999980926513672,1.8141212160639495 +1739502641.618693,2.019998073577881,1.7819622468259055,1739502641.618697,2.019998073577881,-0.04005261744435895,1739502641.6187015,2.019998073577881,1.0380001494086928,1739502641.618707,2.019998073577881,6.660508475842497,1739502641.6187098,2.019998073577881,-0.125,1739502641.6187134,2.019998073577881,-0.01741067830035398,1739502641.6187167,2.019998073577881,0.0684701826073158,1739502641.6187198,2.019998073577881,0.022087285988851978,1739502641.6187232,2.019998073577881,2.3667426151869067,1739502641.6187265,2.019998073577881,0.0,1739502641.6187298,2.019998073577881,0.5526213991229572,1739502641.6187332,2.019998073577881,6.251741339254254,1739502641.6187363,2.019998073577881,1.8141212160639495 +1739502641.6379106,2.0399980545043945,1.7819622468259055,1739502641.6379144,2.0399980545043945,-0.04005261744435895,1739502641.6379192,2.0399980545043945,1.0380001494086928,1739502641.6379244,2.0399980545043945,6.660508475842497,1739502641.6379275,2.0399980545043945,-0.125,1739502641.637931,2.0399980545043945,-0.01741067830035398,1739502641.6379344,2.0399980545043945,0.0684701826073158,1739502641.6379375,2.0399980545043945,0.022087285988851978,1739502641.637941,2.0399980545043945,2.3667426151869067,1739502641.6379445,2.0399980545043945,0.0,1739502641.6379478,2.0399980545043945,0.5526213991229572,1739502641.6379514,2.0399980545043945,6.251741339254254,1739502641.6379552,2.0399980545043945,1.8141212160639495 +1739502641.657716,2.059998035430908,1.9843566375051767,1739502641.6577196,2.059998035430908,-0.04648733142190942,1739502641.6577244,2.059998035430908,1.0406312764875234,1739502641.6577296,2.059998035430908,6.782341344534461,1739502641.6577322,2.059998035430908,-0.12525532496540798,1739502641.6577358,2.059998035430908,-0.016415416707095287,1739502641.6577399,2.059998035430908,0.07556656657383842,1739502641.6577432,2.059998035430908,0.025202634533404333,1739502641.6577463,2.059998035430908,2.3533444311571627,1739502641.6577501,2.059998035430908,0.0,1739502641.6577532,2.059998035430908,0.4464403364567495,1739502641.6577566,2.059998035430908,6.251021714256675,1739502641.6577601,2.059998035430908,1.8737224908616685 +1739502641.6775732,2.079998016357422,1.9843566375051767,1739502641.6775773,2.079998016357422,-0.04648733142190942,1739502641.6775818,2.079998016357422,1.0406312764875234,1739502641.6775873,2.079998016357422,6.782341344534461,1739502641.6775904,2.079998016357422,-0.12525532496540798,1739502641.6775942,2.079998016357422,-0.016415416707095287,1739502641.677598,2.079998016357422,0.07556656657383842,1739502641.6776016,2.079998016357422,0.025202634533404333,1739502641.677605,2.079998016357422,2.3533444311571627,1739502641.6776085,2.079998016357422,0.0,1739502641.677612,2.079998016357422,0.4796219402954942,1739502641.6776154,2.079998016357422,6.251021714256675,1739502641.677619,2.079998016357422,1.8737224908616685 +1739502641.6978672,2.0999979972839355,1.9843566375051767,1739502641.6978714,2.0999979972839355,-0.04648733142190942,1739502641.697876,2.0999979972839355,1.0406312764875234,1739502641.697881,2.0999979972839355,6.782341344534461,1739502641.697884,2.0999979972839355,-0.12525532496540798,1739502641.6978884,2.0999979972839355,-0.016415416707095287,1739502641.6978915,2.0999979972839355,0.07556656657383842,1739502641.697895,2.0999979972839355,0.025202634533404333,1739502641.6978989,2.0999979972839355,2.3533444311571627,1739502641.6979024,2.0999979972839355,0.0,1739502641.6979058,2.0999979972839355,0.4796219402954942,1739502641.6979094,2.0999979972839355,6.251021714256675,1739502641.6979127,2.0999979972839355,1.8737224908616685 +1739502641.7175357,2.119997978210449,1.9843566375051767,1739502641.7175395,2.119997978210449,-0.04648733142190942,1739502641.7175446,2.119997978210449,1.0406312764875234,1739502641.71755,2.119997978210449,6.782341344534461,1739502641.717553,2.119997978210449,-0.12525532496540798,1739502641.717557,2.119997978210449,-0.016415416707095287,1739502641.717561,2.119997978210449,0.07556656657383842,1739502641.7175655,2.119997978210449,0.025202634533404333,1739502641.7175689,2.119997978210449,2.3533444311571627,1739502641.717573,2.119997978210449,0.0,1739502641.7175763,2.119997978210449,0.4796219402954942,1739502641.7175798,2.119997978210449,6.251021714256675,1739502641.7175834,2.119997978210449,1.8737224908616685 +1739502641.7386713,2.139997959136963,1.9843566375051767,1739502641.7386756,2.139997959136963,-0.04648733142190942,1739502641.7386806,2.139997959136963,1.0406312764875234,1739502641.7386856,2.139997959136963,6.782341344534461,1739502641.7386885,2.139997959136963,-0.12525532496540798,1739502641.7386923,2.139997959136963,-0.016415416707095287,1739502641.7386956,2.139997959136963,0.07556656657383842,1739502641.7386987,2.139997959136963,0.025202634533404333,1739502641.738702,2.139997959136963,2.3533444311571627,1739502641.7387056,2.139997959136963,0.0,1739502641.738709,2.139997959136963,0.4796219402954942,1739502641.7387125,2.139997959136963,6.251021714256675,1739502641.7387161,2.139997959136963,1.8737224908616685 +1739502641.7579775,2.1599979400634766,2.1929984760120886,1739502641.757982,2.1599979400634766,-0.0532618823806601,1739502641.7579873,2.1599979400634766,1.3758485241070102,1739502641.7579925,2.1599979400634766,7.222625225854546,1739502641.7579954,2.1599979400634766,-0.1282141111470747,1739502641.7579992,2.1599979400634766,-0.014901042347882218,1739502641.758003,2.1599979400634766,0.09000926096939052,1739502641.7580063,2.1599979400634766,0.027319230460840747,1739502641.7580097,2.1599979400634766,2.326310004355574,1739502641.7580132,2.1599979400634766,0.0,1739502641.7580168,2.1599979400634766,0.36387586368069386,1739502641.7580204,2.1599979400634766,6.250389483321406,1739502641.7580237,2.1599979400634766,1.926263468017414 +1739502641.7775526,2.1799979209899902,2.1929984760120886,1739502641.7775824,2.1799979209899902,-0.0532618823806601,1739502641.777594,2.1799979209899902,1.3758485241070102,1739502641.7776058,2.1799979209899902,7.222625225854546,1739502641.7776098,2.1799979209899902,-0.1282141111470747,1739502641.7776148,2.1799979209899902,-0.014901042347882218,1739502641.777641,2.1799979209899902,0.09000926096939052,1739502641.7776456,2.1799979209899902,0.027319230460840747,1739502641.7776544,2.1799979209899902,2.326310004355574,1739502641.77766,2.1799979209899902,0.0,1739502641.7776635,2.1799979209899902,0.40004653633816,1739502641.7776673,2.1799979209899902,6.250389483321406,1739502641.7776716,2.1799979209899902,1.926263468017414 +1739502641.7981205,2.199997901916504,2.1929984760120886,1739502641.7981248,2.199997901916504,-0.0532618823806601,1739502641.7981296,2.199997901916504,1.3758485241070102,1739502641.7981353,2.199997901916504,7.222625225854546,1739502641.7981384,2.199997901916504,-0.1282141111470747,1739502641.7981424,2.199997901916504,-0.014901042347882218,1739502641.7981462,2.199997901916504,0.09000926096939052,1739502641.7981503,2.199997901916504,0.027319230460840747,1739502641.7981544,2.199997901916504,2.326310004355574,1739502641.7981584,2.199997901916504,0.0,1739502641.798162,2.199997901916504,0.40004653633816,1739502641.7981658,2.199997901916504,6.250389483321406,1739502641.7981694,2.199997901916504,1.926263468017414 +1739502641.8173776,2.2199978828430176,2.1929984760120886,1739502641.8173804,2.2199978828430176,-0.0532618823806601,1739502641.8173838,2.2199978828430176,1.3758485241070102,1739502641.8173862,2.2199978828430176,7.222625225854546,1739502641.8173878,2.2199978828430176,-0.1282141111470747,1739502641.8173892,2.2199978828430176,-0.014901042347882218,1739502641.817391,2.2199978828430176,0.09000926096939052,1739502641.817392,2.2199978828430176,0.027319230460840747,1739502641.8173938,2.2199978828430176,2.326310004355574,1739502641.8173952,2.2199978828430176,0.0,1739502641.8173966,2.2199978828430176,0.40004653633816,1739502641.817398,2.2199978828430176,6.250389483321406,1739502641.8173995,2.2199978828430176,1.926263468017414 +1739502641.8382213,2.2399978637695312,2.1929984760120886,1739502641.8382258,2.2399978637695312,-0.0532618823806601,1739502641.8382308,2.2399978637695312,1.3758485241070102,1739502641.838236,2.2399978637695312,7.222625225854546,1739502641.8382394,2.2399978637695312,-0.1282141111470747,1739502641.8382435,2.2399978637695312,-0.014901042347882218,1739502641.8382468,2.2399978637695312,0.09000926096939052,1739502641.8382504,2.2399978637695312,0.027319230460840747,1739502641.8382537,2.2399978637695312,2.326310004355574,1739502641.8382576,2.2399978637695312,0.0,1739502641.838261,2.2399978637695312,0.40004653633816,1739502641.8382645,2.2399978637695312,6.250389483321406,1739502641.838268,2.2399978637695312,1.926263468017414 +1739502641.858709,2.259997844696045,2.1929984760120886,1739502641.8587132,2.259997844696045,-0.0532618823806601,1739502641.8587186,2.259997844696045,1.3758485241070102,1739502641.858724,2.259997844696045,7.222625225854546,1739502641.858727,2.259997844696045,-0.1282141111470747,1739502641.8587356,2.259997844696045,-0.014901042347882218,1739502641.858739,2.259997844696045,0.09000926096939052,1739502641.8587425,2.259997844696045,0.027319230460840747,1739502641.8587458,2.259997844696045,2.326310004355574,1739502641.8587496,2.259997844696045,0.0,1739502641.8587532,2.259997844696045,0.40004653633816,1739502641.858757,2.259997844696045,6.250389483321406,1739502641.8587604,2.259997844696045,1.926263468017414 +1739502641.87882,2.2799978256225586,2.406896542279541,1739502641.878824,2.2799978256225586,-0.060333302990514426,1739502641.8788288,2.2799978256225586,1.6398371053586764,1739502641.878834,2.2799978256225586,7.572790814464956,1739502641.8788366,2.2799978256225586,-0.13,1739502641.8788407,2.2799978256225586,-0.013485075456160378,1739502641.878844,2.2799978256225586,0.10257380497732795,1739502641.8788471,2.2799978256225586,0.029513021271564646,1739502641.8788507,2.2799978256225586,2.303043911843407,1739502641.8788548,2.2799978256225586,0.0,1739502641.878858,2.2799978256225586,0.3035243016083874,1739502641.8788617,2.2799978256225586,6.2498447695709025,1739502641.8788655,2.2799978256225586,1.969356392105419 +1739502641.8977647,2.2999978065490723,2.406896542279541,1739502641.8977695,2.2999978065490723,-0.060333302990514426,1739502641.897775,2.2999978065490723,1.6398371053586764,1739502641.8977807,2.2999978065490723,7.572790814464956,1739502641.897784,2.2999978065490723,-0.13,1739502641.8977885,2.2999978065490723,-0.013485075456160378,1739502641.897792,2.2999978065490723,0.10257380497732795,1739502641.897796,2.2999978065490723,0.029513021271564646,1739502641.8977995,2.2999978065490723,2.303043911843407,1739502641.8978035,2.2999978065490723,0.0,1739502641.8978074,2.2999978065490723,0.33368751973798827,1739502641.8978114,2.2999978065490723,6.2498447695709025,1739502641.8978157,2.2999978065490723,1.969356392105419 +1739502641.9173145,2.319997787475586,2.406896542279541,1739502641.917317,2.319997787475586,-0.060333302990514426,1739502641.91732,2.319997787475586,1.6398371053586764,1739502641.9173224,2.319997787475586,7.572790814464956,1739502641.9173238,2.319997787475586,-0.13,1739502641.9173253,2.319997787475586,-0.013485075456160378,1739502641.917327,2.319997787475586,0.10257380497732795,1739502641.9173281,2.319997787475586,0.029513021271564646,1739502641.9173293,2.319997787475586,2.303043911843407,1739502641.917331,2.319997787475586,0.0,1739502641.9173322,2.319997787475586,0.33368751973798827,1739502641.9173336,2.319997787475586,6.2498447695709025,1739502641.917335,2.319997787475586,1.969356392105419 +1739502641.9376972,2.3399977684020996,2.406896542279541,1739502641.9377,2.3399977684020996,-0.060333302990514426,1739502641.9377038,2.3399977684020996,1.6398371053586764,1739502641.9377072,2.3399977684020996,7.572790814464956,1739502641.937709,2.3399977684020996,-0.13,1739502641.9377115,2.3399977684020996,-0.013485075456160378,1739502641.9377131,2.3399977684020996,0.10257380497732795,1739502641.9377146,2.3399977684020996,0.029513021271564646,1739502641.9377162,2.3399977684020996,2.303043911843407,1739502641.9377182,2.3399977684020996,0.0,1739502641.93772,2.3399977684020996,0.33368751973798827,1739502641.937722,2.3399977684020996,6.2498447695709025,1739502641.9377236,2.3399977684020996,1.969356392105419 +1739502641.9578269,2.3599977493286133,2.406896542279541,1739502641.9578297,2.3599977493286133,-0.060333302990514426,1739502641.9578333,2.3599977493286133,1.6398371053586764,1739502641.9578369,2.3599977493286133,7.572790814464956,1739502641.9578385,2.3599977493286133,-0.13,1739502641.957841,2.3599977493286133,-0.013485075456160378,1739502641.9578424,2.3599977493286133,0.10257380497732795,1739502641.9578443,2.3599977493286133,0.029513021271564646,1739502641.957846,2.3599977493286133,2.303043911843407,1739502641.957848,2.3599977493286133,0.0,1739502641.9578497,2.3599977493286133,0.33368751973798827,1739502641.9578524,2.3599977493286133,6.2498447695709025,1739502641.9578543,2.3599977493286133,1.969356392105419 +1739502641.9794347,2.379997730255127,2.625244380468361,1739502641.9794402,2.379997730255127,-0.06766007926476458,1739502641.9794471,2.379997730255127,2.2289482181887315,1739502641.9794538,2.379997730255127,8.235009545887785,1739502641.979456,2.379997730255127,-0.134,1739502641.9794593,2.379997730255127,-0.011825241611083158,1739502641.9794621,2.379997730255127,0.12301280528761413,1739502641.9794657,2.379997730255127,0.03001559498541677,1739502641.9794686,2.379997730255127,2.265692581391648,1739502641.9794724,2.379997730255127,0.0,1739502641.9794753,2.379997730255127,0.22617634161584885,1739502641.9794796,2.379997730255127,6.249431507155699,1739502641.979483,2.379997730255127,2.005918974584547 +1739502641.999192,2.3999977111816406,2.625244380468361,1739502641.9991972,2.3999977111816406,-0.06766007926476458,1739502641.999204,2.3999977111816406,2.2289482181887315,1739502641.999209,2.3999977111816406,8.235009545887785,1739502641.9992115,2.3999977111816406,-0.134,1739502641.9992151,2.3999977111816406,-0.011825241611083158,1739502641.999219,2.3999977111816406,0.12301280528761413,1739502641.9992218,2.3999977111816406,0.03001559498541677,1739502641.9992247,2.3999977111816406,2.265692581391648,1739502641.9992273,2.3999977111816406,0.0,1739502641.9992309,2.3999977111816406,0.25977360680710104,1739502641.9992354,2.3999977111816406,6.249431507155699,1739502641.9992383,2.3999977111816406,2.005918974584547 +1739502642.018279,2.4199976921081543,2.625244380468361,1739502642.0182836,2.4199976921081543,-0.06766007926476458,1739502642.0182881,2.4199976921081543,2.2289482181887315,1739502642.0182922,2.4199976921081543,8.235009545887785,1739502642.018294,2.4199976921081543,-0.134,1739502642.0182965,2.4199976921081543,-0.011825241611083158,1739502642.0182984,2.4199976921081543,0.12301280528761413,1739502642.0183008,2.4199976921081543,0.03001559498541677,1739502642.0183024,2.4199976921081543,2.265692581391648,1739502642.018305,2.4199976921081543,0.0,1739502642.018307,2.4199976921081543,0.25977360680710104,1739502642.018309,2.4199976921081543,6.249431507155699,1739502642.018311,2.4199976921081543,2.005918974584547 +1739502642.038551,2.439997673034668,2.625244380468361,1739502642.0385575,2.439997673034668,-0.06766007926476458,1739502642.0385656,2.439997673034668,2.2289482181887315,1739502642.0385728,2.439997673034668,8.235009545887785,1739502642.038577,2.439997673034668,-0.134,1739502642.0385826,2.439997673034668,-0.011825241611083158,1739502642.0385878,2.439997673034668,0.12301280528761413,1739502642.0385933,2.439997673034668,0.03001559498541677,1739502642.038598,2.439997673034668,2.265692581391648,1739502642.0386035,2.439997673034668,0.0,1739502642.0386083,2.439997673034668,0.25977360680710104,1739502642.0386138,2.439997673034668,6.249431507155699,1739502642.0386186,2.439997673034668,2.005918974584547 +1739502642.059271,2.4599976539611816,2.625244380468361,1739502642.0592763,2.4599976539611816,-0.06766007926476458,1739502642.0592847,2.4599976539611816,2.2289482181887315,1739502642.0592902,2.4599976539611816,8.235009545887785,1739502642.0592933,2.4599976539611816,-0.134,1739502642.0592973,2.4599976539611816,-0.011825241611083158,1739502642.0593002,2.4599976539611816,0.12301280528761413,1739502642.0593038,2.4599976539611816,0.03001559498541677,1739502642.0593061,2.4599976539611816,2.265692581391648,1739502642.0593102,2.4599976539611816,0.0,1739502642.0593128,2.4599976539611816,0.25977360680710104,1739502642.059316,2.4599976539611816,6.249431507155699,1739502642.0593197,2.4599976539611816,2.005918974584547 +1739502642.0791233,2.4799976348876953,2.625244380468361,1739502642.0791287,2.4799976348876953,-0.06766007926476458,1739502642.079136,2.4799976348876953,2.2289482181887315,1739502642.0791438,2.4799976348876953,8.235009545887785,1739502642.0791478,2.4799976348876953,-0.134,1739502642.0791533,2.4799976348876953,-0.011825241611083158,1739502642.079158,2.4799976348876953,0.12301280528761413,1739502642.0791626,2.4799976348876953,0.03001559498541677,1739502642.0791671,2.4799976348876953,2.265692581391648,1739502642.0791724,2.4799976348876953,0.0,1739502642.0791774,2.4799976348876953,0.25977360680710104,1739502642.0791824,2.4799976348876953,6.249431507155699,1739502642.0791872,2.4799976348876953,2.005918974584547 +1739502642.0986555,2.499997615814209,2.8471290213236937,1739502642.098661,2.499997615814209,-0.07519051146022626,1739502642.098666,2.499997615814209,2.6679107539493265,1739502642.0986717,2.499997615814209,8.729524158516725,1739502642.0986745,2.499997615814209,-0.13576909583506344,1739502642.0986779,2.499997615814209,-0.010297921433491425,1739502642.0986805,2.499997615814209,0.1401870764524467,1739502642.098685,2.499997615814209,0.031109940932051987,1739502642.0986893,2.499997615814209,2.2347761595251194,1739502642.098693,2.499997615814209,0.0,1739502642.0986955,2.499997615814209,0.17439662854238774,1739502642.0986981,2.499997615814209,6.249054761261585,1739502642.0987008,2.499997615814209,2.0336992077820257 +1739502642.118117,2.5199975967407227,2.8471290213236937,1739502642.118126,2.5199975967407227,-0.07519051146022626,1739502642.1181343,2.5199975967407227,2.6679107539493265,1739502642.1181388,2.5199975967407227,8.729524158516725,1739502642.1181407,2.5199975967407227,-0.13576909583506344,1739502642.1181438,2.5199975967407227,-0.010297921433491425,1739502642.1181457,2.5199975967407227,0.1401870764524467,1739502642.1181476,2.5199975967407227,0.031109940932051987,1739502642.1181493,2.5199975967407227,2.2347761595251194,1739502642.118152,2.5199975967407227,0.0,1739502642.1181538,2.5199975967407227,0.2010769517430937,1739502642.118156,2.5199975967407227,6.249054761261585,1739502642.118158,2.5199975967407227,2.0336992077820257 +1739502642.138277,2.5399975776672363,2.8471290213236937,1739502642.1382828,2.5399975776672363,-0.07519051146022626,1739502642.1382916,2.5399975776672363,2.6679107539493265,1739502642.1383016,2.5399975776672363,8.729524158516725,1739502642.138306,2.5399975776672363,-0.13576909583506344,1739502642.1383135,2.5399975776672363,-0.010297921433491425,1739502642.1383216,2.5399975776672363,0.1401870764524467,1739502642.1383276,2.5399975776672363,0.031109940932051987,1739502642.1383338,2.5399975776672363,2.2347761595251194,1739502642.1383388,2.5399975776672363,0.0,1739502642.138346,2.5399975776672363,0.2010769517430937,1739502642.1383536,2.5399975776672363,6.249054761261585,1739502642.1383593,2.5399975776672363,2.0336992077820257 +1739502642.1590302,2.55999755859375,2.8471290213236937,1739502642.159036,2.55999755859375,-0.07519051146022626,1739502642.1590426,2.55999755859375,2.6679107539493265,1739502642.1590486,2.55999755859375,8.729524158516725,1739502642.1590512,2.55999755859375,-0.13576909583506344,1739502642.1590555,2.55999755859375,-0.010297921433491425,1739502642.1590586,2.55999755859375,0.1401870764524467,1739502642.159062,2.55999755859375,0.031109940932051987,1739502642.1590645,2.55999755859375,2.2347761595251194,1739502642.1590703,2.55999755859375,0.0,1739502642.1590755,2.55999755859375,0.2010769517430937,1739502642.1590786,2.55999755859375,6.249054761261585,1739502642.1590817,2.55999755859375,2.0336992077820257 +1739502642.1800742,2.5799975395202637,2.8471290213236937,1739502642.180083,2.5799975395202637,-0.07519051146022626,1739502642.1800938,2.5799975395202637,2.6679107539493265,1739502642.1801045,2.5799975395202637,8.729524158516725,1739502642.1801105,2.5799975395202637,-0.13576909583506344,1739502642.1801178,2.5799975395202637,-0.010297921433491425,1739502642.1801217,2.5799975395202637,0.1401870764524467,1739502642.180124,2.5799975395202637,0.031109940932051987,1739502642.1801264,2.5799975395202637,2.2347761595251194,1739502642.1801288,2.5799975395202637,0.0,1739502642.180131,2.5799975395202637,0.2010769517430937,1739502642.1801333,2.5799975395202637,6.249054761261585,1739502642.1801357,2.5799975395202637,2.0336992077820257 +1739502642.19931,2.5999975204467773,3.071817351510738,1739502642.199316,2.5999975204467773,-0.08290082304367452,1739502642.199323,2.5999975204467773,2.5949566058880973,1739502642.1993299,2.5999975204467773,8.700662446149138,1739502642.1993332,2.5999975204467773,-0.13549681552970885,1739502642.1993377,2.5999975204467773,-0.009343739426761486,1739502642.1993413,2.5999975204467773,0.14163297347471748,1739502642.1993449,2.5999975204467773,0.03432654775068447,1739502642.1993484,2.5999975204467773,2.2321926490536197,1739502642.1993527,2.5999975204467773,0.0,1739502642.199357,2.5999975204467773,0.1652528157400034,1739502642.199361,2.5999975204467773,6.248678015367473,1739502642.199365,2.5999975204467773,2.055744783472604 +1739502642.2186303,2.619997501373291,3.071817351510738,1739502642.2186363,2.619997501373291,-0.08290082304367452,1739502642.2186437,2.619997501373291,2.5949566058880973,1739502642.2186525,2.619997501373291,8.700662446149138,1739502642.2186568,2.619997501373291,-0.13549681552970885,1739502642.2186627,2.619997501373291,-0.009343739426761486,1739502642.218668,2.619997501373291,0.14163297347471748,1739502642.2186732,2.619997501373291,0.03432654775068447,1739502642.2186785,2.619997501373291,2.2321926490536197,1739502642.2186842,2.619997501373291,0.0,1739502642.2186892,2.619997501373291,0.17644786558101577,1739502642.218695,2.619997501373291,6.248678015367473,1739502642.2187006,2.619997501373291,2.055744783472604 +1739502642.2381313,2.6399974822998047,3.071817351510738,1739502642.2381356,2.6399974822998047,-0.08290082304367452,1739502642.2381423,2.6399974822998047,2.5949566058880973,1739502642.2381477,2.6399974822998047,8.700662446149138,1739502642.2381496,2.6399974822998047,-0.13549681552970885,1739502642.2381525,2.6399974822998047,-0.009343739426761486,1739502642.2381546,2.6399974822998047,0.14163297347471748,1739502642.2381573,2.6399974822998047,0.03432654775068447,1739502642.2381594,2.6399974822998047,2.2321926490536197,1739502642.2381618,2.6399974822998047,0.0,1739502642.238164,2.6399974822998047,0.17644786558101577,1739502642.2381666,2.6399974822998047,6.248678015367473,1739502642.2381692,2.6399974822998047,2.055744783472604 +1739502642.257706,2.6599974632263184,3.071817351510738,1739502642.25771,2.6599974632263184,-0.08290082304367452,1739502642.2577152,2.6599974632263184,2.5949566058880973,1739502642.2577205,2.6599974632263184,8.700662446149138,1739502642.2577224,2.6599974632263184,-0.13549681552970885,1739502642.2577271,2.6599974632263184,-0.009343739426761486,1739502642.257732,2.6599974632263184,0.14163297347471748,1739502642.2577357,2.6599974632263184,0.03432654775068447,1739502642.2577405,2.6599974632263184,2.2321926490536197,1739502642.2577438,2.6599974632263184,0.0,1739502642.257749,2.6599974632263184,0.17644786558101577,1739502642.2577517,2.6599974632263184,6.248678015367473,1739502642.2577538,2.6599974632263184,2.055744783472604 +1739502642.2774138,2.679997444152832,3.071817351510738,1739502642.2774165,2.679997444152832,-0.08290082304367452,1739502642.2774198,2.679997444152832,2.5949566058880973,1739502642.2774231,2.679997444152832,8.700662446149138,1739502642.2774246,2.679997444152832,-0.13549681552970885,1739502642.2774265,2.679997444152832,-0.009343739426761486,1739502642.2774282,2.679997444152832,0.14163297347471748,1739502642.2774298,2.679997444152832,0.03432654775068447,1739502642.2774312,2.679997444152832,2.2321926490536197,1739502642.2774332,2.679997444152832,0.0,1739502642.2774346,2.679997444152832,0.17644786558101577,1739502642.2774365,2.679997444152832,6.248678015367473,1739502642.2774382,2.679997444152832,2.055744783472604 +1739502642.2975032,2.6999974250793457,3.071817351510738,1739502642.297508,2.6999974250793457,-0.08290082304367452,1739502642.297514,2.6999974250793457,2.5949566058880973,1739502642.2975209,2.6999974250793457,8.700662446149138,1739502642.2975247,2.6999974250793457,-0.13549681552970885,1739502642.2975297,2.6999974250793457,-0.009343739426761486,1739502642.2975345,2.6999974250793457,0.14163297347471748,1739502642.2975388,2.6999974250793457,0.03432654775068447,1739502642.297543,2.6999974250793457,2.2321926490536197,1739502642.2975478,2.6999974250793457,0.0,1739502642.2975523,2.6999974250793457,0.17644786558101577,1739502642.2975566,2.6999974250793457,6.248678015367473,1739502642.2975612,2.6999974250793457,2.055744783472604 +1739502642.3179634,2.7199974060058594,3.298759796063872,1739502642.317969,2.7199974060058594,-0.09076179914124971,1739502642.317974,2.7199974060058594,2.6228862485203286,1739502642.3179812,2.7199974060058594,8.766787710735594,1739502642.3179848,2.7199974060058594,-0.136,1739502642.3179886,2.7199974060058594,-0.008273031791304127,1739502642.3179936,2.7199974060058594,0.1447369313893771,1739502642.3179982,2.7199974060058594,0.03717296326576365,1739502642.318,2.7199974060058594,2.226656619707051,1739502642.3180022,2.7199974060058594,0.0,1739502642.3180053,2.7199974060058594,0.14061508827931524,1739502642.31801,2.7199974060058594,6.248440412834193,1739502642.318014,2.7199974060058594,2.0748437811791374 +1739502642.338179,2.739997386932373,3.298759796063872,1739502642.3381834,2.739997386932373,-0.09076179914124971,1739502642.3381898,2.739997386932373,2.6228862485203286,1739502642.3381965,2.739997386932373,8.766787710735594,1739502642.3381999,2.739997386932373,-0.136,1739502642.3382044,2.739997386932373,-0.008273031791304127,1739502642.3382082,2.739997386932373,0.1447369313893771,1739502642.338212,2.739997386932373,0.03717296326576365,1739502642.3382163,2.739997386932373,2.226656619707051,1739502642.3382204,2.739997386932373,0.0,1739502642.3382246,2.739997386932373,0.15181283852791383,1739502642.3382287,2.739997386932373,6.248440412834193,1739502642.3382328,2.739997386932373,2.0748437811791374 +1739502642.3583665,2.7599973678588867,3.298759796063872,1739502642.3583727,2.7599973678588867,-0.09076179914124971,1739502642.3583791,2.7599973678588867,2.6228862485203286,1739502642.3583858,2.7599973678588867,8.766787710735594,1739502642.3583908,2.7599973678588867,-0.136,1739502642.358396,2.7599973678588867,-0.008273031791304127,1739502642.3584003,2.7599973678588867,0.1447369313893771,1739502642.3584042,2.7599973678588867,0.03717296326576365,1739502642.358408,2.7599973678588867,2.226656619707051,1739502642.3584123,2.7599973678588867,0.0,1739502642.3584163,2.7599973678588867,0.15181283852791383,1739502642.3584201,2.7599973678588867,6.248440412834193,1739502642.3584244,2.7599973678588867,2.0748437811791374 +1739502642.378401,2.7799973487854004,3.298759796063872,1739502642.3784068,2.7799973487854004,-0.09076179914124971,1739502642.3784125,2.7799973487854004,2.6228862485203286,1739502642.3784187,2.7799973487854004,8.766787710735594,1739502642.378422,2.7799973487854004,-0.136,1739502642.3784263,2.7799973487854004,-0.008273031791304127,1739502642.3784304,2.7799973487854004,0.1447369313893771,1739502642.3784344,2.7799973487854004,0.03717296326576365,1739502642.3784382,2.7799973487854004,2.226656619707051,1739502642.3784428,2.7799973487854004,0.0,1739502642.3784468,2.7799973487854004,0.15181283852791383,1739502642.378451,2.7799973487854004,6.248440412834193,1739502642.3784554,2.7799973487854004,2.0748437811791374 +1739502642.3974247,2.799997329711914,3.298759796063872,1739502642.397427,2.799997329711914,-0.09076179914124971,1739502642.3974304,2.799997329711914,2.6228862485203286,1739502642.3974338,2.799997329711914,8.766787710735594,1739502642.3974354,2.799997329711914,-0.136,1739502642.3974373,2.799997329711914,-0.008273031791304127,1739502642.397439,2.799997329711914,0.1447369313893771,1739502642.3974404,2.799997329711914,0.03717296326576365,1739502642.397442,2.799997329711914,2.226656619707051,1739502642.3974438,2.799997329711914,0.0,1739502642.3974454,2.799997329711914,0.15181283852791383,1739502642.3974469,2.799997329711914,6.248440412834193,1739502642.3974488,2.799997329711914,2.0748437811791374 +1739502642.4178526,2.8199973106384277,3.527690424979127,1739502642.417857,2.8199973106384277,-0.09873186824256219,1739502642.4178624,2.8199973106384277,3.2871393388811057,1739502642.4178686,2.8199973106384277,9.464286082569544,1739502642.4178717,2.8199973106384277,-0.1386322785423106,1739502642.4178762,2.8199973106384277,-0.006720991593349242,1739502642.4178803,2.8199973106384277,0.16688819913508746,1739502642.417884,2.8199973106384277,0.03636394730018068,1739502642.417888,2.8199973106384277,2.1875455733544604,1739502642.417892,2.8199973106384277,0.0,1739502642.417896,2.8199973106384277,0.07073821198376691,1739502642.4178998,2.8199973106384277,6.248349478909339,1739502642.417904,2.8199973106384277,2.091471523964178 +1739502642.4381104,2.8399972915649414,3.527690424979127,1739502642.4381144,2.8399972915649414,-0.09873186824256219,1739502642.4381182,2.8399972915649414,3.2871393388811057,1739502642.4381218,2.8399972915649414,9.464286082569544,1739502642.4381235,2.8399972915649414,-0.1386322785423106,1739502642.4381258,2.8399972915649414,-0.006720991593349242,1739502642.4381275,2.8399972915649414,0.16688819913508746,1739502642.4381292,2.8399972915649414,0.03636394730018068,1739502642.4381306,2.8399972915649414,2.1875455733544604,1739502642.4381328,2.8399972915649414,0.0,1739502642.4381342,2.8399972915649414,0.0960740493902823,1739502642.438136,2.8399972915649414,6.248349478909339,1739502642.4381375,2.8399972915649414,2.091471523964178 +1739502642.4577942,2.859997272491455,3.527690424979127,1739502642.4577973,2.859997272491455,-0.09873186824256219,1739502642.4578006,2.859997272491455,3.2871393388811057,1739502642.4578037,2.859997272491455,9.464286082569544,1739502642.4578054,2.859997272491455,-0.1386322785423106,1739502642.4578075,2.859997272491455,-0.006720991593349242,1739502642.4578092,2.859997272491455,0.16688819913508746,1739502642.4578106,2.859997272491455,0.03636394730018068,1739502642.457812,2.859997272491455,2.1875455733544604,1739502642.4578137,2.859997272491455,0.0,1739502642.4578156,2.859997272491455,0.0960740493902823,1739502642.4578176,2.859997272491455,6.248349478909339,1739502642.4578195,2.859997272491455,2.091471523964178 +1739502642.4775162,2.8799972534179688,3.527690424979127,1739502642.4775188,2.8799972534179688,-0.09873186824256219,1739502642.477522,2.8799972534179688,3.2871393388811057,1739502642.477525,2.8799972534179688,9.464286082569544,1739502642.4775264,2.8799972534179688,-0.1386322785423106,1739502642.4775286,2.8799972534179688,-0.006720991593349242,1739502642.47753,2.8799972534179688,0.16688819913508746,1739502642.4775317,2.8799972534179688,0.03636394730018068,1739502642.4775329,2.8799972534179688,2.1875455733544604,1739502642.4775352,2.8799972534179688,0.0,1739502642.4775367,2.8799972534179688,0.0960740493902823,1739502642.4775386,2.8799972534179688,6.248349478909339,1739502642.47754,2.8799972534179688,2.091471523964178 +1739502642.4977021,2.8999972343444824,3.527690424979127,1739502642.497705,2.8999972343444824,-0.09873186824256219,1739502642.4977086,2.8999972343444824,3.2871393388811057,1739502642.4977117,2.8999972343444824,9.464286082569544,1739502642.497713,2.8999972343444824,-0.1386322785423106,1739502642.497715,2.8999972343444824,-0.006720991593349242,1739502642.4977167,2.8999972343444824,0.16688819913508746,1739502642.4977183,2.8999972343444824,0.03636394730018068,1739502642.4977198,2.8999972343444824,2.1875455733544604,1739502642.4977217,2.8999972343444824,0.0,1739502642.497723,2.8999972343444824,0.0960740493902823,1739502642.4977248,2.8999972343444824,6.248349478909339,1739502642.4977264,2.8999972343444824,2.091471523964178 +1739502642.5174901,2.919997215270996,3.527690424979127,1739502642.5174928,2.919997215270996,-0.09873186824256219,1739502642.5174966,2.919997215270996,3.2871393388811057,1739502642.5175,2.919997215270996,9.464286082569544,1739502642.5175014,2.919997215270996,-0.1386322785423106,1739502642.517504,2.919997215270996,-0.006720991593349242,1739502642.517506,2.919997215270996,0.16688819913508746,1739502642.5175073,2.919997215270996,0.03636394730018068,1739502642.5175087,2.919997215270996,2.1875455733544604,1739502642.517511,2.919997215270996,0.0,1739502642.5175128,2.919997215270996,0.0960740493902823,1739502642.5175142,2.919997215270996,6.248349478909339,1739502642.5175164,2.919997215270996,2.091471523964178 +1739502642.5377643,2.9399971961975098,3.758091227316167,1739502642.5377698,2.9399971961975098,-0.10676701352363693,1739502642.537775,2.9399971961975098,3.3074306797773274,1739502642.5377784,2.9399971961975098,9.504610518949184,1739502642.53778,2.9399971961975098,-0.13900560109127694,1739502642.5377817,2.9399971961975098,-0.005610048051648453,1739502642.5377839,2.9399971961975098,0.1682369104101732,1739502642.5377853,2.9399971961975098,0.03912320962592891,1739502642.5377867,2.9399971961975098,2.185186552334981,1739502642.5377884,2.9399971961975098,0.0,1739502642.53779,2.9399971961975098,0.07807195995790508,1739502642.5377915,2.9399971961975098,6.248295221020758,1739502642.5377934,2.9399971961975098,2.1014889357409903 +1739502642.5577612,2.9599971771240234,3.758091227316167,1739502642.5577638,2.9599971771240234,-0.10676701352363693,1739502642.5577674,2.9599971771240234,3.3074306797773274,1739502642.5577705,2.9599971771240234,9.504610518949184,1739502642.557772,2.9599971771240234,-0.13900560109127694,1739502642.557774,2.9599971771240234,-0.005610048051648453,1739502642.5577755,2.9599971771240234,0.1682369104101732,1739502642.5577772,2.9599971771240234,0.03912320962592891,1739502642.5577784,2.9599971771240234,2.185186552334981,1739502642.5577805,2.9599971771240234,0.0,1739502642.557782,2.9599971771240234,0.08369761659399089,1739502642.5577838,2.9599971771240234,6.248295221020758,1739502642.5577853,2.9599971771240234,2.1014889357409903 +1739502642.5777705,2.979997158050537,3.758091227316167,1739502642.5777736,2.979997158050537,-0.10676701352363693,1739502642.5777798,2.979997158050537,3.3074306797773274,1739502642.5777874,2.979997158050537,9.504610518949184,1739502642.5777917,2.979997158050537,-0.13900560109127694,1739502642.577796,2.979997158050537,-0.005610048051648453,1739502642.5777977,2.979997158050537,0.1682369104101732,1739502642.5777993,2.979997158050537,0.03912320962592891,1739502642.577801,2.979997158050537,2.185186552334981,1739502642.5778024,2.979997158050537,0.0,1739502642.577804,2.979997158050537,0.08369761659399089,1739502642.5778058,2.979997158050537,6.248295221020758,1739502642.5778074,2.979997158050537,2.1014889357409903 +1739502642.597618,2.999997138977051,3.758091227316167,1739502642.597621,2.999997138977051,-0.10676701352363693,1739502642.597624,2.999997138977051,3.3074306797773274,1739502642.5976272,2.999997138977051,9.504610518949184,1739502642.5976286,2.999997138977051,-0.13900560109127694,1739502642.597631,2.999997138977051,-0.005610048051648453,1739502642.5976324,2.999997138977051,0.1682369104101732,1739502642.597636,2.999997138977051,0.03912320962592891,1739502642.597641,2.999997138977051,2.185186552334981,1739502642.597646,2.999997138977051,0.0,1739502642.597651,2.999997138977051,0.08369761659399089,1739502642.5976553,2.999997138977051,6.248295221020758,1739502642.5976567,2.999997138977051,2.1014889357409903 +1739502642.6177452,3.0199971199035645,3.758091227316167,1739502642.6177478,3.0199971199035645,-0.10676701352363693,1739502642.6177511,3.0199971199035645,3.3074306797773274,1739502642.6177542,3.0199971199035645,9.504610518949184,1739502642.6177557,3.0199971199035645,-0.13900560109127694,1739502642.6177578,3.0199971199035645,-0.005610048051648453,1739502642.6177592,3.0199971199035645,0.1682369104101732,1739502642.6177611,3.0199971199035645,0.03912320962592891,1739502642.6177626,3.0199971199035645,2.185186552334981,1739502642.6177642,3.0199971199035645,0.0,1739502642.617766,3.0199971199035645,0.08369761659399089,1739502642.6177673,3.0199971199035645,6.248295221020758,1739502642.617769,3.0199971199035645,2.1014889357409903 +1739502642.638052,3.039997100830078,3.989574984388282,1739502642.638055,3.039997100830078,-0.11484692510284766,1739502642.6380582,3.039997100830078,3.3278174102228317,1739502642.6380613,3.039997100830078,9.543328285022039,1739502642.638063,3.039997100830078,-0.13936080995433064,1739502642.6380649,3.039997100830078,-0.004413902513627268,1739502642.638067,3.039997100830078,0.1691669635253729,1739502642.6380684,3.039997100830078,0.04211789032864445,1739502642.6380699,3.039997100830078,2.1835612853955584,1739502642.6380715,3.039997100830078,0.0,1739502642.6380732,3.039997100830078,0.06800074001023133,1739502642.6380749,3.039997100830078,6.248307054577268,1739502642.6380763,3.039997100830078,2.110655268236752 +1739502642.65793,3.059997081756592,3.989574984388282,1739502642.6579328,3.059997081756592,-0.11484692510284766,1739502642.657936,3.059997081756592,3.3278174102228317,1739502642.6579392,3.059997081756592,9.543328285022039,1739502642.6579406,3.059997081756592,-0.13936080995433064,1739502642.6579428,3.059997081756592,-0.004413902513627268,1739502642.6579442,3.059997081756592,0.1691669635253729,1739502642.6579459,3.059997081756592,0.04211789032864445,1739502642.6579473,3.059997081756592,2.1835612853955584,1739502642.6579492,3.059997081756592,0.0,1739502642.6579506,3.059997081756592,0.07290601715880651,1739502642.6579525,3.059997081756592,6.248307054577268,1739502642.657954,3.059997081756592,2.110655268236752 +1739502642.6778219,3.0799970626831055,3.989574984388282,1739502642.6778247,3.0799970626831055,-0.11484692510284766,1739502642.677828,3.0799970626831055,3.3278174102228317,1739502642.6778312,3.0799970626831055,9.543328285022039,1739502642.6778324,3.0799970626831055,-0.13936080995433064,1739502642.6778343,3.0799970626831055,-0.004413902513627268,1739502642.6778357,3.0799970626831055,0.1691669635253729,1739502642.6778374,3.0799970626831055,0.04211789032864445,1739502642.6778388,3.0799970626831055,2.1835612853955584,1739502642.677841,3.0799970626831055,0.0,1739502642.6778424,3.0799970626831055,0.07290601715880651,1739502642.677844,3.0799970626831055,6.248307054577268,1739502642.6778455,3.0799970626831055,2.110655268236752 +1739502642.6977174,3.099997043609619,3.989574984388282,1739502642.69772,3.099997043609619,-0.11484692510284766,1739502642.6977234,3.099997043609619,3.3278174102228317,1739502642.6977262,3.099997043609619,9.543328285022039,1739502642.697728,3.099997043609619,-0.13936080995433064,1739502642.6977298,3.099997043609619,-0.004413902513627268,1739502642.6977313,3.099997043609619,0.1691669635253729,1739502642.6977332,3.099997043609619,0.04211789032864445,1739502642.6977344,3.099997043609619,2.1835612853955584,1739502642.6977365,3.099997043609619,0.0,1739502642.697738,3.099997043609619,0.07290601715880651,1739502642.6977396,3.099997043609619,6.248307054577268,1739502642.697741,3.099997043609619,2.110655268236752 +1739502642.717907,3.119997024536133,3.989574984388282,1739502642.7179098,3.119997024536133,-0.11484692510284766,1739502642.7179132,3.119997024536133,3.3278174102228317,1739502642.7179163,3.119997024536133,9.543328285022039,1739502642.7179174,3.119997024536133,-0.13936080995433064,1739502642.7179196,3.119997024536133,-0.004413902513627268,1739502642.717921,3.119997024536133,0.1691669635253729,1739502642.7179224,3.119997024536133,0.04211789032864445,1739502642.7179239,3.119997024536133,2.1835612853955584,1739502642.7179255,3.119997024536133,0.0,1739502642.717927,3.119997024536133,0.07290601715880651,1739502642.717929,3.119997024536133,6.248307054577268,1739502642.7179306,3.119997024536133,2.110655268236752 +1739502642.7377791,3.1399970054626465,3.989574984388282,1739502642.737783,3.1399970054626465,-0.11484692510284766,1739502642.7377865,3.1399970054626465,3.3278174102228317,1739502642.7377903,3.1399970054626465,9.543328285022039,1739502642.7377923,3.1399970054626465,-0.13936080995433064,1739502642.7377944,3.1399970054626465,-0.004413902513627268,1739502642.7377963,3.1399970054626465,0.1691669635253729,1739502642.7377982,3.1399970054626465,0.04211789032864445,1739502642.7378004,3.1399970054626465,2.1835612853955584,1739502642.737803,3.1399970054626465,0.0,1739502642.7378056,3.1399970054626465,0.07290601715880651,1739502642.737808,3.1399970054626465,6.248307054577268,1739502642.73781,3.1399970054626465,2.110655268236752 +1739502642.7578895,3.15999698638916,4.221996556602605,1739502642.7578924,3.15999698638916,-0.12294685641402303,1739502642.7578957,3.15999698638916,3.3482867084403147,1739502642.7578988,3.15999698638916,9.579567096348208,1739502642.7579,3.15999698638916,-0.13969327611328633,1739502642.7579021,3.15999698638916,-0.003125738622783602,1739502642.7579038,3.15999698638916,0.1695526378867835,1739502642.7579052,3.15999698638916,0.045362045723926055,1739502642.7579067,3.15999698638916,2.1828876744352166,1739502642.7579088,3.15999698638916,0.0,1739502642.7579103,3.15999698638916,0.06045636976022529,1739502642.757912,3.15999698638916,6.248407138913457,1739502642.7579136,3.15999698638916,2.1185407873121127 +1739502642.777518,3.179996967315674,4.221996556602605,1739502642.777521,3.179996967315674,-0.12294685641402303,1739502642.7775242,3.179996967315674,3.3482867084403147,1739502642.777527,3.179996967315674,9.579567096348208,1739502642.7775285,3.179996967315674,-0.13969327611328633,1739502642.7775307,3.179996967315674,-0.003125738622783602,1739502642.777532,3.179996967315674,0.1695526378867835,1739502642.7775338,3.179996967315674,0.045362045723926055,1739502642.7775352,3.179996967315674,2.1828876744352166,1739502642.777537,3.179996967315674,0.0,1739502642.7775388,3.179996967315674,0.06434688712310388,1739502642.7775404,3.179996967315674,6.248407138913457,1739502642.777542,3.179996967315674,2.1185407873121127 +1739502642.7977316,3.1999969482421875,4.221996556602605,1739502642.7977345,3.1999969482421875,-0.12294685641402303,1739502642.7977378,3.1999969482421875,3.3482867084403147,1739502642.7977407,3.1999969482421875,9.579567096348208,1739502642.7977424,3.1999969482421875,-0.13969327611328633,1739502642.797744,3.1999969482421875,-0.003125738622783602,1739502642.7977457,3.1999969482421875,0.1695526378867835,1739502642.7977471,3.1999969482421875,0.045362045723926055,1739502642.7977488,3.1999969482421875,2.1828876744352166,1739502642.7977505,3.1999969482421875,0.0,1739502642.7977521,3.1999969482421875,0.06434688712310388,1739502642.7977538,3.1999969482421875,6.248407138913457,1739502642.7977555,3.1999969482421875,2.1185407873121127 +1739502642.8179286,3.219996929168701,4.221996556602605,1739502642.8179314,3.219996929168701,-0.12294685641402303,1739502642.817935,3.219996929168701,3.3482867084403147,1739502642.817938,3.219996929168701,9.579567096348208,1739502642.81794,3.219996929168701,-0.13969327611328633,1739502642.817942,3.219996929168701,-0.003125738622783602,1739502642.8179436,3.219996929168701,0.1695526378867835,1739502642.817945,3.219996929168701,0.045362045723926055,1739502642.8179467,3.219996929168701,2.1828876744352166,1739502642.8179483,3.219996929168701,0.0,1739502642.81795,3.219996929168701,0.06434688712310388,1739502642.8179514,3.219996929168701,6.248407138913457,1739502642.8179533,3.219996929168701,2.1185407873121127 +1739502642.8376415,3.239996910095215,4.221996556602605,1739502642.8376443,3.239996910095215,-0.12294685641402303,1739502642.8376477,3.239996910095215,3.3482867084403147,1739502642.8376508,3.239996910095215,9.579567096348208,1739502642.837652,3.239996910095215,-0.13969327611328633,1739502642.837654,3.239996910095215,-0.003125738622783602,1739502642.8376555,3.239996910095215,0.1695526378867835,1739502642.8376575,3.239996910095215,0.045362045723926055,1739502642.837659,3.239996910095215,2.1828876744352166,1739502642.837661,3.239996910095215,0.0,1739502642.8376625,3.239996910095215,0.06434688712310388,1739502642.837664,3.239996910095215,6.248407138913457,1739502642.8376658,3.239996910095215,2.1185407873121127 +1739502642.8579195,3.2599968910217285,4.455249790099751,1739502642.8579223,3.2599968910217285,-0.13104081377911925,1739502642.8579257,3.2599968910217285,3.693490903828139,1739502642.857929,3.2599968910217285,9.938845801720971,1739502642.8579302,3.2599968910217285,-0.142,1739502642.8579323,3.2599968910217285,-0.001998537384367376,1739502642.857934,3.2599968910217285,0.178442854022669,1739502642.8579357,3.2599968910217285,0.04557160619134478,1739502642.857937,3.2599968910217285,2.1674176777100014,1739502642.8579388,3.2599968910217285,0.0,1739502642.8579402,3.2599968910217285,0.031596433999177,1739502642.857942,3.2599968910217285,6.248639878083607,1739502642.8579438,3.2599968910217285,2.125586720399321 +1739502642.8775604,3.279996871948242,4.455249790099751,1739502642.8775628,3.279996871948242,-0.13104081377911925,1739502642.877566,3.279996871948242,3.693490903828139,1739502642.8775692,3.279996871948242,9.938845801720971,1739502642.877571,3.279996871948242,-0.142,1739502642.8775728,3.279996871948242,-0.001998537384367376,1739502642.877575,3.279996871948242,0.178442854022669,1739502642.8775764,3.279996871948242,0.04557160619134478,1739502642.8775778,3.279996871948242,2.1674176777100014,1739502642.8775797,3.279996871948242,0.0,1739502642.8775811,3.279996871948242,0.04183095731068054,1739502642.8775828,3.279996871948242,6.248639878083607,1739502642.8775845,3.279996871948242,2.125586720399321 +1739502642.8976028,3.299996852874756,4.455249790099751,1739502642.8976057,3.299996852874756,-0.13104081377911925,1739502642.8976095,3.299996852874756,3.693490903828139,1739502642.8976126,3.299996852874756,9.938845801720971,1739502642.897614,3.299996852874756,-0.142,1739502642.897616,3.299996852874756,-0.001998537384367376,1739502642.8976176,3.299996852874756,0.178442854022669,1739502642.8976192,3.299996852874756,0.04557160619134478,1739502642.8976204,3.299996852874756,2.1674176777100014,1739502642.8976223,3.299996852874756,0.0,1739502642.897624,3.299996852874756,0.04183095731068054,1739502642.8976257,3.299996852874756,6.248639878083607,1739502642.897627,3.299996852874756,2.125586720399321 +1739502642.9178066,3.3199968338012695,4.455249790099751,1739502642.9178092,3.3199968338012695,-0.13104081377911925,1739502642.9178126,3.3199968338012695,3.693490903828139,1739502642.9178154,3.3199968338012695,9.938845801720971,1739502642.917817,3.3199968338012695,-0.142,1739502642.917819,3.3199968338012695,-0.001998537384367376,1739502642.9178207,3.3199968338012695,0.178442854022669,1739502642.9178224,3.3199968338012695,0.04557160619134478,1739502642.9178238,3.3199968338012695,2.1674176777100014,1739502642.9178257,3.3199968338012695,0.0,1739502642.9178274,3.3199968338012695,0.04183095731068054,1739502642.917829,3.3199968338012695,6.248639878083607,1739502642.9178307,3.3199968338012695,2.125586720399321 +1739502642.9387057,3.339996814727783,4.455249790099751,1739502642.9387102,3.339996814727783,-0.13104081377911925,1739502642.938716,3.339996814727783,3.693490903828139,1739502642.9387205,3.339996814727783,9.938845801720971,1739502642.9387226,3.339996814727783,-0.142,1739502642.938729,3.339996814727783,-0.001998537384367376,1739502642.9387348,3.339996814727783,0.178442854022669,1739502642.9387372,3.339996814727783,0.04557160619134478,1739502642.9387393,3.339996814727783,2.1674176777100014,1739502642.938742,3.339996814727783,0.0,1739502642.9387443,3.339996814727783,0.04183095731068054,1739502642.9387467,3.339996814727783,6.248639878083607,1739502642.9387488,3.339996814727783,2.125586720399321 +1739502642.9589264,3.359996795654297,4.455249790099751,1739502642.9589307,3.359996795654297,-0.13104081377911925,1739502642.9589362,3.359996795654297,3.693490903828139,1739502642.9589415,3.359996795654297,9.938845801720971,1739502642.958944,3.359996795654297,-0.142,1739502642.9589472,3.359996795654297,-0.001998537384367376,1739502642.9589496,3.359996795654297,0.178442854022669,1739502642.9589522,3.359996795654297,0.04557160619134478,1739502642.9589546,3.359996795654297,2.1674176777100014,1739502642.958958,3.359996795654297,0.0,1739502642.9589603,3.359996795654297,0.04183095731068054,1739502642.958963,3.359996795654297,6.248639878083607,1739502642.9589655,3.359996795654297,2.125586720399321 +1739502642.9794328,3.3799967765808105,4.689135754434787,1739502642.9794369,3.3799967765808105,-0.13909501459392803,1739502642.9794426,3.3799967765808105,3.8774285516088263,1739502642.979448,3.3799967765808105,10.1315346317157,1739502642.9794507,3.3799967765808105,-0.14274122392468816,1739502642.9794538,3.3799967765808105,-0.0006699635339934382,1739502642.9794562,3.3799967765808105,0.18286218711264307,1739502642.9794588,3.3799967765808105,0.04740979113870869,1739502642.9794612,3.3799967765808105,2.1597683750739027,1739502642.979464,3.3799967765808105,0.0,1739502642.9794662,3.3799967765808105,0.024337747285449556,1739502642.9794688,3.3799967765808105,6.248909469819413,1739502642.9794714,3.3799967765808105,2.1299639960713654 +1739502642.998606,3.399996757507324,4.689135754434787,1739502642.9986103,3.399996757507324,-0.13909501459392803,1739502642.9986143,3.399996757507324,3.8774285516088263,1739502642.9986186,3.399996757507324,10.1315346317157,1739502642.998621,3.399996757507324,-0.14274122392468816,1739502642.9986234,3.399996757507324,-0.0006699635339934382,1739502642.998626,3.399996757507324,0.18286218711264307,1739502642.9986281,3.399996757507324,0.04740979113870869,1739502642.99863,3.399996757507324,2.1597683750739027,1739502642.9986324,3.399996757507324,0.0,1739502642.9986348,3.399996757507324,0.029804379002537296,1739502642.998637,3.399996757507324,6.248909469819413,1739502642.998639,3.399996757507324,2.1299639960713654 +1739502643.018744,3.419996738433838,4.689135754434787,1739502643.0187469,3.419996738433838,-0.13909501459392803,1739502643.0187507,3.419996738433838,3.8774285516088263,1739502643.018754,3.419996738433838,10.1315346317157,1739502643.018756,3.419996738433838,-0.14274122392468816,1739502643.0187578,3.419996738433838,-0.0006699635339934382,1739502643.0187597,3.419996738433838,0.18286218711264307,1739502643.0187614,3.419996738433838,0.04740979113870869,1739502643.018763,3.419996738433838,2.1597683750739027,1739502643.018765,3.419996738433838,0.0,1739502643.0187666,3.419996738433838,0.029804379002537296,1739502643.0187683,3.419996738433838,6.248909469819413,1739502643.0187705,3.419996738433838,2.1299639960713654 +1739502643.0374484,3.4399967193603516,4.689135754434787,1739502643.0374506,3.4399967193603516,-0.13909501459392803,1739502643.0374537,3.4399967193603516,3.8774285516088263,1739502643.0374563,3.4399967193603516,10.1315346317157,1739502643.037458,3.4399967193603516,-0.14274122392468816,1739502643.0374596,3.4399967193603516,-0.0006699635339934382,1739502643.037461,3.4399967193603516,0.18286218711264307,1739502643.0374622,3.4399967193603516,0.04740979113870869,1739502643.0374637,3.4399967193603516,2.1597683750739027,1739502643.0374653,3.4399967193603516,0.0,1739502643.0374668,3.4399967193603516,0.029804379002537296,1739502643.0374682,3.4399967193603516,6.248909469819413,1739502643.0374699,3.4399967193603516,2.1299639960713654 +1739502643.0575235,3.4599967002868652,4.689135754434787,1739502643.0575264,3.4599967002868652,-0.13909501459392803,1739502643.057529,3.4599967002868652,3.8774285516088263,1739502643.0575318,3.4599967002868652,10.1315346317157,1739502643.0575333,3.4599967002868652,-0.14274122392468816,1739502643.057535,3.4599967002868652,-0.0006699635339934382,1739502643.0575364,3.4599967002868652,0.18286218711264307,1739502643.0575376,3.4599967002868652,0.04740979113870869,1739502643.0575387,3.4599967002868652,2.1597683750739027,1739502643.0575404,3.4599967002868652,0.0,1739502643.0575418,3.4599967002868652,0.029804379002537296,1739502643.0575433,3.4599967002868652,6.248909469819413,1739502643.0575447,3.4599967002868652,2.1299639960713654 +1739502643.077805,3.479996681213379,4.923461037747035,1739502643.0778077,3.479996681213379,-0.14709543259579494,1739502643.0778112,3.479996681213379,4.143385316942074,1739502643.0778139,3.479996681213379,10.404028843315174,1739502643.0778153,3.479996681213379,-0.14343244415042047,1739502643.0778167,3.479996681213379,0.0006683591974227649,1739502643.0778184,3.479996681213379,0.1896347054588148,1739502643.0778198,3.479996681213379,0.04848304915578315,1739502643.0778215,3.479996681213379,2.1480983610203226,1739502643.077823,3.479996681213379,0.0,1739502643.0778244,3.479996681213379,0.008073430293049707,1739502643.0778258,3.479996681213379,6.249245477918026,1739502643.077827,3.479996681213379,2.13323400480308 +1739502643.0977933,3.4999966621398926,4.923461037747035,1739502643.0977955,3.4999966621398926,-0.14709543259579494,1739502643.0977986,3.4999966621398926,4.143385316942074,1739502643.0978012,3.4999966621398926,10.404028843315174,1739502643.0978024,3.4999966621398926,-0.14343244415042047,1739502643.097804,3.4999966621398926,0.0006683591974227649,1739502643.0978055,3.4999966621398926,0.1896347054588148,1739502643.097807,3.4999966621398926,0.04848304915578315,1739502643.0978084,3.4999966621398926,2.1480983610203226,1739502643.09781,3.4999966621398926,0.0,1739502643.0978112,3.4999966621398926,0.01486435621724258,1739502643.0978127,3.4999966621398926,6.249245477918026,1739502643.097814,3.4999966621398926,2.13323400480308 +1739502643.117623,3.5199966430664062,4.923461037747035,1739502643.1176257,3.5199966430664062,-0.14709543259579494,1739502643.1176293,3.5199966430664062,4.143385316942074,1739502643.1176317,3.5199966430664062,10.404028843315174,1739502643.1176333,3.5199966430664062,-0.14343244415042047,1739502643.117635,3.5199966430664062,0.0006683591974227649,1739502643.1176367,3.5199966430664062,0.1896347054588148,1739502643.117638,3.5199966430664062,0.04848304915578315,1739502643.117639,3.5199966430664062,2.1480983610203226,1739502643.117641,3.5199966430664062,0.0,1739502643.1176422,3.5199966430664062,0.01486435621724258,1739502643.1176438,3.5199966430664062,6.249245477918026,1739502643.117645,3.5199966430664062,2.13323400480308 +1739502643.137884,3.53999662399292,4.923461037747035,1739502643.1378865,3.53999662399292,-0.14709543259579494,1739502643.1378899,3.53999662399292,4.143385316942074,1739502643.137893,3.53999662399292,10.404028843315174,1739502643.1378944,3.53999662399292,-0.14343244415042047,1739502643.1378963,3.53999662399292,0.0006683591974227649,1739502643.1378977,3.53999662399292,0.1896347054588148,1739502643.137899,3.53999662399292,0.04848304915578315,1739502643.1379006,3.53999662399292,2.1480983610203226,1739502643.1379023,3.53999662399292,0.0,1739502643.137904,3.53999662399292,0.01486435621724258,1739502643.1379054,3.53999662399292,6.249245477918026,1739502643.137907,3.53999662399292,2.13323400480308 +1739502643.1579657,3.5599966049194336,4.923461037747035,1739502643.1579683,3.5599966049194336,-0.14709543259579494,1739502643.1579719,3.5599966049194336,4.143385316942074,1739502643.1579752,3.5599966049194336,10.404028843315174,1739502643.1579769,3.5599966049194336,-0.14343244415042047,1739502643.1579788,3.5599966049194336,0.0006683591974227649,1739502643.1579807,3.5599966049194336,0.1896347054588148,1739502643.157982,3.5599966049194336,0.04848304915578315,1739502643.1579838,3.5599966049194336,2.1480983610203226,1739502643.1579854,3.5599966049194336,0.0,1739502643.157987,3.5599966049194336,0.01486435621724258,1739502643.1579888,3.5599966049194336,6.249245477918026,1739502643.1579907,3.5599966049194336,2.13323400480308 +1739502643.1776283,3.5799965858459473,4.923461037747035,1739502643.1776311,3.5799965858459473,-0.14709543259579494,1739502643.1776347,3.5799965858459473,4.143385316942074,1739502643.177638,3.5799965858459473,10.404028843315174,1739502643.17764,3.5799965858459473,-0.14343244415042047,1739502643.1776419,3.5799965858459473,0.0006683591974227649,1739502643.1776438,3.5799965858459473,0.1896347054588148,1739502643.1776452,3.5799965858459473,0.04848304915578315,1739502643.1776469,3.5799965858459473,2.1480983610203226,1739502643.1776488,3.5799965858459473,0.0,1739502643.1776505,3.5799965858459473,0.01486435621724258,1739502643.177652,3.5799965858459473,6.249245477918026,1739502643.1776538,3.5799965858459473,2.13323400480308 +1739502643.2014318,3.599996566772461,5.158051780258839,1739502643.2014344,3.599996566772461,-0.15501591405488746,1739502643.2014372,3.599996566772461,4.491186427131467,1739502643.2014399,3.599996566772461,10.75480945101561,1739502643.201441,3.599996566772461,-0.145,1739502643.2014427,3.599996566772461,0.0017895903220510254,1739502643.2014441,3.599996566772461,0.19755172379586913,1739502643.2014453,3.599996566772461,0.04843172243728691,1739502643.2014468,3.599996566772461,2.1345361280450064,1739502643.201448,3.599996566772461,0.0,1739502643.2014492,3.599996566772461,-0.007034020101487708,1739502643.2014506,3.599996566772461,6.249670089963592,1739502643.201452,3.599996566772461,2.1347269010601084 +1739502643.2174978,3.6199965476989746,5.158051780258839,1739502643.2175002,3.6199965476989746,-0.15501591405488746,1739502643.2175033,3.6199965476989746,4.491186427131467,1739502643.217506,3.6199965476989746,10.75480945101561,1739502643.2175076,3.6199965476989746,-0.145,1739502643.2175093,3.6199965476989746,0.0017895903220510254,1739502643.2175114,3.6199965476989746,0.19755172379586913,1739502643.2175128,3.6199965476989746,0.04843172243728691,1739502643.2175143,3.6199965476989746,2.1345361280450064,1739502643.2175157,3.6199965476989746,0.0,1739502643.2175171,3.6199965476989746,-0.00019077301510206368,1739502643.2175183,3.6199965476989746,6.249670089963592,1739502643.2175198,3.6199965476989746,2.1347269010601084 +1739502643.237533,3.6399965286254883,5.158051780258839,1739502643.2375374,3.6399965286254883,-0.15501591405488746,1739502643.2375412,3.6399965286254883,4.491186427131467,1739502643.237545,3.6399965286254883,10.75480945101561,1739502643.2375472,3.6399965286254883,-0.145,1739502643.2375495,3.6399965286254883,0.0017895903220510254,1739502643.2375515,3.6399965286254883,0.19755172379586913,1739502643.2375531,3.6399965286254883,0.04843172243728691,1739502643.2375553,3.6399965286254883,2.1345361280450064,1739502643.2375576,3.6399965286254883,0.0,1739502643.2375598,3.6399965286254883,-0.00019077301510206368,1739502643.237562,3.6399965286254883,6.249670089963592,1739502643.2375636,3.6399965286254883,2.1347269010601084 +1739502643.2575812,3.659996509552002,5.158051780258839,1739502643.2575846,3.659996509552002,-0.15501591405488746,1739502643.257588,3.659996509552002,4.491186427131467,1739502643.2575912,3.659996509552002,10.75480945101561,1739502643.2575932,3.659996509552002,-0.145,1739502643.257595,3.659996509552002,0.0017895903220510254,1739502643.257597,3.659996509552002,0.19755172379586913,1739502643.2575986,3.659996509552002,0.04843172243728691,1739502643.2576,3.659996509552002,2.1345361280450064,1739502643.2576017,3.659996509552002,0.0,1739502643.257604,3.659996509552002,-0.00019077301510206368,1739502643.2576056,3.659996509552002,6.249670089963592,1739502643.2576072,3.659996509552002,2.1347269010601084 +1739502643.2779958,3.6799964904785156,5.158051780258839,1739502643.2779994,3.6799964904785156,-0.15501591405488746,1739502643.278003,3.6799964904785156,4.491186427131467,1739502643.2780066,3.6799964904785156,10.75480945101561,1739502643.2780082,3.6799964904785156,-0.145,1739502643.2780108,3.6799964904785156,0.0017895903220510254,1739502643.2780128,3.6799964904785156,0.19755172379586913,1739502643.2780144,3.6799964904785156,0.04843172243728691,1739502643.2780163,3.6799964904785156,2.1345361280450064,1739502643.2780182,3.6799964904785156,0.0,1739502643.2780204,3.6799964904785156,-0.00019077301510206368,1739502643.2780223,3.6799964904785156,6.249670089963592,1739502643.2780242,3.6799964904785156,2.1347269010601084 +1739502643.2981179,3.6999964714050293,5.392743621505659,1739502643.2981215,3.6999964714050293,-0.16283847281764618,1739502643.2981255,3.6999964714050293,4.512324337961206,1739502643.298129,3.6999964714050293,10.775929586554103,1739502643.298131,3.6999964714050293,-0.145,1739502643.2981336,3.6999964714050293,0.003313726785576202,1739502643.2981353,3.6999964714050293,0.19588935556959902,1739502643.2981377,3.6999964714050293,0.0519093005932185,1739502643.2981393,3.6999964714050293,2.1373767245029334,1739502643.2981417,3.6999964714050293,0.0,1739502643.2981434,3.6999964714050293,0.003953932370734765,1739502643.2981453,3.6999964714050293,6.25010208648468,1739502643.2981474,3.6999964714050293,2.134718013414486 +1739502643.3178625,3.719996452331543,5.392743621505659,1739502643.3178656,3.719996452331543,-0.16283847281764618,1739502643.31787,3.719996452331543,4.512324337961206,1739502643.3178735,3.719996452331543,10.775929586554103,1739502643.3178751,3.719996452331543,-0.145,1739502643.3178775,3.719996452331543,0.003313726785576202,1739502643.31788,3.719996452331543,0.19588935556959902,1739502643.3178816,3.719996452331543,0.0519093005932185,1739502643.3178835,3.719996452331543,2.1373767245029334,1739502643.3178854,3.719996452331543,0.0,1739502643.3178875,3.719996452331543,0.0026587110884475074,1739502643.3178895,3.719996452331543,6.25010208648468,1739502643.3178918,3.719996452331543,2.134718013414486 +1739502643.3379843,3.7399964332580566,5.392743621505659,1739502643.3379877,3.7399964332580566,-0.16283847281764618,1739502643.337992,3.7399964332580566,4.512324337961206,1739502643.3379955,3.7399964332580566,10.775929586554103,1739502643.3379977,3.7399964332580566,-0.145,1739502643.3379998,3.7399964332580566,0.003313726785576202,1739502643.3380017,3.7399964332580566,0.19588935556959902,1739502643.3380036,3.7399964332580566,0.0519093005932185,1739502643.3380053,3.7399964332580566,2.1373767245029334,1739502643.3380075,3.7399964332580566,0.0,1739502643.3380094,3.7399964332580566,0.0026587110884475074,1739502643.3380115,3.7399964332580566,6.25010208648468,1739502643.3380132,3.7399964332580566,2.134718013414486 +1739502643.358039,3.7599964141845703,5.392743621505659,1739502643.358042,3.7599964141845703,-0.16283847281764618,1739502643.3580463,3.7599964141845703,4.512324337961206,1739502643.3580499,3.7599964141845703,10.775929586554103,1739502643.3580515,3.7599964141845703,-0.145,1739502643.358054,3.7599964141845703,0.003313726785576202,1739502643.3580556,3.7599964141845703,0.19588935556959902,1739502643.3580575,3.7599964141845703,0.0519093005932185,1739502643.3580592,3.7599964141845703,2.1373767245029334,1739502643.3580618,3.7599964141845703,0.0,1739502643.3580637,3.7599964141845703,0.0026587110884475074,1739502643.3580654,3.7599964141845703,6.25010208648468,1739502643.3580675,3.7599964141845703,2.134718013414486 +1739502643.3781676,3.779996395111084,5.392743621505659,1739502643.3781712,3.779996395111084,-0.16283847281764618,1739502643.3781755,3.779996395111084,4.512324337961206,1739502643.3781793,3.779996395111084,10.775929586554103,1739502643.3781812,3.779996395111084,-0.145,1739502643.3781831,3.779996395111084,0.003313726785576202,1739502643.3781853,3.779996395111084,0.19588935556959902,1739502643.378187,3.779996395111084,0.0519093005932185,1739502643.3781888,3.779996395111084,2.1373767245029334,1739502643.378191,3.779996395111084,0.0,1739502643.378193,3.779996395111084,0.0026587110884475074,1739502643.378195,3.779996395111084,6.25010208648468,1739502643.3781967,3.779996395111084,2.134718013414486 +1739502643.4015186,3.7999963760375977,5.392743621505659,1739502643.4015276,3.7999963760375977,-0.16283847281764618,1739502643.4015381,3.7999963760375977,4.512324337961206,1739502643.4015477,3.7999963760375977,10.775929586554103,1739502643.401553,3.7999963760375977,-0.145,1739502643.4015589,3.7999963760375977,0.003313726785576202,1739502643.4015641,3.7999963760375977,0.19588935556959902,1739502643.4015691,3.7999963760375977,0.0519093005932185,1739502643.401574,3.7999963760375977,2.1373767245029334,1739502643.4015796,3.7999963760375977,0.0,1739502643.4015844,3.7999963760375977,0.0026587110884475074,1739502643.4015899,3.7999963760375977,6.25010208648468,1739502643.401595,3.7999963760375977,2.134718013414486 +1739502643.4432404,3.839996337890625,5.6274528862152255,1739502643.443249,3.839996337890625,-0.17055299312879857,1739502643.4432595,3.839996337890625,5.068968004451558,1739502643.4432695,3.839996337890625,11.333179309307496,1739502643.4432743,3.839996337890625,-0.14751512891268015,1739502643.4432802,3.839996337890625,0.00403765223129331,1739502643.4432852,3.839996337890625,0.20886951341453175,1739502643.44329,3.839996337890625,0.049268377392816906,1739502643.4432948,3.839996337890625,2.1152967736021338,1739502643.443301,3.839996337890625,0.0,1739502643.4433057,3.839996337890625,-0.029918367126446948,1739502643.4433112,3.839996337890625,6.250608079478647,1739502643.4433162,3.839996337890625,2.1350347971116728 +1739502643.4639943,3.8599963188171387,5.6274528862152255,1739502643.4640007,3.8599963188171387,-0.17055299312879857,1739502643.4640083,3.8599963188171387,5.068968004451558,1739502643.4640174,3.8599963188171387,11.333179309307496,1739502643.4640222,3.8599963188171387,-0.14751512891268015,1739502643.4640286,3.8599963188171387,0.00403765223129331,1739502643.4640343,3.8599963188171387,0.20886951341453175,1739502643.4640403,3.8599963188171387,0.049268377392816906,1739502643.4640458,3.8599963188171387,2.1152967736021338,1739502643.4640517,3.8599963188171387,0.0,1739502643.4640574,3.8599963188171387,-0.019738023509539016,1739502643.4640636,3.8599963188171387,6.250608079478647,1739502643.4640694,3.8599963188171387,2.1350347971116728 +1739502643.4799662,3.8799962997436523,5.6274528862152255,1739502643.4799705,3.8799962997436523,-0.17055299312879857,1739502643.479976,3.8799962997436523,5.068968004451558,1739502643.479982,3.8799962997436523,11.333179309307496,1739502643.479985,3.8799962997436523,-0.14751512891268015,1739502643.4799888,3.8799962997436523,0.00403765223129331,1739502643.4799926,3.8799962997436523,0.20886951341453175,1739502643.4799962,3.8799962997436523,0.049268377392816906,1739502643.4800003,3.8799962997436523,2.1152967736021338,1739502643.4800043,3.8799962997436523,0.0,1739502643.4800081,3.8799962997436523,-0.019738023509539016,1739502643.4800117,3.8799962997436523,6.250608079478647,1739502643.4800155,3.8799962997436523,2.1350347971116728 +1739502643.497479,3.899996280670166,5.6274528862152255,1739502643.4974809,3.899996280670166,-0.17055299312879857,1739502643.4974837,3.899996280670166,5.068968004451558,1739502643.4974868,3.899996280670166,11.333179309307496,1739502643.497488,3.899996280670166,-0.14751512891268015,1739502643.49749,3.899996280670166,0.00403765223129331,1739502643.4974911,3.899996280670166,0.20886951341453175,1739502643.4974926,3.899996280670166,0.049268377392816906,1739502643.4974937,3.899996280670166,2.1152967736021338,1739502643.4974954,3.899996280670166,0.0,1739502643.4974966,3.899996280670166,-0.019738023509539016,1739502643.4974978,3.899996280670166,6.250608079478647,1739502643.4974992,3.899996280670166,2.1350347971116728 +1739502643.5180306,3.9199962615966797,5.862122618578281,1739502643.5180328,3.9199962615966797,-0.1781457764691714,1739502643.5180357,3.9199962615966797,5.077893047064695,1739502643.5180383,3.9199962615966797,11.338707953056579,1739502643.5180395,3.9199962615966797,-0.14756493651402322,1739502643.5180414,3.9199962615966797,0.0055838666348390475,1739502643.5180426,3.9199962615966797,0.20613536297343077,1739502643.518044,3.9199962615966797,0.05277590123347228,1739502643.5180452,3.9199962615966797,2.119928669160405,1739502643.5180466,3.9199962615966797,0.0,1739502643.518048,3.9199962615966797,-0.01053077303713721,1739502643.5180492,3.9199962615966797,6.2511214721199035,1739502643.518051,3.9199962615966797,2.1333367098566516 +1739502643.5378747,3.9399962425231934,5.862122618578281,1739502643.5378773,3.9399962425231934,-0.1781457764691714,1739502643.5378804,3.9399962425231934,5.077893047064695,1739502643.5378833,3.9399962425231934,11.338707953056579,1739502643.5378847,3.9399962425231934,-0.14756493651402322,1739502643.5378864,3.9399962425231934,0.0055838666348390475,1739502643.5378878,3.9399962425231934,0.20613536297343077,1739502643.537889,3.9399962425231934,0.05277590123347228,1739502643.5378902,3.9399962425231934,2.119928669160405,1739502643.537892,3.9399962425231934,0.0,1739502643.5378933,3.9399962425231934,-0.01340804069624646,1739502643.537895,3.9399962425231934,6.2511214721199035,1739502643.5378964,3.9399962425231934,2.1333367098566516 +1739502643.5578482,3.959996223449707,5.862122618578281,1739502643.557851,3.959996223449707,-0.1781457764691714,1739502643.5578542,3.959996223449707,5.077893047064695,1739502643.557857,3.959996223449707,11.338707953056579,1739502643.5578582,3.959996223449707,-0.14756493651402322,1739502643.55786,3.959996223449707,0.0055838666348390475,1739502643.5578613,3.959996223449707,0.20613536297343077,1739502643.5578628,3.959996223449707,0.05277590123347228,1739502643.5578642,3.959996223449707,2.119928669160405,1739502643.5578656,3.959996223449707,0.0,1739502643.557867,3.959996223449707,-0.01340804069624646,1739502643.5578687,3.959996223449707,6.2511214721199035,1739502643.5578704,3.959996223449707,2.1333367098566516 +1739502643.5789716,3.9799962043762207,5.862122618578281,1739502643.578975,3.9799962043762207,-0.1781457764691714,1739502643.5789793,3.9799962043762207,5.077893047064695,1739502643.5789845,3.9799962043762207,11.338707953056579,1739502643.5789874,3.9799962043762207,-0.14756493651402322,1739502643.5789912,3.9799962043762207,0.0055838666348390475,1739502643.5789945,3.9799962043762207,0.20613536297343077,1739502643.5789979,3.9799962043762207,0.05277590123347228,1739502643.5790012,3.9799962043762207,2.119928669160405,1739502643.5790045,3.9799962043762207,0.0,1739502643.5790076,3.9799962043762207,-0.01340804069624646,1739502643.5790114,3.9799962043762207,6.2511214721199035,1739502643.5790145,3.9799962043762207,2.1333367098566516 +1739502643.5990732,3.9999961853027344,5.862122618578281,1739502643.5990767,3.9999961853027344,-0.1781457764691714,1739502643.5990813,3.9999961853027344,5.077893047064695,1739502643.5990863,3.9999961853027344,11.338707953056579,1739502643.5990894,3.9999961853027344,-0.14756493651402322,1739502643.599093,3.9999961853027344,0.0055838666348390475,1739502643.5990963,3.9999961853027344,0.20613536297343077,1739502643.5990996,3.9999961853027344,0.05277590123347228,1739502643.599103,3.9999961853027344,2.119928669160405,1739502643.5991066,3.9999961853027344,0.0,1739502643.59911,3.9999961853027344,-0.01340804069624646,1739502643.5991132,3.9999961853027344,6.2511214721199035,1739502643.5991166,3.9999961853027344,2.1333367098566516 +1739502643.617751,4.019996166229248,5.862122618578281,1739502643.6177535,4.019996166229248,-0.1781457764691714,1739502643.6177566,4.019996166229248,5.077893047064695,1739502643.6177595,4.019996166229248,11.338707953056579,1739502643.6177611,4.019996166229248,-0.14756493651402322,1739502643.6177628,4.019996166229248,0.0055838666348390475,1739502643.6177647,4.019996166229248,0.20613536297343077,1739502643.617766,4.019996166229248,0.05277590123347228,1739502643.617767,4.019996166229248,2.119928669160405,1739502643.617769,4.019996166229248,0.0,1739502643.6177702,4.019996166229248,-0.01340804069624646,1739502643.6177719,4.019996166229248,6.2511214721199035,1739502643.6177733,4.019996166229248,2.1333367098566516 +1739502643.6375551,4.039996147155762,6.096602949372915,1739502643.6375573,4.039996147155762,-0.1856048169332487,1739502643.6375604,4.039996147155762,5.507272192333409,1739502643.637563,4.039996147155762,11.765254351208286,1739502643.6375644,4.039996147155762,-0.15039512813578826,1739502643.6375659,4.039996147155762,0.0062112191265072695,1739502643.6375673,4.039996147155762,0.2135915523756114,1739502643.6375687,4.039996147155762,0.05104193470271706,1739502643.6375701,4.039996147155762,2.1073210367596316,1739502643.637572,4.039996147155762,0.0,1739502643.6375735,4.039996147155762,-0.02969401318698855,1739502643.6375747,4.039996147155762,6.251708902344365,1739502643.637576,4.039996147155762,2.1319256802064124 +1739502643.6574633,4.059996128082275,6.096602949372915,1739502643.657466,4.059996128082275,-0.1856048169332487,1739502643.6574686,4.059996128082275,5.507272192333409,1739502643.6574714,4.059996128082275,11.765254351208286,1739502643.657473,4.059996128082275,-0.15039512813578826,1739502643.6574745,4.059996128082275,0.0062112191265072695,1739502643.657476,4.059996128082275,0.2135915523756114,1739502643.6574774,4.059996128082275,0.05104193470271706,1739502643.6574786,4.059996128082275,2.1073210367596316,1739502643.65748,4.059996128082275,0.0,1739502643.6574814,4.059996128082275,-0.024604643446780816,1739502643.6574829,4.059996128082275,6.251708902344365,1739502643.657484,4.059996128082275,2.1319256802064124 +1739502643.6773717,4.079996109008789,6.096602949372915,1739502643.677374,4.079996109008789,-0.1856048169332487,1739502643.677377,4.079996109008789,5.507272192333409,1739502643.6773798,4.079996109008789,11.765254351208286,1739502643.677381,4.079996109008789,-0.15039512813578826,1739502643.677383,4.079996109008789,0.0062112191265072695,1739502643.6773846,4.079996109008789,0.2135915523756114,1739502643.677386,4.079996109008789,0.05104193470271706,1739502643.6773872,4.079996109008789,2.1073210367596316,1739502643.6773891,4.079996109008789,0.0,1739502643.6773903,4.079996109008789,-0.024604643446780816,1739502643.6773918,4.079996109008789,6.251708902344365,1739502643.6773937,4.079996109008789,2.1319256802064124 +1739502643.6974964,4.099996089935303,6.096602949372915,1739502643.6974986,4.099996089935303,-0.1856048169332487,1739502643.6975017,4.099996089935303,5.507272192333409,1739502643.6975045,4.099996089935303,11.765254351208286,1739502643.697506,4.099996089935303,-0.15039512813578826,1739502643.6975079,4.099996089935303,0.0062112191265072695,1739502643.697509,4.099996089935303,0.2135915523756114,1739502643.6975107,4.099996089935303,0.05104193470271706,1739502643.697512,4.099996089935303,2.1073210367596316,1739502643.6975138,4.099996089935303,0.0,1739502643.697515,4.099996089935303,-0.024604643446780816,1739502643.6975162,4.099996089935303,6.251708902344365,1739502643.6975179,4.099996089935303,2.1319256802064124 +1739502643.717533,4.119996070861816,6.096602949372915,1739502643.7175355,4.119996070861816,-0.1856048169332487,1739502643.7175386,4.119996070861816,5.507272192333409,1739502643.7175415,4.119996070861816,11.765254351208286,1739502643.7175431,4.119996070861816,-0.15039512813578826,1739502643.717545,4.119996070861816,0.0062112191265072695,1739502643.7175462,4.119996070861816,0.2135915523756114,1739502643.717548,4.119996070861816,0.05104193470271706,1739502643.7175493,4.119996070861816,2.1073210367596316,1739502643.7175508,4.119996070861816,0.0,1739502643.7175522,4.119996070861816,-0.024604643446780816,1739502643.7175536,4.119996070861816,6.251708902344365,1739502643.717555,4.119996070861816,2.1319256802064124 +1739502643.7374725,4.13999605178833,6.330868366519734,1739502643.7374752,4.13999605178833,-0.19291769837837514,1739502643.7374778,4.13999605178833,5.529542032725248,1739502643.7374806,4.13999605178833,11.782157974331335,1739502643.7374823,4.13999605178833,-0.15054605334224408,1739502643.737484,4.13999605178833,0.007772618005392996,1739502643.7374856,4.13999605178833,0.2106690723267555,1739502643.7374868,4.13999605178833,0.054436423776429516,1739502643.7374883,4.13999605178833,2.112253683686806,1739502643.73749,4.13999605178833,0.0,1739502643.7374911,4.13999605178833,-0.013527667517710994,1739502643.737493,4.13999605178833,6.252303736327147,1739502643.7374945,4.13999605178833,2.1292429084519253 +1739502643.762174,4.159996032714844,6.330868366519734,1739502643.7621827,4.159996032714844,-0.19291769837837514,1739502643.762193,4.159996032714844,5.529542032725248,1739502643.762203,4.159996032714844,11.782157974331335,1739502643.7622077,4.159996032714844,-0.15054605334224408,1739502643.7622142,4.159996032714844,0.007772618005392996,1739502643.7622192,4.159996032714844,0.2106690723267555,1739502643.7622244,4.159996032714844,0.054436423776429516,1739502643.7622287,4.159996032714844,2.112253683686806,1739502643.7622344,4.159996032714844,0.0,1739502643.7622392,4.159996032714844,-0.016989224765119104,1739502643.7622445,4.159996032714844,6.252303736327147,1739502643.7622492,4.159996032714844,2.1292429084519253 +1739502643.781538,4.179996013641357,6.330868366519734,1739502643.7815468,4.179996013641357,-0.19291769837837514,1739502643.7815576,4.179996013641357,5.529542032725248,1739502643.7815678,4.179996013641357,11.782157974331335,1739502643.7815728,4.179996013641357,-0.15054605334224408,1739502643.7815793,4.179996013641357,0.007772618005392996,1739502643.7815845,4.179996013641357,0.2106690723267555,1739502643.7815895,4.179996013641357,0.054436423776429516,1739502643.7815943,4.179996013641357,2.112253683686806,1739502643.7815998,4.179996013641357,0.0,1739502643.7816045,4.179996013641357,-0.016989224765119104,1739502643.7816098,4.179996013641357,6.252303736327147,1739502643.7816148,4.179996013641357,2.1292429084519253 +1739502643.8042774,4.199995994567871,6.330868366519734,1739502643.8042836,4.199995994567871,-0.19291769837837514,1739502643.8042908,4.199995994567871,5.529542032725248,1739502643.8042974,4.199995994567871,11.782157974331335,1739502643.8043008,4.199995994567871,-0.15054605334224408,1739502643.804305,4.199995994567871,0.007772618005392996,1739502643.8043087,4.199995994567871,0.2106690723267555,1739502643.8043122,4.199995994567871,0.054436423776429516,1739502643.8043156,4.199995994567871,2.112253683686806,1739502643.8043194,4.199995994567871,0.0,1739502643.804323,4.199995994567871,-0.016989224765119104,1739502643.8043268,4.199995994567871,6.252303736327147,1739502643.8043303,4.199995994567871,2.1292429084519253 +1739502643.8202677,4.209995985031128,6.330868366519734,1739502643.820274,4.209995985031128,-0.19291769837837514,1739502643.8202798,4.209995985031128,5.529542032725248,1739502643.8202856,4.209995985031128,11.782157974331335,1739502643.8202882,4.209995985031128,-0.15054605334224408,1739502643.8202918,4.209995985031128,0.007772618005392996,1739502643.8202946,4.209995985031128,0.2106690723267555,1739502643.8202977,4.209995985031128,0.054436423776429516,1739502643.8203003,4.209995985031128,2.112253683686806,1739502643.8203032,4.209995985031128,0.0,1739502643.8203058,4.209995985031128,-0.016989224765119104,1739502643.8203092,4.209995985031128,6.252303736327147,1739502643.820312,4.209995985031128,2.1292429084519253 +1739502643.8403826,4.239995956420898,6.330868366519734,1739502643.8403866,4.239995956420898,-0.19291769837837514,1739502643.8403916,4.239995956420898,5.529542032725248,1739502643.8403978,4.239995956420898,11.782157974331335,1739502643.8404014,4.239995956420898,-0.15054605334224408,1739502643.8404057,4.239995956420898,0.007772618005392996,1739502643.8404095,4.239995956420898,0.2106690723267555,1739502643.8404138,4.239995956420898,0.054436423776429516,1739502643.8404176,4.239995956420898,2.112253683686806,1739502643.8404217,4.239995956420898,0.0,1739502643.8404257,4.239995956420898,-0.016989224765119104,1739502643.8404298,4.239995956420898,6.252303736327147,1739502643.8404338,4.239995956420898,2.1292429084519253 +1739502643.8593216,4.259995937347412,6.564888981594651,1739502643.8593242,4.259995937347412,-0.2000764957973855,1739502643.8593273,4.259995937347412,5.7265333452068425,1739502643.8593307,4.259995937347412,11.975564132555624,1739502643.8593323,4.259995937347412,-0.151,1739502643.8593345,4.259995937347412,0.009070060324304317,1739502643.859336,4.259995937347412,0.2124999188064242,1739502643.8593378,4.259995937347412,0.05573543161848481,1739502643.859339,4.259995937347412,2.10916217849129,1739502643.859341,4.259995937347412,0.0,1739502643.8593426,4.259995937347412,-0.01888004906747827,1739502643.8593442,4.259995937347412,6.252972684245004,1739502643.8593457,4.259995937347412,2.127451344576868 +1739502643.8904026,4.279995918273926,6.564888981594651,1739502643.890412,4.279995918273926,-0.2000764957973855,1739502643.890423,4.279995918273926,5.7265333452068425,1739502643.8904335,4.279995918273926,11.975564132555624,1739502643.8904383,4.279995918273926,-0.151,1739502643.8904445,4.279995918273926,0.009070060324304317,1739502643.8904498,4.279995918273926,0.2124999188064242,1739502643.8904545,4.279995918273926,0.05573543161848481,1739502643.8904593,4.279995918273926,2.10916217849129,1739502643.8904655,4.279995918273926,0.0,1739502643.89047,4.279995918273926,-0.018289166085577957,1739502643.8904755,4.279995918273926,6.252972684245004,1739502643.8904808,4.279995918273926,2.127451344576868 +1739502643.9029617,4.2999958992004395,6.564888981594651,1739502643.9029703,4.2999958992004395,-0.2000764957973855,1739502643.9029806,4.2999958992004395,5.7265333452068425,1739502643.9029906,4.2999958992004395,11.975564132555624,1739502643.9029953,4.2999958992004395,-0.151,1739502643.9030015,4.2999958992004395,0.009070060324304317,1739502643.9030066,4.2999958992004395,0.2124999188064242,1739502643.9030113,4.2999958992004395,0.05573543161848481,1739502643.9030159,4.2999958992004395,2.10916217849129,1739502643.9030216,4.2999958992004395,0.0,1739502643.903027,4.2999958992004395,-0.018289166085577957,1739502643.903032,4.2999958992004395,6.252972684245004,1739502643.903037,4.2999958992004395,2.127451344576868 +1739502643.926654,4.309995889663696,6.564888981594651,1739502643.926663,4.309995889663696,-0.2000764957973855,1739502643.9266737,4.309995889663696,5.7265333452068425,1739502643.9266837,4.309995889663696,11.975564132555624,1739502643.9266882,4.309995889663696,-0.151,1739502643.9266946,4.309995889663696,0.009070060324304317,1739502643.9266996,4.309995889663696,0.2124999188064242,1739502643.9267044,4.309995889663696,0.05573543161848481,1739502643.9267092,4.309995889663696,2.10916217849129,1739502643.926715,4.309995889663696,0.0,1739502643.9267197,4.309995889663696,-0.018289166085577957,1739502643.926725,4.309995889663696,6.252972684245004,1739502643.92673,4.309995889663696,2.127451344576868 +1739502643.9466875,4.339995861053467,6.564888981594651,1739502643.9466994,4.339995861053467,-0.2000764957973855,1739502643.9467142,4.339995861053467,5.7265333452068425,1739502643.9467251,4.339995861053467,11.975564132555624,1739502643.9467287,4.339995861053467,-0.151,1739502643.9467332,4.339995861053467,0.009070060324304317,1739502643.9467368,4.339995861053467,0.2124999188064242,1739502643.946741,4.339995861053467,0.05573543161848481,1739502643.9467516,4.339995861053467,2.10916217849129,1739502643.9467578,4.339995861053467,0.0,1739502643.9467657,4.339995861053467,-0.018289166085577957,1739502643.946777,4.339995861053467,6.252972684245004,1739502643.9467847,4.339995861053467,2.127451344576868 +1739502643.9639776,4.3599958419799805,6.798704179917509,1739502643.9639802,4.3599958419799805,-0.20707088054905665,1739502643.963984,4.3599958419799805,5.976758364221622,1739502643.9639878,4.3599958419799805,12.221782383505456,1739502643.9639895,4.3599958419799805,-0.1524550993317131,1739502643.9639919,4.3599958419799805,0.010070652277695,1739502643.9639935,4.3599958419799805,0.21474613872115492,1739502643.9639955,4.3599958419799805,0.05606608581929086,1739502643.9639971,4.3599958419799805,2.1053754681529595,1739502643.9639995,4.3599958419799805,0.0,1739502643.9640012,4.3599958419799805,-0.02088841375768698,1739502643.9640033,4.3599958419799805,6.253649043556369,1739502643.9640052,4.3599958419799805,2.1254516164805497 +1739502643.982575,4.379995822906494,6.798704179917509,1739502643.9825773,4.379995822906494,-0.20707088054905665,1739502643.9825802,4.379995822906494,5.976758364221622,1739502643.9825828,4.379995822906494,12.221782383505456,1739502643.9825842,4.379995822906494,-0.1524550993317131,1739502643.982586,4.379995822906494,0.010070652277695,1739502643.9825873,4.379995822906494,0.21474613872115492,1739502643.982589,4.379995822906494,0.05606608581929086,1739502643.9825902,4.379995822906494,2.1053754681529595,1739502643.9825916,4.379995822906494,0.0,1739502643.982593,4.379995822906494,-0.020076148327590193,1739502643.9825945,4.379995822906494,6.253649043556369,1739502643.9825962,4.379995822906494,2.1254516164805497 +1739502644.0024278,4.399995803833008,6.798704179917509,1739502644.0024302,4.399995803833008,-0.20707088054905665,1739502644.002433,4.399995803833008,5.976758364221622,1739502644.0024357,4.399995803833008,12.221782383505456,1739502644.0024369,4.399995803833008,-0.1524550993317131,1739502644.0024383,4.399995803833008,0.010070652277695,1739502644.0024397,4.399995803833008,0.21474613872115492,1739502644.0024412,4.399995803833008,0.05606608581929086,1739502644.0024426,4.399995803833008,2.1053754681529595,1739502644.002444,4.399995803833008,0.0,1739502644.0024452,4.399995803833008,-0.020076148327590193,1739502644.002447,4.399995803833008,6.253649043556369,1739502644.002448,4.399995803833008,2.1254516164805497 +1739502644.0226343,4.4199957847595215,6.798704179917509,1739502644.022637,4.4199957847595215,-0.20707088054905665,1739502644.02264,4.4199957847595215,5.976758364221622,1739502644.0226424,4.4199957847595215,12.221782383505456,1739502644.0226438,4.4199957847595215,-0.1524550993317131,1739502644.0226455,4.4199957847595215,0.010070652277695,1739502644.0226471,4.4199957847595215,0.21474613872115492,1739502644.0226483,4.4199957847595215,0.05606608581929086,1739502644.0226495,4.4199957847595215,2.1053754681529595,1739502644.0226512,4.4199957847595215,0.0,1739502644.0226526,4.4199957847595215,-0.020076148327590193,1739502644.022654,4.4199957847595215,6.253649043556369,1739502644.022656,4.4199957847595215,2.1254516164805497 +1739502644.0425336,4.439995765686035,6.798704179917509,1739502644.0425363,4.439995765686035,-0.20707088054905665,1739502644.0425394,4.439995765686035,5.976758364221622,1739502644.0425417,4.439995765686035,12.221782383505456,1739502644.0425434,4.439995765686035,-0.1524550993317131,1739502644.042545,4.439995765686035,0.010070652277695,1739502644.0425467,4.439995765686035,0.21474613872115492,1739502644.042548,4.439995765686035,0.05606608581929086,1739502644.0425491,4.439995765686035,2.1053754681529595,1739502644.0425508,4.439995765686035,0.0,1739502644.042552,4.439995765686035,-0.020076148327590193,1739502644.0425537,4.439995765686035,6.253649043556369,1739502644.042555,4.439995765686035,2.1254516164805497 +1739502644.062708,4.459995746612549,6.798704179917509,1739502644.062711,4.459995746612549,-0.20707088054905665,1739502644.0627139,4.459995746612549,5.976758364221622,1739502644.0627167,4.459995746612549,12.221782383505456,1739502644.062718,4.459995746612549,-0.1524550993317131,1739502644.0627196,4.459995746612549,0.010070652277695,1739502644.062721,4.459995746612549,0.21474613872115492,1739502644.0627224,4.459995746612549,0.05606608581929086,1739502644.0627239,4.459995746612549,2.1053754681529595,1739502644.0627258,4.459995746612549,0.0,1739502644.0627272,4.459995746612549,-0.020076148327590193,1739502644.0627284,4.459995746612549,6.253649043556369,1739502644.06273,4.459995746612549,2.1254516164805497 +1739502644.0826836,4.4799957275390625,7.032292593177704,1739502644.082686,4.4799957275390625,-0.21389326060200275,1739502644.0826888,4.4799957275390625,6.208885022174687,1739502644.0826914,4.4799957275390625,12.449477714234202,1739502644.0826929,4.4799957275390625,-0.153,1739502644.0826948,4.4799957275390625,0.011240283416738182,1739502644.082696,4.4799957275390625,0.21678404450841865,1739502644.0826972,4.4799957275390625,0.056719782553635245,1739502644.0826986,4.4799957275390625,2.101945819152504,1739502644.0827,4.4799957275390625,0.0,1739502644.0827012,4.4799957275390625,-0.021843937146623613,1739502644.0827029,4.4799957275390625,6.254399592491855,1739502644.0827043,4.4799957275390625,2.1232373219309753 +1739502644.1028476,4.499995708465576,7.032292593177704,1739502644.1028495,4.499995708465576,-0.21389326060200275,1739502644.1028526,4.499995708465576,6.208885022174687,1739502644.1028554,4.499995708465576,12.449477714234202,1739502644.1028566,4.499995708465576,-0.153,1739502644.1028585,4.499995708465576,0.011240283416738182,1739502644.1028597,4.499995708465576,0.21678404450841865,1739502644.1028612,4.499995708465576,0.056719782553635245,1739502644.1028621,4.499995708465576,2.101945819152504,1739502644.1028636,4.499995708465576,0.0,1739502644.102865,4.499995708465576,-0.02129150277847147,1739502644.1028664,4.499995708465576,6.254399592491855,1739502644.1028676,4.499995708465576,2.1232373219309753 +1739502644.1225054,4.51999568939209,7.032292593177704,1739502644.1225078,4.51999568939209,-0.21389326060200275,1739502644.1225107,4.51999568939209,6.208885022174687,1739502644.1225133,4.51999568939209,12.449477714234202,1739502644.1225147,4.51999568939209,-0.153,1739502644.1225164,4.51999568939209,0.011240283416738182,1739502644.1225178,4.51999568939209,0.21678404450841865,1739502644.122519,4.51999568939209,0.056719782553635245,1739502644.1225202,4.51999568939209,2.101945819152504,1739502644.1225219,4.51999568939209,0.0,1739502644.1225233,4.51999568939209,-0.02129150277847147,1739502644.1225247,4.51999568939209,6.254399592491855,1739502644.122526,4.51999568939209,2.1232373219309753 +1739502644.142945,4.5399956703186035,7.032292593177704,1739502644.142947,4.5399956703186035,-0.21389326060200275,1739502644.1429498,4.5399956703186035,6.208885022174687,1739502644.1429524,4.5399956703186035,12.449477714234202,1739502644.1429536,4.5399956703186035,-0.153,1739502644.1429553,4.5399956703186035,0.011240283416738182,1739502644.1429565,4.5399956703186035,0.21678404450841865,1739502644.142958,4.5399956703186035,0.056719782553635245,1739502644.142959,4.5399956703186035,2.101945819152504,1739502644.1429605,4.5399956703186035,0.0,1739502644.142962,4.5399956703186035,-0.02129150277847147,1739502644.1429632,4.5399956703186035,6.254399592491855,1739502644.1429648,4.5399956703186035,2.1232373219309753 +1739502644.1638436,4.559995651245117,7.032292593177704,1739502644.1638474,4.559995651245117,-0.21389326060200275,1739502644.1638522,4.559995651245117,6.208885022174687,1739502644.163858,4.559995651245117,12.449477714234202,1739502644.163861,4.559995651245117,-0.153,1739502644.163865,4.559995651245117,0.011240283416738182,1739502644.1638687,4.559995651245117,0.21678404450841865,1739502644.1638725,4.559995651245117,0.056719782553635245,1739502644.163876,4.559995651245117,2.101945819152504,1739502644.1638799,4.559995651245117,0.0,1739502644.1638834,4.559995651245117,-0.02129150277847147,1739502644.163887,4.559995651245117,6.254399592491855,1739502644.1638906,4.559995651245117,2.1232373219309753 +1739502644.1839767,4.579995632171631,7.2656379834310965,1739502644.18398,4.579995632171631,-0.22053168588505034,1739502644.1839852,4.579995632171631,6.408571955940202,1739502644.1839905,4.579995632171631,12.644503086290456,1739502644.1839936,4.579995632171631,-0.15432885663324736,1739502644.1839976,4.579995632171631,0.012307333491577834,1739502644.1840012,4.579995632171631,0.21691455984368258,1739502644.1840048,4.579995632171631,0.05756380992177493,1739502644.1840084,4.579995632171631,2.101726361679095,1739502644.184012,4.579995632171631,0.0,1739502644.1840155,4.579995632171631,-0.018224297420048476,1739502644.1840196,4.579995632171631,6.255157560389752,1739502644.1840231,4.579995632171631,2.1209091614020936 +1739502644.211412,4.5999956130981445,7.2656379834310965,1739502644.2114248,4.5999956130981445,-0.22053168588505034,1739502644.2114415,4.5999956130981445,6.408571955940202,1739502644.211461,4.5999956130981445,12.644503086290456,1739502644.2114718,4.5999956130981445,-0.15432885663324736,1739502644.211486,4.5999956130981445,0.012307333491577834,1739502644.2114987,4.5999956130981445,0.21691455984368258,1739502644.2115114,4.5999956130981445,0.05756380992177493,1739502644.2115238,4.5999956130981445,2.101726361679095,1739502644.211537,4.5999956130981445,0.0,1739502644.2115498,4.5999956130981445,-0.019182799722998745,1739502644.2115624,4.5999956130981445,6.255157560389752,1739502644.2115753,4.5999956130981445,2.1209091614020936 +1739502644.2277067,4.619995594024658,7.2656379834310965,1739502644.227711,4.619995594024658,-0.22053168588505034,1739502644.2277172,4.619995594024658,6.408571955940202,1739502644.2277243,4.619995594024658,12.644503086290456,1739502644.2277281,4.619995594024658,-0.15432885663324736,1739502644.2277336,4.619995594024658,0.012307333491577834,1739502644.2277381,4.619995594024658,0.21691455984368258,1739502644.2277427,4.619995594024658,0.05756380992177493,1739502644.2277474,4.619995594024658,2.101726361679095,1739502644.2277522,4.619995594024658,0.0,1739502644.2277567,4.619995594024658,-0.019182799722998745,1739502644.2277615,4.619995594024658,6.255157560389752,1739502644.2277663,4.619995594024658,2.1209091614020936 +1739502644.2442465,4.639995574951172,7.2656379834310965,1739502644.24425,4.639995574951172,-0.22053168588505034,1739502644.2442544,4.639995574951172,6.408571955940202,1739502644.2442594,4.639995574951172,12.644503086290456,1739502644.244262,4.639995574951172,-0.15432885663324736,1739502644.2442656,4.639995574951172,0.012307333491577834,1739502644.2442687,4.639995574951172,0.21691455984368258,1739502644.2442718,4.639995574951172,0.05756380992177493,1739502644.2442749,4.639995574951172,2.101726361679095,1739502644.244278,4.639995574951172,0.0,1739502644.2442813,4.639995574951172,-0.019182799722998745,1739502644.2442844,4.639995574951172,6.255157560389752,1739502644.2442877,4.639995574951172,2.1209091614020936 +1739502644.2642074,4.6599955558776855,7.2656379834310965,1739502644.2642107,4.6599955558776855,-0.22053168588505034,1739502644.2642148,4.6599955558776855,6.408571955940202,1739502644.2642193,4.6599955558776855,12.644503086290456,1739502644.264222,4.6599955558776855,-0.15432885663324736,1739502644.2642255,4.6599955558776855,0.012307333491577834,1739502644.2642286,4.6599955558776855,0.21691455984368258,1739502644.2642317,4.6599955558776855,0.05756380992177493,1739502644.2642345,4.6599955558776855,2.101726361679095,1739502644.2642379,4.6599955558776855,0.0,1739502644.264241,4.6599955558776855,-0.019182799722998745,1739502644.264244,4.6599955558776855,6.255157560389752,1739502644.264247,4.6599955558776855,2.1209091614020936 +1739502644.2839303,4.679995536804199,7.2656379834310965,1739502644.2839336,4.679995536804199,-0.22053168588505034,1739502644.283938,4.679995536804199,6.408571955940202,1739502644.2839432,4.679995536804199,12.644503086290456,1739502644.2839458,4.679995536804199,-0.15432885663324736,1739502644.2839494,4.679995536804199,0.012307333491577834,1739502644.2839527,4.679995536804199,0.21691455984368258,1739502644.283956,4.679995536804199,0.05756380992177493,1739502644.2839592,4.679995536804199,2.101726361679095,1739502644.2839622,4.679995536804199,0.0,1739502644.2839656,4.679995536804199,-0.019182799722998745,1739502644.283969,4.679995536804199,6.255157560389752,1739502644.2839723,4.679995536804199,2.1209091614020936 +1739502644.3037806,4.699995517730713,7.498745235178198,1739502644.3037837,4.699995517730713,-0.22698650765050665,1739502644.3037882,4.699995517730713,6.941762970837709,1739502644.303793,4.699995517730713,13.173519302650336,1739502644.3037953,4.699995517730713,-0.157,1739502644.3037992,4.699995517730713,0.01233229002734548,1739502644.303802,4.699995517730713,0.22469114192905285,1739502644.303805,4.699995517730713,0.05357199287665603,1739502644.3038082,4.699995517730713,2.0886915521692133,1739502644.3038113,4.699995517730713,0.0,1739502644.3038144,4.699995517730713,-0.035115060773246325,1739502644.3038175,4.699995517730713,6.255915528287648,1739502644.3038206,4.699995517730713,2.1188277780998788 +1739502644.3238275,4.719995498657227,7.498745235178198,1739502644.3238313,4.719995498657227,-0.22698650765050665,1739502644.3238354,4.719995498657227,6.941762970837709,1739502644.3238401,4.719995498657227,13.173519302650336,1739502644.3238428,4.719995498657227,-0.157,1739502644.323846,4.719995498657227,0.01233229002734548,1739502644.3238494,4.719995498657227,0.22469114192905285,1739502644.3238525,4.719995498657227,0.05357199287665603,1739502644.3238556,4.719995498657227,2.0886915521692133,1739502644.3238587,4.719995498657227,0.0,1739502644.3238618,4.719995498657227,-0.03013622593066545,1739502644.3238652,4.719995498657227,6.255915528287648,1739502644.3238683,4.719995498657227,2.1188277780998788 +1739502644.3441956,4.73999547958374,7.498745235178198,1739502644.3441987,4.73999547958374,-0.22698650765050665,1739502644.344203,4.73999547958374,6.941762970837709,1739502644.3442082,4.73999547958374,13.173519302650336,1739502644.3442106,4.73999547958374,-0.157,1739502644.3442144,4.73999547958374,0.01233229002734548,1739502644.3442175,4.73999547958374,0.22469114192905285,1739502644.3442209,4.73999547958374,0.05357199287665603,1739502644.3442242,4.73999547958374,2.0886915521692133,1739502644.3442273,4.73999547958374,0.0,1739502644.3442307,4.73999547958374,-0.03013622593066545,1739502644.344234,4.73999547958374,6.255915528287648,1739502644.3442373,4.73999547958374,2.1188277780998788 +1739502644.363713,4.759995460510254,7.498745235178198,1739502644.3637164,4.759995460510254,-0.22698650765050665,1739502644.3637207,4.759995460510254,6.941762970837709,1739502644.363726,4.759995460510254,13.173519302650336,1739502644.3637285,4.759995460510254,-0.157,1739502644.3637323,4.759995460510254,0.01233229002734548,1739502644.3637354,4.759995460510254,0.22469114192905285,1739502644.3637385,4.759995460510254,0.05357199287665603,1739502644.3637419,4.759995460510254,2.0886915521692133,1739502644.3637452,4.759995460510254,0.0,1739502644.3637483,4.759995460510254,-0.03013622593066545,1739502644.3637516,4.759995460510254,6.255915528287648,1739502644.363755,4.759995460510254,2.1188277780998788 +1739502644.383596,4.779995441436768,7.498745235178198,1739502644.3835993,4.779995441436768,-0.22698650765050665,1739502644.3836038,4.779995441436768,6.941762970837709,1739502644.3836088,4.779995441436768,13.173519302650336,1739502644.3836114,4.779995441436768,-0.157,1739502644.383615,4.779995441436768,0.01233229002734548,1739502644.3836184,4.779995441436768,0.22469114192905285,1739502644.3836217,4.779995441436768,0.05357199287665603,1739502644.3836248,4.779995441436768,2.0886915521692133,1739502644.3836281,4.779995441436768,0.0,1739502644.3836315,4.779995441436768,-0.03013622593066545,1739502644.3836348,4.779995441436768,6.255915528287648,1739502644.383638,4.779995441436768,2.1188277780998788 +1739502644.4113104,4.799995422363281,7.731569238083926,1739502644.411323,4.799995422363281,-0.23325689011528006,1739502644.41134,4.799995422363281,6.955738681394517,1739502644.41136,4.799995422363281,13.18091884371748,1739502644.411371,4.799995422363281,-0.157,1739502644.411385,4.799995422363281,0.01399284658570403,1739502644.411398,4.799995422363281,0.22068529515644425,1739502644.4114103,4.799995422363281,0.057056859965651685,1739502644.4114232,4.799995422363281,2.095395871672702,1739502644.4114363,4.799995422363281,0.0,1739502644.4114492,4.799995422363281,-0.015601815419695318,1739502644.4114618,4.799995422363281,6.256673496185545,1739502644.411475,4.799995422363281,2.1155396933550468 +1739502644.4278605,4.809995412826538,7.731569238083926,1739502644.4278662,4.809995412826538,-0.23325689011528006,1739502644.4278736,4.809995412826538,6.955738681394517,1739502644.4278817,4.809995412826538,13.18091884371748,1739502644.4278862,4.809995412826538,-0.157,1739502644.4278924,4.809995412826538,0.01399284658570403,1739502644.427898,4.809995412826538,0.22068529515644425,1739502644.4279034,4.809995412826538,0.057056859965651685,1739502644.427909,4.809995412826538,2.095395871672702,1739502644.4279144,4.809995412826538,0.0,1739502644.4279199,4.809995412826538,-0.020143821682344853,1739502644.4279253,4.809995412826538,6.256673496185545,1739502644.4279308,4.809995412826538,2.1155396933550468 +1739502644.444393,4.839995384216309,7.731569238083926,1739502644.444396,4.839995384216309,-0.23325689011528006,1739502644.4443994,4.839995384216309,6.955738681394517,1739502644.4444022,4.839995384216309,13.18091884371748,1739502644.4444034,4.839995384216309,-0.157,1739502644.4444053,4.839995384216309,0.01399284658570403,1739502644.4444067,4.839995384216309,0.22068529515644425,1739502644.4444087,4.839995384216309,0.057056859965651685,1739502644.4444098,4.839995384216309,2.095395871672702,1739502644.4444113,4.839995384216309,0.0,1739502644.4444127,4.839995384216309,-0.020143821682344853,1739502644.4444141,4.839995384216309,6.256673496185545,1739502644.4444158,4.839995384216309,2.1155396933550468 +1739502644.4640129,4.859995365142822,7.731569238083926,1739502644.464016,4.859995365142822,-0.23325689011528006,1739502644.4640193,4.859995365142822,6.955738681394517,1739502644.4640222,4.859995365142822,13.18091884371748,1739502644.464024,4.859995365142822,-0.157,1739502644.4640262,4.859995365142822,0.01399284658570403,1739502644.4640281,4.859995365142822,0.22068529515644425,1739502644.4640298,4.859995365142822,0.057056859965651685,1739502644.4640312,4.859995365142822,2.095395871672702,1739502644.4640334,4.859995365142822,0.0,1739502644.4640348,4.859995365142822,-0.020143821682344853,1739502644.4640365,4.859995365142822,6.256673496185545,1739502644.464038,4.859995365142822,2.1155396933550468 +1739502644.484164,4.879995346069336,7.731569238083926,1739502644.4841664,4.879995346069336,-0.23325689011528006,1739502644.484169,4.879995346069336,6.955738681394517,1739502644.4841716,4.879995346069336,13.18091884371748,1739502644.4841728,4.879995346069336,-0.157,1739502644.4841745,4.879995346069336,0.01399284658570403,1739502644.484176,4.879995346069336,0.22068529515644425,1739502644.484177,4.879995346069336,0.057056859965651685,1739502644.4841785,4.879995346069336,2.095395871672702,1739502644.48418,4.879995346069336,0.0,1739502644.4841812,4.879995346069336,-0.020143821682344853,1739502644.4841826,4.879995346069336,6.256673496185545,1739502644.4841838,4.879995346069336,2.1155396933550468 +1739502644.5043588,4.89999532699585,7.731569238083926,1739502644.5043616,4.89999532699585,-0.23325689011528006,1739502644.5043662,4.89999532699585,6.955738681394517,1739502644.504371,4.89999532699585,13.18091884371748,1739502644.5043738,4.89999532699585,-0.157,1739502644.5043774,4.89999532699585,0.01399284658570403,1739502644.5043805,4.89999532699585,0.22068529515644425,1739502644.5043838,4.89999532699585,0.057056859965651685,1739502644.5043871,4.89999532699585,2.095395871672702,1739502644.5043905,4.89999532699585,0.0,1739502644.5043938,4.89999532699585,-0.020143821682344853,1739502644.504397,4.89999532699585,6.256673496185545,1739502644.5044,4.89999532699585,2.1155396933550468 +1739502644.5240657,4.919995307922363,7.964093006505637,1739502644.5240679,4.919995307922363,-0.23934280888091575,1739502644.5240705,4.919995307922363,7.283932910823044,1739502644.524073,4.919995307922363,13.50478488064978,1739502644.5240743,4.919995307922363,-0.159,1739502644.5240757,4.919995307922363,0.014499484962345252,1739502644.524077,4.919995307922363,0.22299450205148594,1739502644.5240784,4.919995307922363,0.05576812467874796,1739502644.5240796,4.919995307922363,2.091528482937101,1739502644.5240812,4.919995307922363,0.0,1739502644.5240824,4.919995307922363,-0.022626394581131064,1739502644.5240839,4.919995307922363,6.257431464083442,1739502644.5240855,4.919995307922363,2.113379072978704 +1739502644.5455108,4.939995288848877,7.964093006505637,1739502644.5455136,4.939995288848877,-0.23934280888091575,1739502644.5455182,4.939995288848877,7.283932910823044,1739502644.5455232,4.939995288848877,13.50478488064978,1739502644.5455258,4.939995288848877,-0.159,1739502644.5455294,4.939995288848877,0.014499484962345252,1739502644.5455327,4.939995288848877,0.22299450205148594,1739502644.545536,4.939995288848877,0.05576812467874796,1739502644.5455391,4.939995288848877,2.091528482937101,1739502644.5455425,4.939995288848877,0.0,1739502644.5455458,4.939995288848877,-0.02185059004160328,1739502644.5455492,4.939995288848877,6.257431464083442,1739502644.5455525,4.939995288848877,2.113379072978704 +1739502644.5643494,4.959995269775391,7.964093006505637,1739502644.5643523,4.959995269775391,-0.23934280888091575,1739502644.5643556,4.959995269775391,7.283932910823044,1739502644.564359,4.959995269775391,13.50478488064978,1739502644.5643604,4.959995269775391,-0.159,1739502644.5643625,4.959995269775391,0.014499484962345252,1739502644.564364,4.959995269775391,0.22299450205148594,1739502644.5643656,4.959995269775391,0.05576812467874796,1739502644.564367,4.959995269775391,2.091528482937101,1739502644.564369,4.959995269775391,0.0,1739502644.5643704,4.959995269775391,-0.02185059004160328,1739502644.564372,4.959995269775391,6.257431464083442,1739502644.5643735,4.959995269775391,2.113379072978704 +1739502644.5846045,4.979995250701904,7.964093006505637,1739502644.584609,4.979995250701904,-0.23934280888091575,1739502644.584615,4.979995250701904,7.283932910823044,1739502644.584622,4.979995250701904,13.50478488064978,1739502644.5846257,4.979995250701904,-0.159,1739502644.5846305,4.979995250701904,0.014499484962345252,1739502644.584635,4.979995250701904,0.22299450205148594,1739502644.5846395,4.979995250701904,0.05576812467874796,1739502644.5846438,4.979995250701904,2.091528482937101,1739502644.5846481,4.979995250701904,0.0,1739502644.584653,4.979995250701904,-0.02185059004160328,1739502644.5846572,4.979995250701904,6.257431464083442,1739502644.5846617,4.979995250701904,2.113379072978704 +1739502644.604714,4.999995231628418,7.964093006505637,1739502644.6047168,4.999995231628418,-0.23934280888091575,1739502644.6047204,4.999995231628418,7.283932910823044,1739502644.604724,4.999995231628418,13.50478488064978,1739502644.6047258,4.999995231628418,-0.159,1739502644.6047277,4.999995231628418,0.014499484962345252,1739502644.6047297,4.999995231628418,0.22299450205148594,1739502644.6047313,4.999995231628418,0.05576812467874796,1739502644.604733,4.999995231628418,2.091528482937101,1739502644.604735,4.999995231628418,0.0,1739502644.6047368,4.999995231628418,-0.02185059004160328,1739502644.6047385,4.999995231628418,6.257431464083442,1739502644.6047404,4.999995231628418,2.113379072978704 +1739502644.625246,5.019995212554932,8.196370433155991,1739502644.6252494,5.019995212554932,-0.24524610559101578,1739502644.625254,5.019995212554932,7.30739883421144,1739502644.6252575,5.019995212554932,13.523472769899588,1739502644.6252592,5.019995212554932,-0.159,1739502644.6252618,5.019995212554932,0.016188645490771484,1739502644.625264,5.019995212554932,0.21936088379263605,1739502644.6252654,5.019995212554932,0.059342775736297676,1739502644.6252675,5.019995212554932,2.0976171811191833,1739502644.6252697,5.019995212554932,0.0,1739502644.6252713,5.019995212554932,-0.009519364182787652,1739502644.6252732,5.019995212554932,6.258189431981339,1739502644.6252756,5.019995212554932,2.1109900559094092 +1739502644.6446164,5.039995193481445,8.196370433155991,1739502644.6446192,5.039995193481445,-0.24524610559101578,1739502644.6446228,5.039995193481445,7.30739883421144,1739502644.6446264,5.039995193481445,13.523472769899588,1739502644.644628,5.039995193481445,-0.159,1739502644.64463,5.039995193481445,0.016188645490771484,1739502644.6446319,5.039995193481445,0.21936088379263605,1739502644.6446338,5.039995193481445,0.059342775736297676,1739502644.6446354,5.039995193481445,2.0976171811191833,1739502644.6446373,5.039995193481445,0.0,1739502644.644639,5.039995193481445,-0.013372874790225975,1739502644.644641,5.039995193481445,6.258189431981339,1739502644.6446428,5.039995193481445,2.1109900559094092 +1739502644.6646316,5.059995174407959,8.196370433155991,1739502644.664636,5.059995174407959,-0.24524610559101578,1739502644.664642,5.059995174407959,7.30739883421144,1739502644.664649,5.059995174407959,13.523472769899588,1739502644.6646526,5.059995174407959,-0.159,1739502644.6646574,5.059995174407959,0.016188645490771484,1739502644.6646621,5.059995174407959,0.21936088379263605,1739502644.6646664,5.059995174407959,0.059342775736297676,1739502644.6646807,5.059995174407959,2.0976171811191833,1739502644.6646833,5.059995174407959,0.0,1739502644.664685,5.059995174407959,-0.013372874790225975,1739502644.664687,5.059995174407959,6.258189431981339,1739502644.6646886,5.059995174407959,2.1109900559094092 +1739502644.6846297,5.079995155334473,8.196370433155991,1739502644.6846342,5.079995155334473,-0.24524610559101578,1739502644.68464,5.079995155334473,7.30739883421144,1739502644.6846468,5.079995155334473,13.523472769899588,1739502644.6846507,5.079995155334473,-0.159,1739502644.6846557,5.079995155334473,0.016188645490771484,1739502644.68466,5.079995155334473,0.21936088379263605,1739502644.6846645,5.079995155334473,0.059342775736297676,1739502644.684669,5.079995155334473,2.0976171811191833,1739502644.6846836,5.079995155334473,0.0,1739502644.6846855,5.079995155334473,-0.013372874790225975,1739502644.6846874,5.079995155334473,6.258189431981339,1739502644.684689,5.079995155334473,2.1109900559094092 +1739502644.7045672,5.099995136260986,8.196370433155991,1739502644.70457,5.099995136260986,-0.24524610559101578,1739502644.7045736,5.099995136260986,7.30739883421144,1739502644.7045772,5.099995136260986,13.523472769899588,1739502644.704579,5.099995136260986,-0.159,1739502644.704581,5.099995136260986,0.016188645490771484,1739502644.7045832,5.099995136260986,0.21936088379263605,1739502644.704585,5.099995136260986,0.059342775736297676,1739502644.7045865,5.099995136260986,2.0976171811191833,1739502644.7045887,5.099995136260986,0.0,1739502644.70459,5.099995136260986,-0.013372874790225975,1739502644.7045922,5.099995136260986,6.258189431981339,1739502644.704594,5.099995136260986,2.1109900559094092 +1739502644.725649,5.1199951171875,8.196370433155991,1739502644.7256525,5.1199951171875,-0.24524610559101578,1739502644.7256563,5.1199951171875,7.30739883421144,1739502644.7256594,5.1199951171875,13.523472769899588,1739502644.7256613,5.1199951171875,-0.159,1739502644.7256632,5.1199951171875,0.016188645490771484,1739502644.725665,5.1199951171875,0.21936088379263605,1739502644.7256668,5.1199951171875,0.059342775736297676,1739502644.7256684,5.1199951171875,2.0976171811191833,1739502644.7256703,5.1199951171875,0.0,1739502644.7256722,5.1199951171875,-0.013372874790225975,1739502644.725674,5.1199951171875,6.258189431981339,1739502644.725676,5.1199951171875,2.1109900559094092 +1739502644.7458823,5.139995098114014,8.428442919754117,1739502644.7458854,5.139995098114014,-0.25096111235751195,1739502644.7458892,5.139995098114014,7.69748865695159,1739502644.745893,5.139995098114014,13.910782457875488,1739502644.7458947,5.139995098114014,-0.16,1739502644.745897,5.139995098114014,0.01659013755268527,1739502644.7458985,5.139995098114014,0.22339455727393673,1739502644.7459006,5.139995098114014,0.05705977276026293,1739502644.745902,5.139995098114014,2.0908592085274997,1739502644.7459042,5.139995098114014,0.0,1739502644.7459056,5.139995098114014,-0.021183957199021036,1739502644.7459075,5.139995098114014,6.259021738184658,1739502644.7459095,5.139995098114014,2.109602200873351 +1739502644.765435,5.159995079040527,8.428442919754117,1739502644.7654378,5.159995079040527,-0.25096111235751195,1739502644.7654414,5.159995079040527,7.69748865695159,1739502644.7654448,5.159995079040527,13.910782457875488,1739502644.7654467,5.159995079040527,-0.16,1739502644.7654488,5.159995079040527,0.01659013755268527,1739502644.7654505,5.159995079040527,0.22339455727393673,1739502644.7654524,5.159995079040527,0.05705977276026293,1739502644.7654538,5.159995079040527,2.0908592085274997,1739502644.765456,5.159995079040527,0.0,1739502644.7654576,5.159995079040527,-0.018742992345851306,1739502644.7654595,5.159995079040527,6.259021738184658,1739502644.7654612,5.159995079040527,2.109602200873351 +1739502644.7853045,5.179995059967041,8.428442919754117,1739502644.7853076,5.179995059967041,-0.25096111235751195,1739502644.7853115,5.179995059967041,7.69748865695159,1739502644.7853148,5.179995059967041,13.910782457875488,1739502644.7853167,5.179995059967041,-0.16,1739502644.7853189,5.179995059967041,0.01659013755268527,1739502644.7853208,5.179995059967041,0.22339455727393673,1739502644.7853222,5.179995059967041,0.05705977276026293,1739502644.785324,5.179995059967041,2.0908592085274997,1739502644.785326,5.179995059967041,0.0,1739502644.7853277,5.179995059967041,-0.018742992345851306,1739502644.7853296,5.179995059967041,6.259021738184658,1739502644.7853317,5.179995059967041,2.109602200873351 +1739502644.8053737,5.199995040893555,8.428442919754117,1739502644.8053768,5.199995040893555,-0.25096111235751195,1739502644.8053806,5.199995040893555,7.69748865695159,1739502644.8053844,5.199995040893555,13.910782457875488,1739502644.8053863,5.199995040893555,-0.16,1739502644.8053882,5.199995040893555,0.01659013755268527,1739502644.8053901,5.199995040893555,0.22339455727393673,1739502644.8053918,5.199995040893555,0.05705977276026293,1739502644.8053935,5.199995040893555,2.0908592085274997,1739502644.8053954,5.199995040893555,0.0,1739502644.8053973,5.199995040893555,-0.018742992345851306,1739502644.805399,5.199995040893555,6.259021738184658,1739502644.805401,5.199995040893555,2.109602200873351 +1739502644.8265033,5.219995021820068,8.428442919754117,1739502644.8265076,5.219995021820068,-0.25096111235751195,1739502644.826514,5.219995021820068,7.69748865695159,1739502644.826521,5.219995021820068,13.910782457875488,1739502644.8265245,5.219995021820068,-0.16,1739502644.8265295,5.219995021820068,0.01659013755268527,1739502644.8265338,5.219995021820068,0.22339455727393673,1739502644.8265383,5.219995021820068,0.05705977276026293,1739502644.8265426,5.219995021820068,2.0908592085274997,1739502644.8265471,5.219995021820068,0.0,1739502644.8265514,5.219995021820068,-0.018742992345851306,1739502644.8265562,5.219995021820068,6.259021738184658,1739502644.8265607,5.219995021820068,2.109602200873351 +1739502644.8467653,5.239995002746582,8.660332101796328,1739502644.8467696,5.239995002746582,-0.25647692627286833,1739502644.8467755,5.239995002746582,8.091849450626789,1739502644.8467824,5.239995002746582,14.301042759350198,1739502644.8467863,5.239995002746582,-0.162,1739502644.8467915,5.239995002746582,0.016747551658780183,1739502644.8467958,5.239995002746582,0.22600227218898358,1739502644.8468003,5.239995002746582,0.054530154695777475,1739502644.8468046,5.239995002746582,2.0865018633986856,1739502644.8468094,5.239995002746582,0.0,1739502644.8468137,5.239995002746582,-0.022104637244850223,1739502644.8468182,5.239995002746582,6.25986147821852,1739502644.846823,5.239995002746582,2.1075559859238275 +1739502644.8726451,5.259994983673096,8.660332101796328,1739502644.8726528,5.259994983673096,-0.25647692627286833,1739502644.8726623,5.259994983673096,8.091849450626789,1739502644.8726885,5.259994983673096,14.301042759350198,1739502644.8726962,5.259994983673096,-0.162,1739502644.8727047,5.259994983673096,0.016747551658780183,1739502644.872712,5.259994983673096,0.22600227218898358,1739502644.8727193,5.259994983673096,0.054530154695777475,1739502644.8727262,5.259994983673096,2.0865018633986856,1739502644.8727336,5.259994983673096,0.0,1739502644.8727407,5.259994983673096,-0.02105412252514194,1739502644.8727484,5.259994983673096,6.25986147821852,1739502644.8727555,5.259994983673096,2.1075559859238275 +1739502644.886667,5.279994964599609,8.660332101796328,1739502644.8866718,5.279994964599609,-0.25647692627286833,1739502644.8866785,5.279994964599609,8.091849450626789,1739502644.8866858,5.279994964599609,14.301042759350198,1739502644.8866901,5.279994964599609,-0.162,1739502644.8866954,5.279994964599609,0.016747551658780183,1739502644.8867,5.279994964599609,0.22600227218898358,1739502644.886705,5.279994964599609,0.054530154695777475,1739502644.8867097,5.279994964599609,2.0865018633986856,1739502644.8867147,5.279994964599609,0.0,1739502644.8867195,5.279994964599609,-0.02105412252514194,1739502644.8867242,5.279994964599609,6.25986147821852,1739502644.8867292,5.279994964599609,2.1075559859238275 +1739502644.9058268,5.299994945526123,8.660332101796328,1739502644.9058304,5.299994945526123,-0.25647692627286833,1739502644.9058344,5.299994945526123,8.091849450626789,1739502644.9058394,5.299994945526123,14.301042759350198,1739502644.9058418,5.299994945526123,-0.162,1739502644.9058452,5.299994945526123,0.016747551658780183,1739502644.9058483,5.299994945526123,0.22600227218898358,1739502644.9058514,5.299994945526123,0.054530154695777475,1739502644.9058545,5.299994945526123,2.0865018633986856,1739502644.9058578,5.299994945526123,0.0,1739502644.905861,5.299994945526123,-0.02105412252514194,1739502644.905864,5.299994945526123,6.25986147821852,1739502644.9058673,5.299994945526123,2.1075559859238275 +1739502644.9264066,5.319994926452637,8.660332101796328,1739502644.9264097,5.319994926452637,-0.25647692627286833,1739502644.9264143,5.319994926452637,8.091849450626789,1739502644.926419,5.319994926452637,14.301042759350198,1739502644.9264214,5.319994926452637,-0.162,1739502644.926425,5.319994926452637,0.016747551658780183,1739502644.926428,5.319994926452637,0.22600227218898358,1739502644.9264312,5.319994926452637,0.054530154695777475,1739502644.9264343,5.319994926452637,2.0865018633986856,1739502644.9264376,5.319994926452637,0.0,1739502644.9264407,5.319994926452637,-0.02105412252514194,1739502644.9264438,5.319994926452637,6.25986147821852,1739502644.926447,5.319994926452637,2.1075559859238275 +1739502644.9456553,5.33999490737915,8.660332101796328,1739502644.9456587,5.33999490737915,-0.25647692627286833,1739502644.9456632,5.33999490737915,8.091849450626789,1739502644.9456685,5.33999490737915,14.301042759350198,1739502644.945671,5.33999490737915,-0.162,1739502644.945675,5.33999490737915,0.016747551658780183,1739502644.9456782,5.33999490737915,0.22600227218898358,1739502644.9456816,5.33999490737915,0.054530154695777475,1739502644.945685,5.33999490737915,2.0865018633986856,1739502644.9456882,5.33999490737915,0.0,1739502644.9456916,5.33999490737915,-0.02105412252514194,1739502644.945695,5.33999490737915,6.25986147821852,1739502644.9456985,5.33999490737915,2.1075559859238275 +1739502644.9658186,5.359994888305664,8.891983971707562,1739502644.965822,5.359994888305664,-0.2617924637860307,1739502644.9658265,5.359994888305664,8.11571490876516,1739502644.965832,5.359994888305664,14.320235079813838,1739502644.9658349,5.359994888305664,-0.162,1739502644.9658387,5.359994888305664,0.018381836406777013,1739502644.9658422,5.359994888305664,0.22180623813934572,1739502644.9658456,5.359994888305664,0.05778493778169059,1739502644.965849,5.359994888305664,2.0935176585075137,1739502644.9658525,5.359994888305664,0.0,1739502644.965856,5.359994888305664,-0.007450680003807038,1739502644.9658594,5.359994888305664,6.260701218252381,1739502644.965863,5.359994888305664,2.105219417086462 +1739502644.9862227,5.379994869232178,8.891983971707562,1739502644.986226,5.379994869232178,-0.2617924637860307,1739502644.986231,5.379994869232178,8.11571490876516,1739502644.986236,5.379994869232178,14.320235079813838,1739502644.986239,5.379994869232178,-0.162,1739502644.986243,5.379994869232178,0.018381836406777013,1739502644.9862466,5.379994869232178,0.22180623813934572,1739502644.98625,5.379994869232178,0.05778493778169059,1739502644.9862533,5.379994869232178,2.0935176585075137,1739502644.9862566,5.379994869232178,0.0,1739502644.9862602,5.379994869232178,-0.011701758578948507,1739502644.9862638,5.379994869232178,6.260701218252381,1739502644.986267,5.379994869232178,2.105219417086462 +1739502645.0133398,5.399994850158691,8.891983971707562,1739502645.013347,5.399994850158691,-0.2617924637860307,1739502645.0133557,5.399994850158691,8.11571490876516,1739502645.0133665,5.399994850158691,14.320235079813838,1739502645.0133724,5.399994850158691,-0.162,1739502645.0133798,5.399994850158691,0.018381836406777013,1739502645.0133865,5.399994850158691,0.22180623813934572,1739502645.0133932,5.399994850158691,0.05778493778169059,1739502645.0133998,5.399994850158691,2.0935176585075137,1739502645.0134068,5.399994850158691,0.0,1739502645.0134137,5.399994850158691,-0.011701758578948507,1739502645.0134206,5.399994850158691,6.260701218252381,1739502645.0134273,5.399994850158691,2.105219417086462 +1739502645.0265703,5.419994831085205,8.891983971707562,1739502645.026575,5.419994831085205,-0.2617924637860307,1739502645.0265813,5.419994831085205,8.11571490876516,1739502645.0265884,5.419994831085205,14.320235079813838,1739502645.0265923,5.419994831085205,-0.162,1739502645.0265973,5.419994831085205,0.018381836406777013,1739502645.0266023,5.419994831085205,0.22180623813934572,1739502645.0266068,5.419994831085205,0.05778493778169059,1739502645.026611,5.419994831085205,2.0935176585075137,1739502645.026616,5.419994831085205,0.0,1739502645.0266206,5.419994831085205,-0.011701758578948507,1739502645.0266254,5.419994831085205,6.260701218252381,1739502645.0266302,5.419994831085205,2.105219417086462 +1739502645.0459998,5.439994812011719,8.891983971707562,1739502645.046003,5.439994812011719,-0.2617924637860307,1739502645.0460076,5.439994812011719,8.11571490876516,1739502645.0460122,5.439994812011719,14.320235079813838,1739502645.0460148,5.439994812011719,-0.162,1739502645.0460184,5.439994812011719,0.018381836406777013,1739502645.0460215,5.439994812011719,0.22180623813934572,1739502645.0460246,5.439994812011719,0.05778493778169059,1739502645.0460274,5.439994812011719,2.0935176585075137,1739502645.0460308,5.439994812011719,0.0,1739502645.0460339,5.439994812011719,-0.011701758578948507,1739502645.0460372,5.439994812011719,6.260701218252381,1739502645.0460403,5.439994812011719,2.105219417086462 +1739502645.0685174,5.459994792938232,9.123435475612741,1739502645.0685232,5.459994792938232,-0.26690893757825407,1739502645.068531,5.459994792938232,8.421010255346957,1739502645.0685399,5.459994792938232,14.622955140256037,1739502645.0685449,5.459994792938232,-0.16210186233763532,1739502645.068551,5.459994792938232,0.019055189573895803,1739502645.0685568,5.459994792938232,0.22380675479346285,1739502645.0685625,5.459994792938232,0.05680352467774418,1739502645.068568,5.459994792938232,2.090169844611838,1739502645.068574,5.459994792938232,0.0,1739502645.06858,5.459994792938232,-0.014698641950024096,1739502645.0685856,5.459994792938232,6.261540958286242,1739502645.0685916,5.459994792938232,2.1039319598943664 +1739502645.086151,5.479994773864746,9.123435475612741,1739502645.0861554,5.479994773864746,-0.26690893757825407,1739502645.0861607,5.479994773864746,8.421010255346957,1739502645.086166,5.479994773864746,14.622955140256037,1739502645.0861692,5.479994773864746,-0.16210186233763532,1739502645.0861735,5.479994773864746,0.019055189573895803,1739502645.0861773,5.479994773864746,0.22380675479346285,1739502645.086181,5.479994773864746,0.05680352467774418,1739502645.0861845,5.479994773864746,2.090169844611838,1739502645.086188,5.479994773864746,0.0,1739502645.086192,5.479994773864746,-0.013762115282528242,1739502645.0861955,5.479994773864746,6.261540958286242,1739502645.0861995,5.479994773864746,2.1039319598943664 +1739502645.1059213,5.49999475479126,9.123435475612741,1739502645.1059244,5.49999475479126,-0.26690893757825407,1739502645.1059282,5.49999475479126,8.421010255346957,1739502645.105933,5.49999475479126,14.622955140256037,1739502645.1059356,5.49999475479126,-0.16210186233763532,1739502645.105939,5.49999475479126,0.019055189573895803,1739502645.1059422,5.49999475479126,0.22380675479346285,1739502645.1059453,5.49999475479126,0.05680352467774418,1739502645.1059482,5.49999475479126,2.090169844611838,1739502645.1059515,5.49999475479126,0.0,1739502645.1059544,5.49999475479126,-0.013762115282528242,1739502645.1059577,5.49999475479126,6.261540958286242,1739502645.1059606,5.49999475479126,2.1039319598943664 +1739502645.1260774,5.519994735717773,9.123435475612741,1739502645.1260805,5.519994735717773,-0.26690893757825407,1739502645.1260846,5.519994735717773,8.421010255346957,1739502645.1260893,5.519994735717773,14.622955140256037,1739502645.126092,5.519994735717773,-0.16210186233763532,1739502645.1260953,5.519994735717773,0.019055189573895803,1739502645.1260984,5.519994735717773,0.22380675479346285,1739502645.1261015,5.519994735717773,0.05680352467774418,1739502645.1261046,5.519994735717773,2.090169844611838,1739502645.1261077,5.519994735717773,0.0,1739502645.1261108,5.519994735717773,-0.013762115282528242,1739502645.126114,5.519994735717773,6.261540958286242,1739502645.1261168,5.519994735717773,2.1039319598943664 +1739502645.1457443,5.539994716644287,9.123435475612741,1739502645.1457474,5.539994716644287,-0.26690893757825407,1739502645.1457515,5.539994716644287,8.421010255346957,1739502645.1457562,5.539994716644287,14.622955140256037,1739502645.1457586,5.539994716644287,-0.16210186233763532,1739502645.1457622,5.539994716644287,0.019055189573895803,1739502645.1457653,5.539994716644287,0.22380675479346285,1739502645.1457684,5.539994716644287,0.05680352467774418,1739502645.1457713,5.539994716644287,2.090169844611838,1739502645.1457744,5.539994716644287,0.0,1739502645.1457775,5.539994716644287,-0.013762115282528242,1739502645.1457806,5.539994716644287,6.261540958286242,1739502645.145784,5.539994716644287,2.1039319598943664 +1739502645.1657982,5.559994697570801,9.123435475612741,1739502645.1658015,5.559994697570801,-0.26690893757825407,1739502645.165806,5.559994697570801,8.421010255346957,1739502645.1658113,5.559994697570801,14.622955140256037,1739502645.165814,5.559994697570801,-0.16210186233763532,1739502645.1658177,5.559994697570801,0.019055189573895803,1739502645.165821,5.559994697570801,0.22380675479346285,1739502645.1658244,5.559994697570801,0.05680352467774418,1739502645.1658275,5.559994697570801,2.090169844611838,1739502645.165831,5.559994697570801,0.0,1739502645.1658344,5.559994697570801,-0.013762115282528242,1739502645.1658378,5.559994697570801,6.261540958286242,1739502645.1658413,5.559994697570801,2.1039319598943664 +1739502645.1861846,5.5799946784973145,9.354738432921286,1739502645.1861887,5.5799946784973145,-0.27182780404831774,1739502645.186195,5.5799946784973145,8.728832484960531,1739502645.1862009,5.5799946784973145,14.927720668771697,1739502645.1862042,5.5799946784973145,-0.16358017972844954,1739502645.1862085,5.5799946784973145,0.019421202091202537,1739502645.1862123,5.5799946784973145,0.2241595504190188,1739502645.1862159,5.5799946784973145,0.0554025755651565,1739502645.1862197,5.5799946784973145,2.0895800056305203,1739502645.1862235,5.5799946784973145,0.0,1739502645.1862278,5.5799946784973145,-0.012401225545035617,1739502645.1862316,5.5799946784973145,6.262380698320103,1739502645.1862354,5.5799946784973145,2.1024065094973565 +1739502645.2056,5.599994659423828,9.354738432921286,1739502645.2056031,5.599994659423828,-0.27182780404831774,1739502645.2056077,5.599994659423828,8.728832484960531,1739502645.2056127,5.599994659423828,14.927720668771697,1739502645.2056153,5.599994659423828,-0.16358017972844954,1739502645.205619,5.599994659423828,0.019421202091202537,1739502645.2056224,5.599994659423828,0.2241595504190188,1739502645.2056258,5.599994659423828,0.0554025755651565,1739502645.205629,5.599994659423828,2.0895800056305203,1739502645.2056324,5.599994659423828,0.0,1739502645.2056358,5.599994659423828,-0.012826503866836259,1739502645.2056391,5.599994659423828,6.262380698320103,1739502645.2056427,5.599994659423828,2.1024065094973565 +1739502645.226915,5.619994640350342,9.354738432921286,1739502645.2269182,5.619994640350342,-0.27182780404831774,1739502645.2269225,5.619994640350342,8.728832484960531,1739502645.2269273,5.619994640350342,14.927720668771697,1739502645.2269301,5.619994640350342,-0.16358017972844954,1739502645.2269337,5.619994640350342,0.019421202091202537,1739502645.2269368,5.619994640350342,0.2241595504190188,1739502645.2269402,5.619994640350342,0.0554025755651565,1739502645.2269435,5.619994640350342,2.0895800056305203,1739502645.2269468,5.619994640350342,0.0,1739502645.2269502,5.619994640350342,-0.012826503866836259,1739502645.2269535,5.619994640350342,6.262380698320103,1739502645.2269568,5.619994640350342,2.1024065094973565 +1739502645.2456312,5.6399946212768555,9.354738432921286,1739502645.2456346,5.6399946212768555,-0.27182780404831774,1739502645.2456388,5.6399946212768555,8.728832484960531,1739502645.245644,5.6399946212768555,14.927720668771697,1739502645.245647,5.6399946212768555,-0.16358017972844954,1739502645.2456508,5.6399946212768555,0.019421202091202537,1739502645.245654,5.6399946212768555,0.2241595504190188,1739502645.2456574,5.6399946212768555,0.0554025755651565,1739502645.2456603,5.6399946212768555,2.0895800056305203,1739502645.245664,5.6399946212768555,0.0,1739502645.2456672,5.6399946212768555,-0.012826503866836259,1739502645.2456706,5.6399946212768555,6.262380698320103,1739502645.2456741,5.6399946212768555,2.1024065094973565 +1739502645.265676,5.659994602203369,9.354738432921286,1739502645.2656791,5.659994602203369,-0.27182780404831774,1739502645.2656834,5.659994602203369,8.728832484960531,1739502645.2656884,5.659994602203369,14.927720668771697,1739502645.265691,5.659994602203369,-0.16358017972844954,1739502645.2656946,5.659994602203369,0.019421202091202537,1739502645.265698,5.659994602203369,0.2241595504190188,1739502645.265701,5.659994602203369,0.0554025755651565,1739502645.2657044,5.659994602203369,2.0895800056305203,1739502645.2657077,5.659994602203369,0.0,1739502645.2657108,5.659994602203369,-0.012826503866836259,1739502645.2657142,5.659994602203369,6.262380698320103,1739502645.2657175,5.659994602203369,2.1024065094973565 +1739502645.2857907,5.679994583129883,9.585884505922996,1739502645.2857938,5.679994583129883,-0.2765491463508507,1739502645.285798,5.679994583129883,8.753338690041014,1739502645.2858033,5.679994583129883,14.949418293664692,1739502645.2858062,5.679994583129883,-0.16376885472751906,1739502645.2858098,5.679994583129883,0.021024137958186633,1739502645.285813,5.679994583129883,0.2198329503808182,1739502645.285816,5.679994583129883,0.05865494673137937,1739502645.2858193,5.679994583129883,2.0968251586947235,1739502645.2858226,5.679994583129883,0.0,1739502645.2858257,5.679994583129883,-0.00024608847734599194,1739502645.285829,5.679994583129883,6.263220438353964,1739502645.2858324,5.679994583129883,2.1010026295589004 +1739502645.3123095,5.6999945640563965,9.585884505922996,1739502645.3123186,5.6999945640563965,-0.2765491463508507,1739502645.3123302,5.6999945640563965,8.753338690041014,1739502645.312358,5.6999945640563965,14.949418293664692,1739502645.312364,5.6999945640563965,-0.16376885472751906,1739502645.3123715,5.6999945640563965,0.021024137958186633,1739502645.3123782,5.6999945640563965,0.2198329503808182,1739502645.3123848,5.6999945640563965,0.05865494673137937,1739502645.3123915,5.6999945640563965,2.0968251586947235,1739502645.3123984,5.6999945640563965,0.0,1739502645.312405,5.6999945640563965,-0.004177470864176858,1739502645.3124118,5.6999945640563965,6.263220438353964,1739502645.3124187,5.6999945640563965,2.1010026295589004 +1739502645.326541,5.71999454498291,9.585884505922996,1739502645.3265457,5.71999454498291,-0.2765491463508507,1739502645.326552,5.71999454498291,8.753338690041014,1739502645.326559,5.71999454498291,14.949418293664692,1739502645.326563,5.71999454498291,-0.16376885472751906,1739502645.3265681,5.71999454498291,0.021024137958186633,1739502645.326573,5.71999454498291,0.2198329503808182,1739502645.3265774,5.71999454498291,0.05865494673137937,1739502645.326582,5.71999454498291,2.0968251586947235,1739502645.3265867,5.71999454498291,0.0,1739502645.3265913,5.71999454498291,-0.004177470864176858,1739502645.3265958,5.71999454498291,6.263220438353964,1739502645.3266008,5.71999454498291,2.1010026295589004 +1739502645.3458211,5.739994525909424,9.585884505922996,1739502645.3458245,5.739994525909424,-0.2765491463508507,1739502645.3458285,5.739994525909424,8.753338690041014,1739502645.3458333,5.739994525909424,14.949418293664692,1739502645.3458364,5.739994525909424,-0.16376885472751906,1739502645.3458395,5.739994525909424,0.021024137958186633,1739502645.3458426,5.739994525909424,0.2198329503808182,1739502645.3458457,5.739994525909424,0.05865494673137937,1739502645.3458488,5.739994525909424,2.0968251586947235,1739502645.3458521,5.739994525909424,0.0,1739502645.3458552,5.739994525909424,-0.004177470864176858,1739502645.3458583,5.739994525909424,6.263220438353964,1739502645.3458614,5.739994525909424,2.1010026295589004 +1739502645.3658442,5.7599945068359375,9.585884505922996,1739502645.3658476,5.7599945068359375,-0.2765491463508507,1739502645.3658516,5.7599945068359375,8.753338690041014,1739502645.3658562,5.7599945068359375,14.949418293664692,1739502645.3658588,5.7599945068359375,-0.16376885472751906,1739502645.3658624,5.7599945068359375,0.021024137958186633,1739502645.3658655,5.7599945068359375,0.2198329503808182,1739502645.3658686,5.7599945068359375,0.05865494673137937,1739502645.3658717,5.7599945068359375,2.0968251586947235,1739502645.365875,5.7599945068359375,0.0,1739502645.365878,5.7599945068359375,-0.004177470864176858,1739502645.3658814,5.7599945068359375,6.263220438353964,1739502645.3658843,5.7599945068359375,2.1010026295589004 +1739502645.3862984,5.779994487762451,9.585884505922996,1739502645.386302,5.779994487762451,-0.2765491463508507,1739502645.3863063,5.779994487762451,8.753338690041014,1739502645.3863115,5.779994487762451,14.949418293664692,1739502645.3863142,5.779994487762451,-0.16376885472751906,1739502645.3863177,5.779994487762451,0.021024137958186633,1739502645.3863208,5.779994487762451,0.2198329503808182,1739502645.3863242,5.779994487762451,0.05865494673137937,1739502645.3863275,5.779994487762451,2.0968251586947235,1739502645.3863308,5.779994487762451,0.0,1739502645.386334,5.779994487762451,-0.004177470864176858,1739502645.3863373,5.779994487762451,6.263220438353964,1739502645.3863406,5.779994487762451,2.1010026295589004 +1739502645.4057653,5.799994468688965,9.816935004920976,1739502645.4057686,5.799994468688965,-0.2810744288529632,1739502645.4057732,5.799994468688965,9.159426824247415,1739502645.4057782,5.799994468688965,15.35474648208205,1739502645.4057808,5.799994468688965,-0.164,1739502645.4057846,5.799994468688965,0.021137771179428277,1739502645.4057877,5.799994468688965,0.22295791961705516,1739502645.405791,5.799994468688965,0.05580378234093149,1739502645.4057941,5.799994468688965,2.091589694395672,1739502645.4057977,5.799994468688965,0.0,1739502645.405801,5.799994468688965,-0.011240736801565133,1739502645.4058044,5.799994468688965,6.264060178387825,1739502645.4058077,5.799994468688965,2.100623159144603 +1739502645.425818,5.8199944496154785,9.816935004920976,1739502645.425821,5.8199944496154785,-0.2810744288529632,1739502645.4258256,5.8199944496154785,9.159426824247415,1739502645.4258306,5.8199944496154785,15.35474648208205,1739502645.4258335,5.8199944496154785,-0.164,1739502645.425837,5.8199944496154785,0.021137771179428277,1739502645.4258404,5.8199944496154785,0.22295791961705516,1739502645.4258437,5.8199944496154785,0.05580378234093149,1739502645.4258468,5.8199944496154785,2.091589694395672,1739502645.4258502,5.8199944496154785,0.0,1739502645.4258535,5.8199944496154785,-0.009033464748930964,1739502645.4258568,5.8199944496154785,6.264060178387825,1739502645.4258602,5.8199944496154785,2.100623159144603 +1739502645.4455426,5.839994430541992,9.816935004920976,1739502645.445546,5.839994430541992,-0.2810744288529632,1739502645.4455504,5.839994430541992,9.159426824247415,1739502645.4455552,5.839994430541992,15.35474648208205,1739502645.445558,5.839994430541992,-0.164,1739502645.4455616,5.839994430541992,0.021137771179428277,1739502645.445565,5.839994430541992,0.22295791961705516,1739502645.4455683,5.839994430541992,0.05580378234093149,1739502645.4455714,5.839994430541992,2.091589694395672,1739502645.4455748,5.839994430541992,0.0,1739502645.4455776,5.839994430541992,-0.009033464748930964,1739502645.445581,5.839994430541992,6.264060178387825,1739502645.4455843,5.839994430541992,2.100623159144603 +1739502645.4657302,5.859994411468506,9.816935004920976,1739502645.4657335,5.859994411468506,-0.2810744288529632,1739502645.465738,5.859994411468506,9.159426824247415,1739502645.465743,5.859994411468506,15.35474648208205,1739502645.4657457,5.859994411468506,-0.164,1739502645.4657493,5.859994411468506,0.021137771179428277,1739502645.4657526,5.859994411468506,0.22295791961705516,1739502645.465756,5.859994411468506,0.05580378234093149,1739502645.4657593,5.859994411468506,2.091589694395672,1739502645.4657626,5.859994411468506,0.0,1739502645.4657657,5.859994411468506,-0.009033464748930964,1739502645.465769,5.859994411468506,6.264060178387825,1739502645.4657724,5.859994411468506,2.100623159144603 +1739502645.486086,5.8799943923950195,9.816935004920976,1739502645.4860892,5.8799943923950195,-0.2810744288529632,1739502645.4860935,5.8799943923950195,9.159426824247415,1739502645.4860985,5.8799943923950195,15.35474648208205,1739502645.4861012,5.8799943923950195,-0.164,1739502645.4861047,5.8799943923950195,0.021137771179428277,1739502645.486108,5.8799943923950195,0.22295791961705516,1739502645.4861112,5.8799943923950195,0.05580378234093149,1739502645.4861147,5.8799943923950195,2.091589694395672,1739502645.486118,5.8799943923950195,0.0,1739502645.4861212,5.8799943923950195,-0.009033464748930964,1739502645.4861245,5.8799943923950195,6.264060178387825,1739502645.486128,5.8799943923950195,2.100623159144603 +1739502645.505708,5.899994373321533,10.047914550342588,1739502645.5057113,5.899994373321533,-0.2854042922963833,1739502645.505716,5.899994373321533,9.18414596547097,1739502645.505721,5.899994373321533,15.377496697515772,1739502645.505724,5.899994373321533,-0.164,1739502645.5057278,5.899994373321533,0.022775387765174696,1739502645.505731,5.899994373321533,0.21883204765434777,1739502645.5057344,5.899994373321533,0.05912951054724509,1739502645.5057378,5.899994373321533,2.0985048054848168,1739502645.5057411,5.899994373321533,0.0,1739502645.5057445,5.899994373321533,0.002456828106807249,1739502645.5057478,5.899994373321533,6.264899918421686,1739502645.5057511,5.899994373321533,2.0996386962496865 +1739502645.5263433,5.919994354248047,10.047914550342588,1739502645.5263467,5.919994354248047,-0.2854042922963833,1739502645.5263512,5.919994354248047,9.18414596547097,1739502645.5263562,5.919994354248047,15.377496697515772,1739502645.5263588,5.919994354248047,-0.164,1739502645.5263624,5.919994354248047,0.022775387765174696,1739502645.5263658,5.919994354248047,0.21883204765434777,1739502645.526369,5.919994354248047,0.05912951054724509,1739502645.5263722,5.919994354248047,2.0985048054848168,1739502645.5263755,5.919994354248047,0.0,1739502645.5263789,5.919994354248047,-0.0011338907648696939,1739502645.526382,5.919994354248047,6.264899918421686,1739502645.5263853,5.919994354248047,2.0996386962496865 +1739502645.545865,5.9399943351745605,10.047914550342588,1739502645.545868,5.9399943351745605,-0.2854042922963833,1739502645.5458724,5.9399943351745605,9.18414596547097,1739502645.5458775,5.9399943351745605,15.377496697515772,1739502645.54588,5.9399943351745605,-0.164,1739502645.5458841,5.9399943351745605,0.022775387765174696,1739502645.5458872,5.9399943351745605,0.21883204765434777,1739502645.5458906,5.9399943351745605,0.05912951054724509,1739502645.5458937,5.9399943351745605,2.0985048054848168,1739502645.545897,5.9399943351745605,0.0,1739502645.5459003,5.9399943351745605,-0.0011338907648696939,1739502645.5459037,5.9399943351745605,6.264899918421686,1739502645.545907,5.9399943351745605,2.0996386962496865 +1739502645.565556,5.959994316101074,10.047914550342588,1739502645.5655594,5.959994316101074,-0.2854042922963833,1739502645.5655637,5.959994316101074,9.18414596547097,1739502645.5655684,5.959994316101074,15.377496697515772,1739502645.5655713,5.959994316101074,-0.164,1739502645.565575,5.959994316101074,0.022775387765174696,1739502645.565578,5.959994316101074,0.21883204765434777,1739502645.5655813,5.959994316101074,0.05912951054724509,1739502645.5655844,5.959994316101074,2.0985048054848168,1739502645.5655878,5.959994316101074,0.0,1739502645.565591,5.959994316101074,-0.0011338907648696939,1739502645.5655944,5.959994316101074,6.264899918421686,1739502645.5655978,5.959994316101074,2.0996386962496865 +1739502645.5870214,5.979994297027588,10.047914550342588,1739502645.5870245,5.979994297027588,-0.2854042922963833,1739502645.5870285,5.979994297027588,9.18414596547097,1739502645.587033,5.979994297027588,15.377496697515772,1739502645.5870357,5.979994297027588,-0.164,1739502645.5870392,5.979994297027588,0.022775387765174696,1739502645.5870423,5.979994297027588,0.21883204765434777,1739502645.5870454,5.979994297027588,0.05912951054724509,1739502645.5870485,5.979994297027588,2.0985048054848168,1739502645.5870516,5.979994297027588,0.0,1739502645.5870545,5.979994297027588,-0.0011338907648696939,1739502645.5870576,5.979994297027588,6.264899918421686,1739502645.5870607,5.979994297027588,2.0996386962496865 +1739502645.6055565,5.999994277954102,10.047914550342588,1739502645.6055598,5.999994277954102,-0.2854042922963833,1739502645.605564,5.999994277954102,9.18414596547097,1739502645.6055691,5.999994277954102,15.377496697515772,1739502645.6055715,5.999994277954102,-0.164,1739502645.6055753,5.999994277954102,0.022775387765174696,1739502645.6055784,5.999994277954102,0.21883204765434777,1739502645.6055818,5.999994277954102,0.05912951054724509,1739502645.6055849,5.999994277954102,2.0985048054848168,1739502645.6055882,5.999994277954102,0.0,1739502645.6055915,5.999994277954102,-0.0011338907648696939,1739502645.6055949,5.999994277954102,6.264899918421686,1739502645.6055982,5.999994277954102,2.0996386962496865 +1739502645.6260269,6.019994258880615,10.278838361300004,1739502645.62603,6.019994258880615,-0.28953912270570115,1739502645.6260345,6.019994258880615,9.855704607756383,1739502645.6260397,6.019994258880615,16.048946703844283,1739502645.6260424,6.019994258880615,-0.165,1739502645.6260462,6.019994258880615,0.021580147542341284,1739502645.6260495,6.019994258880615,0.2251783485695709,1739502645.6260529,6.019994258880615,0.051912781051368775,1739502645.6260562,6.019994258880615,2.0878776112871105,1739502645.6260595,6.019994258880615,0.0,1739502645.6260629,6.019994258880615,-0.016514589982476898,1739502645.6260662,6.019994258880615,6.265739658455548,1739502645.6260695,6.019994258880615,2.0995857296127167 +1739502645.6455433,6.039994239807129,10.278838361300004,1739502645.6455464,6.039994239807129,-0.28953912270570115,1739502645.645551,6.039994239807129,9.855704607756383,1739502645.6455557,6.039994239807129,16.048946703844283,1739502645.6455586,6.039994239807129,-0.165,1739502645.6455622,6.039994239807129,0.021580147542341284,1739502645.6455655,6.039994239807129,0.2251783485695709,1739502645.6455686,6.039994239807129,0.051912781051368775,1739502645.645572,6.039994239807129,2.0878776112871105,1739502645.6455753,6.039994239807129,0.0,1739502645.6455781,6.039994239807129,-0.011708118325606254,1739502645.6455815,6.039994239807129,6.265739658455548,1739502645.6455848,6.039994239807129,2.0995857296127167 +1739502645.6656587,6.059994220733643,10.278838361300004,1739502645.665662,6.059994220733643,-0.28953912270570115,1739502645.6656663,6.059994220733643,9.855704607756383,1739502645.6656713,6.059994220733643,16.048946703844283,1739502645.665674,6.059994220733643,-0.165,1739502645.6656775,6.059994220733643,0.021580147542341284,1739502645.665681,6.059994220733643,0.2251783485695709,1739502645.665684,6.059994220733643,0.051912781051368775,1739502645.6656873,6.059994220733643,2.0878776112871105,1739502645.6656907,6.059994220733643,0.0,1739502645.6656938,6.059994220733643,-0.011708118325606254,1739502645.665697,6.059994220733643,6.265739658455548,1739502645.6657007,6.059994220733643,2.0995857296127167 +1739502645.6864533,6.079994201660156,10.278838361300004,1739502645.6864567,6.079994201660156,-0.28953912270570115,1739502645.686461,6.079994201660156,9.855704607756383,1739502645.6864657,6.079994201660156,16.048946703844283,1739502645.6864686,6.079994201660156,-0.165,1739502645.6864722,6.079994201660156,0.021580147542341284,1739502645.6864755,6.079994201660156,0.2251783485695709,1739502645.6864789,6.079994201660156,0.051912781051368775,1739502645.686482,6.079994201660156,2.0878776112871105,1739502645.6864853,6.079994201660156,0.0,1739502645.6864884,6.079994201660156,-0.011708118325606254,1739502645.6864917,6.079994201660156,6.265739658455548,1739502645.686495,6.079994201660156,2.0995857296127167 +1739502645.7055073,6.09999418258667,10.278838361300004,1739502645.7055106,6.09999418258667,-0.28953912270570115,1739502645.7055151,6.09999418258667,9.855704607756383,1739502645.7055202,6.09999418258667,16.048946703844283,1739502645.705523,6.09999418258667,-0.165,1739502645.7055268,6.09999418258667,0.021580147542341284,1739502645.7055302,6.09999418258667,0.2251783485695709,1739502645.7055335,6.09999418258667,0.051912781051368775,1739502645.7055368,6.09999418258667,2.0878776112871105,1739502645.7055402,6.09999418258667,0.0,1739502645.7055435,6.09999418258667,-0.011708118325606254,1739502645.7055469,6.09999418258667,6.265739658455548,1739502645.7055502,6.09999418258667,2.0995857296127167 +1739502645.7255147,6.119994163513184,10.509697345387606,1739502645.725518,6.119994163513184,-0.29347888112742027,1739502645.7255228,6.119994163513184,9.86586634281466,1739502645.7255278,6.119994163513184,16.05656334969359,1739502645.7255306,6.119994163513184,-0.165,1739502645.7255344,6.119994163513184,0.023158286534796187,1739502645.7255378,6.119994163513184,0.22056768420096903,1739502645.7255409,6.119994163513184,0.055020701189988794,1739502645.7255442,6.119994163513184,2.095593034156397,1739502645.7255476,6.119994163513184,0.0,1739502645.725551,6.119994163513184,0.0013652928051552712,1739502645.7255545,6.119994163513184,6.266579398489409,1739502645.725558,6.119994163513184,2.09831318500823 +1739502645.7455547,6.139994144439697,10.509697345387606,1739502645.745558,6.139994144439697,-0.29347888112742027,1739502645.7455626,6.139994144439697,9.86586634281466,1739502645.7455678,6.139994144439697,16.05656334969359,1739502645.7455707,6.139994144439697,-0.165,1739502645.7455745,6.139994144439697,0.023158286534796187,1739502645.7455778,6.139994144439697,0.22056768420096903,1739502645.7455812,6.139994144439697,0.055020701189988794,1739502645.7455845,6.139994144439697,2.095593034156397,1739502645.7455878,6.139994144439697,0.0,1739502645.745591,6.139994144439697,-0.002720150851833303,1739502645.7455947,6.139994144439697,6.266579398489409,1739502645.7455978,6.139994144439697,2.09831318500823 +1739502645.7655547,6.159994125366211,10.509697345387606,1739502645.765558,6.159994125366211,-0.29347888112742027,1739502645.7655623,6.159994125366211,9.86586634281466,1739502645.7655675,6.159994125366211,16.05656334969359,1739502645.7655704,6.159994125366211,-0.165,1739502645.7655742,6.159994125366211,0.023158286534796187,1739502645.7655776,6.159994125366211,0.22056768420096903,1739502645.7655807,6.159994125366211,0.055020701189988794,1739502645.7655838,6.159994125366211,2.095593034156397,1739502645.765587,6.159994125366211,0.0,1739502645.7655904,6.159994125366211,-0.002720150851833303,1739502645.765594,6.159994125366211,6.266579398489409,1739502645.7655976,6.159994125366211,2.09831318500823 +1739502645.7841582,6.179994106292725,10.509697345387606,1739502645.7841601,6.179994106292725,-0.29347888112742027,1739502645.7841628,6.179994106292725,9.86586634281466,1739502645.7841656,6.179994106292725,16.05656334969359,1739502645.7841668,6.179994106292725,-0.165,1739502645.7841685,6.179994106292725,0.023158286534796187,1739502645.7841697,6.179994106292725,0.22056768420096903,1739502645.7841713,6.179994106292725,0.055020701189988794,1739502645.7841725,6.179994106292725,2.095593034156397,1739502645.784174,6.179994106292725,0.0,1739502645.7841754,6.179994106292725,-0.002720150851833303,1739502645.7841766,6.179994106292725,6.266579398489409,1739502645.784178,6.179994106292725,2.09831318500823 +1739502645.8045745,6.199994087219238,10.509697345387606,1739502645.8045769,6.199994087219238,-0.29347888112742027,1739502645.8045802,6.199994087219238,9.86586634281466,1739502645.8045828,6.199994087219238,16.05656334969359,1739502645.8045843,6.199994087219238,-0.165,1739502645.804586,6.199994087219238,0.023158286534796187,1739502645.8045874,6.199994087219238,0.22056768420096903,1739502645.8045888,6.199994087219238,0.055020701189988794,1739502645.80459,6.199994087219238,2.095593034156397,1739502645.8045917,6.199994087219238,0.0,1739502645.8045928,6.199994087219238,-0.002720150851833303,1739502645.8045945,6.199994087219238,6.266579398489409,1739502645.804596,6.199994087219238,2.09831318500823 +1739502645.824352,6.219994068145752,10.509697345387606,1739502645.8243544,6.219994068145752,-0.29347888112742027,1739502645.8243573,6.219994068145752,9.86586634281466,1739502645.8243601,6.219994068145752,16.05656334969359,1739502645.8243616,6.219994068145752,-0.165,1739502645.8243635,6.219994068145752,0.023158286534796187,1739502645.8243651,6.219994068145752,0.22056768420096903,1739502645.8243666,6.219994068145752,0.055020701189988794,1739502645.8243678,6.219994068145752,2.095593034156397,1739502645.8243694,6.219994068145752,0.0,1739502645.8243709,6.219994068145752,-0.002720150851833303,1739502645.8243725,6.219994068145752,6.266579398489409,1739502645.824374,6.219994068145752,2.09831318500823 +1739502645.853683,6.239994049072266,10.740474224886462,1739502645.8536913,6.239994049072266,-0.2972233837763083,1739502645.8537016,6.239994049072266,9.87602427001526,1739502645.8537118,6.239994049072266,16.06628758347474,1739502645.8537169,6.239994049072266,-0.165,1739502645.853723,6.239994049072266,0.024821791254170895,1739502645.8537283,6.239994049072266,0.21617114361342524,1739502645.8537328,6.239994049072266,0.05848768349539213,1739502645.8537374,6.239994049072266,2.1029766994418604,1739502645.853743,6.239994049072266,0.0,1739502645.8537476,6.239994049072266,0.00833514261772014,1739502645.8537529,6.239994049072266,6.26741913852327,1739502645.8537579,6.239994049072266,2.098096338298507 +1739502645.8728514,6.259994029998779,10.740474224886462,1739502645.8728604,6.259994029998779,-0.2972233837763083,1739502645.872872,6.259994029998779,9.87602427001526,1739502645.8728857,6.259994029998779,16.06628758347474,1739502645.872893,6.259994029998779,-0.165,1739502645.872903,6.259994029998779,0.024821791254170895,1739502645.872912,6.259994029998779,0.21617114361342524,1739502645.8729205,6.259994029998779,0.05848768349539213,1739502645.8729293,6.259994029998779,2.1029766994418604,1739502645.8729384,6.259994029998779,0.0,1739502645.8729472,6.259994029998779,0.00488036114335344,1739502645.8729563,6.259994029998779,6.26741913852327,1739502645.872965,6.259994029998779,2.098096338298507 +1739502645.8874848,6.279994010925293,10.740474224886462,1739502645.887489,6.279994010925293,-0.2972233837763083,1739502645.8874955,6.279994010925293,9.87602427001526,1739502645.8875027,6.279994010925293,16.06628758347474,1739502645.8875065,6.279994010925293,-0.165,1739502645.8875115,6.279994010925293,0.024821791254170895,1739502645.8875163,6.279994010925293,0.21617114361342524,1739502645.8875208,6.279994010925293,0.05848768349539213,1739502645.8875253,6.279994010925293,2.1029766994418604,1739502645.88753,6.279994010925293,0.0,1739502645.8875349,6.279994010925293,0.00488036114335344,1739502645.8875394,6.279994010925293,6.26741913852327,1739502645.8875444,6.279994010925293,2.098096338298507 +1739502645.9054158,6.299993991851807,10.740474224886462,1739502645.9054196,6.299993991851807,-0.2972233837763083,1739502645.9054236,6.299993991851807,9.87602427001526,1739502645.9054284,6.299993991851807,16.06628758347474,1739502645.9054313,6.299993991851807,-0.165,1739502645.9054348,6.299993991851807,0.024821791254170895,1739502645.905438,6.299993991851807,0.21617114361342524,1739502645.9054413,6.299993991851807,0.05848768349539213,1739502645.9054444,6.299993991851807,2.1029766994418604,1739502645.9054477,6.299993991851807,0.0,1739502645.9054508,6.299993991851807,0.00488036114335344,1739502645.9054542,6.299993991851807,6.26741913852327,1739502645.9054575,6.299993991851807,2.098096338298507 +1739502645.9257736,6.31999397277832,10.740474224886462,1739502645.9257767,6.31999397277832,-0.2972233837763083,1739502645.9257808,6.31999397277832,9.87602427001526,1739502645.9257855,6.31999397277832,16.06628758347474,1739502645.9257882,6.31999397277832,-0.165,1739502645.9257915,6.31999397277832,0.024821791254170895,1739502645.9257946,6.31999397277832,0.21617114361342524,1739502645.9257977,6.31999397277832,0.05848768349539213,1739502645.9258008,6.31999397277832,2.1029766994418604,1739502645.9258037,6.31999397277832,0.0,1739502645.9258068,6.31999397277832,0.00488036114335344,1739502645.9258099,6.31999397277832,6.26741913852327,1739502645.9258132,6.31999397277832,2.098096338298507 +1739502645.9452832,6.339993953704834,10.971262572664498,1739502645.9452868,6.339993953704834,-0.3007742156717983,1739502645.9452913,6.339993953704834,10.157316200114577,1739502645.9452956,6.339993953704834,16.348635161442548,1739502645.945298,6.339993953704834,-0.165,1739502645.9453008,6.339993953704834,0.0252438103369,1739502645.9453032,6.339993953704834,0.2160210784955972,1739502645.9453056,6.339993953704834,0.057330725229717355,1739502645.9453082,6.339993953704834,2.1032291813540014,1739502645.945311,6.339993953704834,0.0,1739502645.9453135,6.339993953704834,0.004479863537299374,1739502645.9453158,6.339993953704834,6.2682588785571305,1739502645.9453182,6.339993953704834,2.0986241622327517 +1739502645.9653323,6.359993934631348,10.971262572664498,1739502645.9653356,6.359993934631348,-0.3007742156717983,1739502645.9653401,6.359993934631348,10.157316200114577,1739502645.9653454,6.359993934631348,16.348635161442548,1739502645.965348,6.359993934631348,-0.165,1739502645.9653523,6.359993934631348,0.0252438103369,1739502645.9653556,6.359993934631348,0.2160210784955972,1739502645.9653587,6.359993934631348,0.057330725229717355,1739502645.9653625,6.359993934631348,2.1032291813540014,1739502645.9653656,6.359993934631348,0.0,1739502645.9653697,6.359993934631348,0.004605019121249665,1739502645.965373,6.359993934631348,6.2682588785571305,1739502645.9653766,6.359993934631348,2.0986241622327517 +1739502645.9852462,6.379993915557861,10.971262572664498,1739502645.9852502,6.379993915557861,-0.3007742156717983,1739502645.9852555,6.379993915557861,10.157316200114577,1739502645.9852607,6.379993915557861,16.348635161442548,1739502645.9852633,6.379993915557861,-0.165,1739502645.9852667,6.379993915557861,0.0252438103369,1739502645.9852705,6.379993915557861,0.2160210784955972,1739502645.9852734,6.379993915557861,0.057330725229717355,1739502645.985276,6.379993915557861,2.1032291813540014,1739502645.985279,6.379993915557861,0.0,1739502645.9852815,6.379993915557861,0.004605019121249665,1739502645.9852843,6.379993915557861,6.2682588785571305,1739502645.9852872,6.379993915557861,2.0986241622327517 +1739502646.0052378,6.399993896484375,10.971262572664498,1739502646.0052416,6.399993896484375,-0.3007742156717983,1739502646.005246,6.399993896484375,10.157316200114577,1739502646.0052505,6.399993896484375,16.348635161442548,1739502646.0052528,6.399993896484375,-0.165,1739502646.005256,6.399993896484375,0.0252438103369,1739502646.005259,6.399993896484375,0.2160210784955972,1739502646.0052617,6.399993896484375,0.057330725229717355,1739502646.0052638,6.399993896484375,2.1032291813540014,1739502646.005267,6.399993896484375,0.0,1739502646.0052695,6.399993896484375,0.004605019121249665,1739502646.0052722,6.399993896484375,6.2682588785571305,1739502646.0052745,6.399993896484375,2.0986241622327517 +1739502646.025458,6.419993877410889,10.971262572664498,1739502646.0254624,6.419993877410889,-0.3007742156717983,1739502646.0254674,6.419993877410889,10.157316200114577,1739502646.0254724,6.419993877410889,16.348635161442548,1739502646.0254753,6.419993877410889,-0.165,1739502646.0254803,6.419993877410889,0.0252438103369,1739502646.0254836,6.419993877410889,0.2160210784955972,1739502646.025487,6.419993877410889,0.057330725229717355,1739502646.0254912,6.419993877410889,2.1032291813540014,1739502646.0254948,6.419993877410889,0.0,1739502646.0254986,6.419993877410889,0.004605019121249665,1739502646.0255027,6.419993877410889,6.2682588785571305,1739502646.0255058,6.419993877410889,2.0986241622327517 +1739502646.0469933,6.439993858337402,10.971262572664498,1739502646.046997,6.439993858337402,-0.3007742156717983,1739502646.0470016,6.439993858337402,10.157316200114577,1739502646.047007,6.439993858337402,16.348635161442548,1739502646.0470097,6.439993858337402,-0.165,1739502646.0470133,6.439993858337402,0.0252438103369,1739502646.0470169,6.439993858337402,0.2160210784955972,1739502646.04702,6.439993858337402,0.057330725229717355,1739502646.0470233,6.439993858337402,2.1032291813540014,1739502646.0470269,6.439993858337402,0.0,1739502646.0470302,6.439993858337402,0.004605019121249665,1739502646.0470335,6.439993858337402,6.2682588785571305,1739502646.047037,6.439993858337402,2.0986241622327517 +1739502646.065927,6.459993839263916,11.202111824689917,1739502646.0659316,6.459993839263916,-0.30413208834202177,1739502646.0659368,6.459993839263916,10.951756370467594,1739502646.0659428,6.459993839263916,17.14407882713519,1739502646.0659456,6.459993839263916,-0.165,1739502646.0659497,6.459993839263916,0.023410878813315043,1739502646.0659533,6.459993839263916,0.22281815478849573,1739502646.065956,6.459993839263916,0.048436810441810085,1739502646.0659604,6.459993839263916,2.0918235720106173,1739502646.065964,6.459993839263916,0.0,1739502646.0659673,6.459993839263916,-0.012714778059650027,1739502646.06597,6.459993839263916,6.269098618590992,1739502646.0659738,6.459993839263916,2.099125909902564 +1739502646.0853326,6.47999382019043,11.202111824689917,1739502646.085335,6.47999382019043,-0.30413208834202177,1739502646.085338,6.47999382019043,10.951756370467594,1739502646.085341,6.47999382019043,17.14407882713519,1739502646.0853422,6.47999382019043,-0.165,1739502646.085344,6.47999382019043,0.023410878813315043,1739502646.0853453,6.47999382019043,0.22281815478849573,1739502646.0853467,6.47999382019043,0.048436810441810085,1739502646.085348,6.47999382019043,2.0918235720106173,1739502646.0853496,6.47999382019043,0.0,1739502646.0853517,6.47999382019043,-0.007302337891946564,1739502646.085353,6.47999382019043,6.269098618590992,1739502646.0853543,6.47999382019043,2.099125909902564 +1739502646.1045532,6.499993801116943,11.202111824689917,1739502646.1045554,6.499993801116943,-0.30413208834202177,1739502646.1045578,6.499993801116943,10.951756370467594,1739502646.1045604,6.499993801116943,17.14407882713519,1739502646.1045616,6.499993801116943,-0.165,1739502646.1045632,6.499993801116943,0.023410878813315043,1739502646.1045644,6.499993801116943,0.22281815478849573,1739502646.1045659,6.499993801116943,0.048436810441810085,1739502646.104567,6.499993801116943,2.0918235720106173,1739502646.1045682,6.499993801116943,0.0,1739502646.1045697,6.499993801116943,-0.007302337891946564,1739502646.1045709,6.499993801116943,6.269098618590992,1739502646.104572,6.499993801116943,2.099125909902564 +1739502646.1340716,6.519993782043457,11.202111824689917,1739502646.13408,6.519993782043457,-0.30413208834202177,1739502646.1340907,6.519993782043457,10.951756370467594,1739502646.134101,6.519993782043457,17.14407882713519,1739502646.134106,6.519993782043457,-0.165,1739502646.134112,6.519993782043457,0.023410878813315043,1739502646.1341171,6.519993782043457,0.22281815478849573,1739502646.134122,6.519993782043457,0.048436810441810085,1739502646.1341264,6.519993782043457,2.0918235720106173,1739502646.1341324,6.519993782043457,0.0,1739502646.1341374,6.519993782043457,-0.007302337891946564,1739502646.1341424,6.519993782043457,6.269098618590992,1739502646.1341472,6.519993782043457,2.099125909902564 +1739502646.149042,6.539993762969971,11.202111824689917,1739502646.14905,6.539993762969971,-0.30413208834202177,1739502646.14906,6.539993762969971,10.951756370467594,1739502646.14907,6.539993762969971,17.14407882713519,1739502646.149075,6.539993762969971,-0.165,1739502646.1490817,6.539993762969971,0.023410878813315043,1739502646.149087,6.539993762969971,0.22281815478849573,1739502646.149092,6.539993762969971,0.048436810441810085,1739502646.1490965,6.539993762969971,2.0918235720106173,1739502646.149102,6.539993762969971,0.0,1739502646.1491072,6.539993762969971,-0.007302337891946564,1739502646.149112,6.539993762969971,6.269098618590992,1739502646.1491175,6.539993762969971,2.099125909902564 +1739502646.1667006,6.559993743896484,11.432956577504482,1739502646.166706,6.559993743896484,-0.3072960176579409,1739502646.1667132,6.559993743896484,10.956838118958832,1739502646.1667202,6.559993743896484,17.147581669458113,1739502646.1667237,6.559993743896484,-0.165,1739502646.1667278,6.559993743896484,0.024895179862315965,1739502646.1667314,6.559993743896484,0.21798266326018018,1739502646.1667347,6.559993743896484,0.05122668867629963,1739502646.166738,6.559993743896484,2.0999312398526593,1739502646.1667418,6.559993743896484,0.0,1739502646.1667452,6.559993743896484,0.005638932766598502,1739502646.166749,6.559993743896484,6.269938358624853,1739502646.1667523,6.559993743896484,2.0983364568184073 +1739502646.1860118,6.579993724822998,11.432956577504482,1739502646.1860166,6.579993724822998,-0.3072960176579409,1739502646.1860223,6.579993724822998,10.956838118958832,1739502646.1860278,6.579993724822998,17.147581669458113,1739502646.1860304,6.579993724822998,-0.165,1739502646.1860335,6.579993724822998,0.024895179862315965,1739502646.186036,6.579993724822998,0.21798266326018018,1739502646.1860387,6.579993724822998,0.05122668867629963,1739502646.1860414,6.579993724822998,2.0999312398526593,1739502646.1860442,6.579993724822998,0.0,1739502646.186047,6.579993724822998,0.0015947830342519786,1739502646.1860497,6.579993724822998,6.269938358624853,1739502646.1860523,6.579993724822998,2.0983364568184073 +1739502646.2050176,6.599993705749512,11.432956577504482,1739502646.2050204,6.599993705749512,-0.3072960176579409,1739502646.2050235,6.599993705749512,10.956838118958832,1739502646.2050266,6.599993705749512,17.147581669458113,1739502646.205028,6.599993705749512,-0.165,1739502646.2050302,6.599993705749512,0.024895179862315965,1739502646.2050316,6.599993705749512,0.21798266326018018,1739502646.205033,6.599993705749512,0.05122668867629963,1739502646.2050345,6.599993705749512,2.0999312398526593,1739502646.2050364,6.599993705749512,0.0,1739502646.2050376,6.599993705749512,0.0015947830342519786,1739502646.2050393,6.599993705749512,6.269938358624853,1739502646.205041,6.599993705749512,2.0983364568184073 +1739502646.2254817,6.619993686676025,11.432956577504482,1739502646.2254844,6.619993686676025,-0.3072960176579409,1739502646.225487,6.619993686676025,10.956838118958832,1739502646.2254899,6.619993686676025,17.147581669458113,1739502646.2254915,6.619993686676025,-0.165,1739502646.225493,6.619993686676025,0.024895179862315965,1739502646.2254944,6.619993686676025,0.21798266326018018,1739502646.2254956,6.619993686676025,0.05122668867629963,1739502646.2254968,6.619993686676025,2.0999312398526593,1739502646.2254984,6.619993686676025,0.0,1739502646.2254996,6.619993686676025,0.0015947830342519786,1739502646.2255008,6.619993686676025,6.269938358624853,1739502646.2255023,6.619993686676025,2.0983364568184073 +1739502646.2443786,6.639993667602539,11.432956577504482,1739502646.244381,6.639993667602539,-0.3072960176579409,1739502646.2443836,6.639993667602539,10.956838118958832,1739502646.244386,6.639993667602539,17.147581669458113,1739502646.2443874,6.639993667602539,-0.165,1739502646.2443888,6.639993667602539,0.024895179862315965,1739502646.2443898,6.639993667602539,0.21798266326018018,1739502646.2443912,6.639993667602539,0.05122668867629963,1739502646.2443924,6.639993667602539,2.0999312398526593,1739502646.244394,6.639993667602539,0.0,1739502646.2443953,6.639993667602539,0.0015947830342519786,1739502646.2443964,6.639993667602539,6.269938358624853,1739502646.2443979,6.639993667602539,2.0983364568184073 +1739502646.265296,6.659993648529053,11.432956577504482,1739502646.2652981,6.659993648529053,-0.3072960176579409,1739502646.2653012,6.659993648529053,10.956838118958832,1739502646.265304,6.659993648529053,17.147581669458113,1739502646.2653053,6.659993648529053,-0.165,1739502646.265307,6.659993648529053,0.024895179862315965,1739502646.2653081,6.659993648529053,0.21798266326018018,1739502646.2653093,6.659993648529053,0.05122668867629963,1739502646.2653105,6.659993648529053,2.0999312398526593,1739502646.265312,6.659993648529053,0.0,1739502646.2653134,6.659993648529053,0.0015947830342519786,1739502646.2653146,6.659993648529053,6.269938358624853,1739502646.2653158,6.659993648529053,2.0983364568184073 +1739502646.2855175,6.679993629455566,11.6637708791411,1739502646.2855198,6.679993629455566,-0.3102656630963958,1739502646.285523,6.679993629455566,10.961919003240276,1739502646.2855258,6.679993629455566,17.153172155248367,1739502646.285527,6.679993629455566,-0.165,1739502646.285529,6.679993629455566,0.026456759274806355,1739502646.28553,6.679993629455566,0.21336088111341187,1739502646.2855313,6.679993629455566,0.05433435850776251,1739502646.2855327,6.679993629455566,2.107709951365824,1739502646.2855344,6.679993629455566,0.0,1739502646.2855356,6.679993629455566,0.012538656490342436,1739502646.2855368,6.679993629455566,6.270778098658714,1739502646.285538,6.679993629455566,2.0985912575728123 +1739502646.304876,6.69999361038208,11.6637708791411,1739502646.3048782,6.69999361038208,-0.3102656630963958,1739502646.304881,6.69999361038208,10.961919003240276,1739502646.3048837,6.69999361038208,17.153172155248367,1739502646.304885,6.69999361038208,-0.165,1739502646.3048866,6.69999361038208,0.026456759274806355,1739502646.304888,6.69999361038208,0.21336088111341187,1739502646.3048894,6.69999361038208,0.05433435850776251,1739502646.3048904,6.69999361038208,2.107709951365824,1739502646.304892,6.69999361038208,0.0,1739502646.3048933,6.69999361038208,0.00911869379301189,1739502646.304895,6.69999361038208,6.270778098658714,1739502646.3048964,6.69999361038208,2.0985912575728123 +1739502646.3244843,6.719993591308594,11.6637708791411,1739502646.3244865,6.719993591308594,-0.3102656630963958,1739502646.324489,6.719993591308594,10.961919003240276,1739502646.324492,6.719993591308594,17.153172155248367,1739502646.3244934,6.719993591308594,-0.165,1739502646.324495,6.719993591308594,0.026456759274806355,1739502646.3244963,6.719993591308594,0.21336088111341187,1739502646.324498,6.719993591308594,0.05433435850776251,1739502646.3244994,6.719993591308594,2.107709951365824,1739502646.324501,6.719993591308594,0.0,1739502646.3245022,6.719993591308594,0.00911869379301189,1739502646.3245037,6.719993591308594,6.270778098658714,1739502646.3245049,6.719993591308594,2.0985912575728123 +1739502646.3511877,6.729993581771851,11.6637708791411,1739502646.351196,6.729993581771851,-0.3102656630963958,1739502646.3512123,6.729993581771851,10.961919003240276,1739502646.351237,6.729993581771851,17.153172155248367,1739502646.3512468,6.729993581771851,-0.165,1739502646.3512576,6.729993581771851,0.026456759274806355,1739502646.3512661,6.729993581771851,0.21336088111341187,1739502646.3512733,6.729993581771851,0.05433435850776251,1739502646.3512807,6.729993581771851,2.107709951365824,1739502646.3512895,6.729993581771851,0.0,1739502646.3512974,6.729993581771851,0.00911869379301189,1739502646.351305,6.729993581771851,6.270778098658714,1739502646.3513129,6.729993581771851,2.0985912575728123 +1739502646.3712587,6.749993562698364,11.6637708791411,1739502646.3712673,6.749993562698364,-0.3102656630963958,1739502646.3712778,6.749993562698364,10.961919003240276,1739502646.3712876,6.749993562698364,17.153172155248367,1739502646.3712926,6.749993562698364,-0.165,1739502646.3712988,6.749993562698364,0.026456759274806355,1739502646.3713043,6.749993562698364,0.21336088111341187,1739502646.371309,6.749993562698364,0.05433435850776251,1739502646.3713138,6.749993562698364,2.107709951365824,1739502646.3713195,6.749993562698364,0.0,1739502646.3713243,6.749993562698364,0.00911869379301189,1739502646.3713295,6.749993562698364,6.270778098658714,1739502646.3713343,6.749993562698364,2.0985912575728123 +1739502646.3926625,6.769993543624878,11.6637708791411,1739502646.392669,6.769993543624878,-0.3102656630963958,1739502646.3927064,6.769993543624878,10.961919003240276,1739502646.392723,6.769993543624878,17.153172155248367,1739502646.3927276,6.769993543624878,-0.165,1739502646.3927321,6.769993543624878,0.026456759274806355,1739502646.392736,6.769993543624878,0.21336088111341187,1739502646.3927398,6.769993543624878,0.05433435850776251,1739502646.3927433,6.769993543624878,2.107709951365824,1739502646.3927472,6.769993543624878,0.0,1739502646.3927505,6.769993543624878,0.00911869379301189,1739502646.392754,6.769993543624878,6.270778098658714,1739502646.3927577,6.769993543624878,2.0985912575728123 +1739502646.410238,6.799993515014648,11.894647508316831,1739502646.4102426,6.799993515014648,-0.31304219791911336,1739502646.4102485,6.799993515014648,10.967001065616964,1739502646.410254,6.799993515014648,17.16023729818609,1739502646.4102566,6.799993515014648,-0.165,1739502646.41026,6.799993515014648,0.028107622399320607,1739502646.4102628,6.799993515014648,0.2089404791600302,1739502646.4102654,6.799993515014648,0.057821961913635506,1739502646.4102678,6.799993515014648,2.1151766861210137,1739502646.410271,6.799993515014648,0.0,1739502646.4102736,6.799993515014648,0.018537161290368323,1739502646.4102764,6.799993515014648,6.271617838692576,1739502646.4102788,6.799993515014648,2.0995827978533295 +1739502646.4279451,6.819993495941162,11.894647508316831,1739502646.4279487,6.819993495941162,-0.31304219791911336,1739502646.4279535,6.819993495941162,10.967001065616964,1739502646.4279578,6.819993495941162,17.16023729818609,1739502646.4279602,6.819993495941162,-0.165,1739502646.4279625,6.819993495941162,0.028107622399320607,1739502646.4279652,6.819993495941162,0.2089404791600302,1739502646.4279673,6.819993495941162,0.057821961913635506,1739502646.4279692,6.819993495941162,2.1151766861210137,1739502646.4279718,6.819993495941162,0.0,1739502646.427974,6.819993495941162,0.015593888267684264,1739502646.427976,6.819993495941162,6.271617838692576,1739502646.4279783,6.819993495941162,2.0995827978533295 +1739502646.4491525,6.839993476867676,11.894647508316831,1739502646.4491556,6.839993476867676,-0.31304219791911336,1739502646.4491594,6.839993476867676,10.967001065616964,1739502646.4491627,6.839993476867676,17.16023729818609,1739502646.4491646,6.839993476867676,-0.165,1739502646.4491668,6.839993476867676,0.028107622399320607,1739502646.4491687,6.839993476867676,0.2089404791600302,1739502646.4491704,6.839993476867676,0.057821961913635506,1739502646.449172,6.839993476867676,2.1151766861210137,1739502646.449174,6.839993476867676,0.0,1739502646.4491758,6.839993476867676,0.015593888267684264,1739502646.4491777,6.839993476867676,6.271617838692576,1739502646.44918,6.839993476867676,2.0995827978533295 +1739502646.469381,6.8599934577941895,11.894647508316831,1739502646.4693856,6.8599934577941895,-0.31304219791911336,1739502646.4693918,6.8599934577941895,10.967001065616964,1739502646.469399,6.8599934577941895,17.16023729818609,1739502646.469403,6.8599934577941895,-0.165,1739502646.4694083,6.8599934577941895,0.028107622399320607,1739502646.4694128,6.8599934577941895,0.2089404791600302,1739502646.4694176,6.8599934577941895,0.057821961913635506,1739502646.469422,6.8599934577941895,2.1151766861210137,1739502646.4694266,6.8599934577941895,0.0,1739502646.4694314,6.8599934577941895,0.015593888267684264,1739502646.469436,6.8599934577941895,6.271617838692576,1739502646.4694407,6.8599934577941895,2.0995827978533295 +1739502646.488205,6.879993438720703,11.894647508316831,1739502646.488208,6.879993438720703,-0.31304219791911336,1739502646.4882116,6.879993438720703,10.967001065616964,1739502646.4882152,6.879993438720703,17.16023729818609,1739502646.488217,6.879993438720703,-0.165,1739502646.488219,6.879993438720703,0.028107622399320607,1739502646.488221,6.879993438720703,0.2089404791600302,1739502646.4882228,6.879993438720703,0.057821961913635506,1739502646.4882245,6.879993438720703,2.1151766861210137,1739502646.4882267,6.879993438720703,0.0,1739502646.4882283,6.879993438720703,0.015593888267684264,1739502646.4882302,6.879993438720703,6.271617838692576,1739502646.488232,6.879993438720703,2.0995827978533295 +1739502646.507698,6.899993419647217,12.125664660577549,1739502646.5077012,6.899993419647217,-0.3156263971482751,1739502646.5077047,6.899993419647217,11.376337372735234,1739502646.5077088,6.899993419647217,17.572840872976563,1739502646.5077105,6.899993419647217,-0.164,1739502646.5077128,6.899993419647217,0.0278285937229107,1739502646.5077145,6.899993419647217,0.21005237874370375,1739502646.5077164,6.899993419647217,0.054320296896996446,1739502646.507718,6.899993419647217,2.1132960314233338,1739502646.5077202,6.899993419647217,0.0,1739502646.507722,6.899993419647217,0.010479138616779312,1739502646.5077238,6.899993419647217,6.272457578726437,1739502646.5077255,6.899993419647217,2.10121853249268 +1739502646.5287697,6.9199934005737305,12.125664660577549,1739502646.5287726,6.9199934005737305,-0.3156263971482751,1739502646.528776,6.9199934005737305,11.376337372735234,1739502646.528779,6.9199934005737305,17.572840872976563,1739502646.5287805,6.9199934005737305,-0.164,1739502646.5287824,6.9199934005737305,0.0278285937229107,1739502646.528784,6.9199934005737305,0.21005237874370375,1739502646.5287857,6.9199934005737305,0.054320296896996446,1739502646.528787,6.9199934005737305,2.1132960314233338,1739502646.5287888,6.9199934005737305,0.0,1739502646.5287902,6.9199934005737305,0.012077498930653796,1739502646.5287921,6.9199934005737305,6.272457578726437,1739502646.5287936,6.9199934005737305,2.10121853249268 +1739502646.5485883,6.939993381500244,12.125664660577549,1739502646.5485919,6.939993381500244,-0.3156263971482751,1739502646.5485964,6.939993381500244,11.376337372735234,1739502646.5486019,6.939993381500244,17.572840872976563,1739502646.548605,6.939993381500244,-0.164,1739502646.5486088,6.939993381500244,0.0278285937229107,1739502646.5486124,6.939993381500244,0.21005237874370375,1739502646.5486157,6.939993381500244,0.054320296896996446,1739502646.5486193,6.939993381500244,2.1132960314233338,1739502646.5486226,6.939993381500244,0.0,1739502646.5486262,6.939993381500244,0.012077498930653796,1739502646.5486298,6.939993381500244,6.272457578726437,1739502646.5486333,6.939993381500244,2.10121853249268 +1739502646.5673058,6.959993362426758,12.125664660577549,1739502646.5673082,6.959993362426758,-0.3156263971482751,1739502646.567311,6.959993362426758,11.376337372735234,1739502646.567314,6.959993362426758,17.572840872976563,1739502646.567315,6.959993362426758,-0.164,1739502646.567317,6.959993362426758,0.0278285937229107,1739502646.5673182,6.959993362426758,0.21005237874370375,1739502646.5673199,6.959993362426758,0.054320296896996446,1739502646.567321,6.959993362426758,2.1132960314233338,1739502646.5673227,6.959993362426758,0.0,1739502646.567324,6.959993362426758,0.012077498930653796,1739502646.5673254,6.959993362426758,6.272457578726437,1739502646.5673268,6.959993362426758,2.10121853249268 +1739502646.5879498,6.9799933433532715,12.125664660577549,1739502646.5879521,6.9799933433532715,-0.3156263971482751,1739502646.5879555,6.9799933433532715,11.376337372735234,1739502646.5879583,6.9799933433532715,17.572840872976563,1739502646.5879595,6.9799933433532715,-0.164,1739502646.5879614,6.9799933433532715,0.0278285937229107,1739502646.5879629,6.9799933433532715,0.21005237874370375,1739502646.587964,6.9799933433532715,0.054320296896996446,1739502646.5879655,6.9799933433532715,2.1132960314233338,1739502646.587967,6.9799933433532715,0.0,1739502646.5879686,6.9799933433532715,0.012077498930653796,1739502646.5879698,6.9799933433532715,6.272457578726437,1739502646.5879712,6.9799933433532715,2.10121853249268 +1739502646.6077409,6.999993324279785,12.356853206070472,1739502646.607743,6.999993324279785,-0.31801835578835913,1739502646.6077464,6.999993324279785,11.50165405086277,1739502646.6077492,6.999993324279785,17.70080430248516,1739502646.6077507,6.999993324279785,-0.16367391342449444,1739502646.607752,6.999993324279785,0.028874056723481843,1739502646.6077535,6.999993324279785,0.20717696261414167,1739502646.607755,6.999993324279785,0.055662891645641754,1739502646.6077564,6.999993324279785,2.1181629113955345,1739502646.6077578,6.999993324279785,0.0,1739502646.6077595,6.999993324279785,0.017230692085238294,1739502646.6077607,6.999993324279785,6.273297318760298,1739502646.607762,6.999993324279785,2.1025425932269473 +1739502646.6275277,7.019993305206299,12.356853206070472,1739502646.62753,7.019993305206299,-0.31801835578835913,1739502646.6275327,7.019993305206299,11.50165405086277,1739502646.6275356,7.019993305206299,17.70080430248516,1739502646.627537,7.019993305206299,-0.16367391342449444,1739502646.6275384,7.019993305206299,0.028874056723481843,1739502646.6275399,7.019993305206299,0.20717696261414167,1739502646.6275413,7.019993305206299,0.055662891645641754,1739502646.6275425,7.019993305206299,2.1181629113955345,1739502646.6275442,7.019993305206299,0.0,1739502646.6275454,7.019993305206299,0.015620318168587222,1739502646.6275468,7.019993305206299,6.273297318760298,1739502646.6275482,7.019993305206299,2.1025425932269473 +1739502646.6477141,7.0399932861328125,12.356853206070472,1739502646.6477168,7.0399932861328125,-0.31801835578835913,1739502646.64772,7.0399932861328125,11.50165405086277,1739502646.6477234,7.0399932861328125,17.70080430248516,1739502646.6477249,7.0399932861328125,-0.16367391342449444,1739502646.6477268,7.0399932861328125,0.028874056723481843,1739502646.6477284,7.0399932861328125,0.20717696261414167,1739502646.6477299,7.0399932861328125,0.055662891645641754,1739502646.6477313,7.0399932861328125,2.1181629113955345,1739502646.6477332,7.0399932861328125,0.0,1739502646.6477346,7.0399932861328125,0.015620318168587222,1739502646.647736,7.0399932861328125,6.273297318760298,1739502646.6477373,7.0399932861328125,2.1025425932269473 +1739502646.6719131,7.059993267059326,12.356853206070472,1739502646.671922,7.059993267059326,-0.31801835578835913,1739502646.6719325,7.059993267059326,11.50165405086277,1739502646.671943,7.059993267059326,17.70080430248516,1739502646.6719477,7.059993267059326,-0.16367391342449444,1739502646.671954,7.059993267059326,0.028874056723481843,1739502646.6719587,7.059993267059326,0.20717696261414167,1739502646.6719635,7.059993267059326,0.055662891645641754,1739502646.671968,7.059993267059326,2.1181629113955345,1739502646.671974,7.059993267059326,0.0,1739502646.6719787,7.059993267059326,0.015620318168587222,1739502646.671984,7.059993267059326,6.273297318760298,1739502646.6719887,7.059993267059326,2.1025425932269473 +1739502646.6974444,7.069993257522583,12.356853206070472,1739502646.6974528,7.069993257522583,-0.31801835578835913,1739502646.6974638,7.069993257522583,11.50165405086277,1739502646.6974747,7.069993257522583,17.70080430248516,1739502646.6974797,7.069993257522583,-0.16367391342449444,1739502646.6974862,7.069993257522583,0.028874056723481843,1739502646.6974912,7.069993257522583,0.20717696261414167,1739502646.6974957,7.069993257522583,0.055662891645641754,1739502646.697501,7.069993257522583,2.1181629113955345,1739502646.6975067,7.069993257522583,0.0,1739502646.6975114,7.069993257522583,0.015620318168587222,1739502646.6975164,7.069993257522583,6.273297318760298,1739502646.6975217,7.069993257522583,2.1025425932269473 +1739502646.7160501,7.0999932289123535,12.356853206070472,1739502646.7160592,7.0999932289123535,-0.31801835578835913,1739502646.7160695,7.0999932289123535,11.50165405086277,1739502646.716079,7.0999932289123535,17.70080430248516,1739502646.7160838,7.0999932289123535,-0.16367391342449444,1739502646.71609,7.0999932289123535,0.028874056723481843,1739502646.7160947,7.0999932289123535,0.20717696261414167,1739502646.7160997,7.0999932289123535,0.055662891645641754,1739502646.7161043,7.0999932289123535,2.1181629113955345,1739502646.71611,7.0999932289123535,0.0,1739502646.7161152,7.0999932289123535,0.015620318168587222,1739502646.7161205,7.0999932289123535,6.273297318760298,1739502646.7161255,7.0999932289123535,2.1025425932269473 +1739502646.7352211,7.119993209838867,12.588211153110645,1739502646.7352269,7.119993209838867,-0.3202177641781869,1739502646.7352343,7.119993209838867,11.82416530452078,1739502646.7352414,7.119993209838867,18.026775403432783,1739502646.7352448,7.119993209838867,-0.15988707660945364,1739502646.735249,7.119993209838867,0.029471797542037804,1739502646.7352526,7.119993209838867,0.2095329331426326,1739502646.735256,7.119993209838867,0.0543525828013183,1739502646.735259,7.119993209838867,2.1141744077800144,1739502646.7352636,7.119993209838867,0.0,1739502646.735267,7.119993209838867,0.007284638436019611,1739502646.7352705,7.119993209838867,6.274137058794159,1739502646.735274,7.119993209838867,2.104284867719661 +1739502646.7547808,7.139993190765381,12.588211153110645,1739502646.7547867,7.139993190765381,-0.3202177641781869,1739502646.7547946,7.139993190765381,11.82416530452078,1739502646.7548018,7.139993190765381,18.026775403432783,1739502646.7548053,7.139993190765381,-0.15988707660945364,1739502646.7548096,7.139993190765381,0.029471797542037804,1739502646.7548132,7.139993190765381,0.2095329331426326,1739502646.7548165,7.139993190765381,0.0543525828013183,1739502646.7548199,7.139993190765381,2.1141744077800144,1739502646.754824,7.139993190765381,0.0,1739502646.7548273,7.139993190765381,0.009889540060353585,1739502646.754831,7.139993190765381,6.274137058794159,1739502646.7548344,7.139993190765381,2.104284867719661 +1739502646.7740047,7.1599931716918945,12.588211153110645,1739502646.7740085,7.1599931716918945,-0.3202177641781869,1739502646.7740135,7.1599931716918945,11.82416530452078,1739502646.774018,7.1599931716918945,18.026775403432783,1739502646.7740202,7.1599931716918945,-0.15988707660945364,1739502646.7740228,7.1599931716918945,0.029471797542037804,1739502646.7740252,7.1599931716918945,0.2095329331426326,1739502646.7740273,7.1599931716918945,0.0543525828013183,1739502646.7740293,7.1599931716918945,2.1141744077800144,1739502646.7740316,7.1599931716918945,0.0,1739502646.7740335,7.1599931716918945,0.009889540060353585,1739502646.774036,7.1599931716918945,6.274137058794159,1739502646.7740383,7.1599931716918945,2.104284867719661 +1739502646.7926183,7.179993152618408,12.588211153110645,1739502646.792621,7.179993152618408,-0.3202177641781869,1739502646.7926245,7.179993152618408,11.82416530452078,1739502646.792627,7.179993152618408,18.026775403432783,1739502646.7926288,7.179993152618408,-0.15988707660945364,1739502646.7926304,7.179993152618408,0.029471797542037804,1739502646.7926323,7.179993152618408,0.2095329331426326,1739502646.7926338,7.179993152618408,0.0543525828013183,1739502646.7926352,7.179993152618408,2.1141744077800144,1739502646.7926369,7.179993152618408,0.0,1739502646.7926385,7.179993152618408,0.009889540060353585,1739502646.79264,7.179993152618408,6.274137058794159,1739502646.7926419,7.179993152618408,2.104284867719661 +1739502646.8127246,7.199993133544922,12.588211153110645,1739502646.8127272,7.199993133544922,-0.3202177641781869,1739502646.8127303,7.199993133544922,11.82416530452078,1739502646.8127332,7.199993133544922,18.026775403432783,1739502646.8127344,7.199993133544922,-0.15988707660945364,1739502646.8127365,7.199993133544922,0.029471797542037804,1739502646.8127377,7.199993133544922,0.2095329331426326,1739502646.8127394,7.199993133544922,0.0543525828013183,1739502646.8127406,7.199993133544922,2.1141744077800144,1739502646.8127422,7.199993133544922,0.0,1739502646.8127437,7.199993133544922,0.009889540060353585,1739502646.8127453,7.199993133544922,6.274137058794159,1739502646.8127468,7.199993133544922,2.104284867719661 +1739502646.8337286,7.2199931144714355,12.81972916386827,1739502646.8337312,7.2199931144714355,-0.32222426838813956,1739502646.8337338,7.2199931144714355,12.23101745395152,1739502646.8337367,7.2199931144714355,18.43570226335801,1739502646.833738,7.2199931144714355,-0.15108829561069984,1739502646.8337398,7.2199931144714355,0.03046364832558692,1739502646.833741,7.2199931144714355,0.21722845167729607,1739502646.8337424,7.2199931144714355,0.05284207578673544,1739502646.8337436,7.2199931144714355,2.101198656145714,1739502646.8337452,7.2199931144714355,0.0,1739502646.8337464,7.2199931144714355,-0.010564439730098948,1739502646.8337476,7.2199931144714355,6.27497679882802,1739502646.8337493,7.2199931144714355,2.105371223000458 +1739502646.8521674,7.239993095397949,12.81972916386827,1739502646.8521695,7.239993095397949,-0.32222426838813956,1739502646.8521724,7.239993095397949,12.23101745395152,1739502646.852175,7.239993095397949,18.43570226335801,1739502646.8521764,7.239993095397949,-0.15108829561069984,1739502646.8521779,7.239993095397949,0.03046364832558692,1739502646.8521795,7.239993095397949,0.21722845167729607,1739502646.852181,7.239993095397949,0.05284207578673544,1739502646.852182,7.239993095397949,2.101198656145714,1739502646.8521836,7.239993095397949,0.0,1739502646.8521848,7.239993095397949,-0.0041725668547440975,1739502646.8521862,7.239993095397949,6.27497679882802,1739502646.8521876,7.239993095397949,2.105371223000458 +1739502646.8758228,7.259993076324463,12.81972916386827,1739502646.8758314,7.259993076324463,-0.32222426838813956,1739502646.8758419,7.259993076324463,12.23101745395152,1739502646.8758516,7.259993076324463,18.43570226335801,1739502646.8758564,7.259993076324463,-0.15108829561069984,1739502646.8758626,7.259993076324463,0.03046364832558692,1739502646.8758676,7.259993076324463,0.21722845167729607,1739502646.8758724,7.259993076324463,0.05284207578673544,1739502646.8758771,7.259993076324463,2.101198656145714,1739502646.8758821,7.259993076324463,0.0,1739502646.8758872,7.259993076324463,-0.0041725668547440975,1739502646.875892,7.259993076324463,6.27497679882802,1739502646.8758976,7.259993076324463,2.105371223000458 +1739502646.8962688,7.279993057250977,12.81972916386827,1739502646.8962812,7.279993057250977,-0.32222426838813956,1739502646.8962944,7.279993057250977,12.23101745395152,1739502646.8963068,7.279993057250977,18.43570226335801,1739502646.8963127,7.279993057250977,-0.15108829561069984,1739502646.8963203,7.279993057250977,0.03046364832558692,1739502646.8963265,7.279993057250977,0.21722845167729607,1739502646.8963325,7.279993057250977,0.05284207578673544,1739502646.896338,7.279993057250977,2.101198656145714,1739502646.896345,7.279993057250977,0.0,1739502646.8963513,7.279993057250977,-0.0041725668547440975,1739502646.8963578,7.279993057250977,6.27497679882802,1739502646.8963642,7.279993057250977,2.105371223000458 +1739502646.9179351,7.29999303817749,12.81972916386827,1739502646.9179435,7.29999303817749,-0.32222426838813956,1739502646.9179537,7.29999303817749,12.23101745395152,1739502646.9179637,7.29999303817749,18.43570226335801,1739502646.9179688,7.29999303817749,-0.15108829561069984,1739502646.9179747,7.29999303817749,0.03046364832558692,1739502646.9179797,7.29999303817749,0.21722845167729607,1739502646.9179845,7.29999303817749,0.05284207578673544,1739502646.917989,7.29999303817749,2.101198656145714,1739502646.9179945,7.29999303817749,0.0,1739502646.9179993,7.29999303817749,-0.0041725668547440975,1739502646.918007,7.29999303817749,6.27497679882802,1739502646.9180121,7.29999303817749,2.105371223000458 +1739502646.950003,7.319993019104004,12.81972916386827,1739502646.9500122,7.319993019104004,-0.32222426838813956,1739502646.9500232,7.319993019104004,12.23101745395152,1739502646.9500332,7.319993019104004,18.43570226335801,1739502646.9500377,7.319993019104004,-0.15108829561069984,1739502646.9500444,7.319993019104004,0.03046364832558692,1739502646.9500492,7.319993019104004,0.21722845167729607,1739502646.9500542,7.319993019104004,0.05284207578673544,1739502646.9500587,7.319993019104004,2.101198656145714,1739502646.9500644,7.319993019104004,0.0,1739502646.9500692,7.319993019104004,-0.0041725668547440975,1739502646.9500747,7.319993019104004,6.27497679882802,1739502646.9500794,7.319993019104004,2.105371223000458 +1739502646.9673853,7.349992990493774,13.051277916417405,1739502646.9673944,7.349992990493774,-0.32403659726563827,1739502646.9674056,7.349992990493774,12.277099280366551,1739502646.9674158,7.349992990493774,18.480610657379803,1739502646.9674206,7.349992990493774,-0.1503398223770033,1739502646.9674268,7.349992990493774,0.031981379593748485,1739502646.967432,7.349992990493774,0.21369919218079064,1739502646.9674368,7.349992990493774,0.055613106567178924,1739502646.9674413,7.349992990493774,2.1071395792718857,1739502646.967447,7.349992990493774,0.0,1739502646.9674525,7.349992990493774,0.005317648192992995,1739502646.9674578,7.349992990493774,6.275816538861881,1739502646.9674633,7.349992990493774,2.104787625225771 +1739502646.9953523,7.369992971420288,13.051277916417405,1739502646.9953654,7.369992971420288,-0.32403659726563827,1739502646.9953814,7.369992971420288,12.277099280366551,1739502646.995396,7.369992971420288,18.480610657379803,1739502646.9954033,7.369992971420288,-0.1503398223770033,1739502646.9954133,7.369992971420288,0.031981379593748485,1739502646.995422,7.369992971420288,0.21369919218079064,1739502646.9954307,7.369992971420288,0.055613106567178924,1739502646.9954395,7.369992971420288,2.1071395792718857,1739502646.9954486,7.369992971420288,0.0,1739502646.9954572,7.369992971420288,0.002351954046114546,1739502646.9954662,7.369992971420288,6.275816538861881,1739502646.9954753,7.369992971420288,2.104787625225771 +1739502647.009616,7.389992952346802,13.051277916417405,1739502647.0096195,7.389992952346802,-0.32403659726563827,1739502647.0096233,7.389992952346802,12.277099280366551,1739502647.009627,7.389992952346802,18.480610657379803,1739502647.009629,7.389992952346802,-0.1503398223770033,1739502647.0096312,7.389992952346802,0.031981379593748485,1739502647.009633,7.389992952346802,0.21369919218079064,1739502647.0096347,7.389992952346802,0.055613106567178924,1739502647.0096366,7.389992952346802,2.1071395792718857,1739502647.0096385,7.389992952346802,0.0,1739502647.0096405,7.389992952346802,0.002351954046114546,1739502647.0096426,7.389992952346802,6.275816538861881,1739502647.0096445,7.389992952346802,2.104787625225771 +1739502647.0282295,7.409992933273315,13.051277916417405,1739502647.028232,7.409992933273315,-0.32403659726563827,1739502647.028235,7.409992933273315,12.277099280366551,1739502647.0282376,7.409992933273315,18.480610657379803,1739502647.028239,7.409992933273315,-0.1503398223770033,1739502647.0282407,7.409992933273315,0.031981379593748485,1739502647.028242,7.409992933273315,0.21369919218079064,1739502647.0282438,7.409992933273315,0.055613106567178924,1739502647.0282452,7.409992933273315,2.1071395792718857,1739502647.0282469,7.409992933273315,0.0,1739502647.028248,7.409992933273315,0.002351954046114546,1739502647.0282493,7.409992933273315,6.275816538861881,1739502647.0282507,7.409992933273315,2.104787625225771 +1739502647.0487344,7.429992914199829,13.051277916417405,1739502647.0487373,7.429992914199829,-0.32403659726563827,1739502647.0487404,7.429992914199829,12.277099280366551,1739502647.048743,7.429992914199829,18.480610657379803,1739502647.0487442,7.429992914199829,-0.1503398223770033,1739502647.0487456,7.429992914199829,0.031981379593748485,1739502647.0487652,7.429992914199829,0.21369919218079064,1739502647.0487664,7.429992914199829,0.055613106567178924,1739502647.0487678,7.429992914199829,2.1071395792718857,1739502647.0487692,7.429992914199829,0.0,1739502647.048771,7.429992914199829,0.002351954046114546,1739502647.048772,7.429992914199829,6.275816538861881,1739502647.0487735,7.429992914199829,2.104787625225771 +1739502647.0686114,7.449992895126343,13.28280398584204,1739502647.0686135,7.449992895126343,-0.32565431018180746,1739502647.0686164,7.449992895126343,12.688960607886452,1739502647.068619,7.449992895126343,18.892765764692122,1739502647.0686204,7.449992895126343,-0.14225585588269696,1739502647.068622,7.449992895126343,0.03267993052023883,1739502647.0686233,7.449992895126343,0.22002188423683777,1739502647.0686247,7.449992895126343,0.05362868289763702,1739502647.068626,7.449992895126343,2.0965082536348603,1739502647.0686276,7.449992895126343,0.0,1739502647.068629,7.449992895126343,-0.013385462096254387,1739502647.0686302,7.449992895126343,6.276656278895742,1739502647.0686316,7.449992895126343,2.104975769962168 +1739502647.089679,7.4699928760528564,13.28280398584204,1739502647.0896819,7.4699928760528564,-0.32565431018180746,1739502647.0896857,7.4699928760528564,12.688960607886452,1739502647.0896883,7.4699928760528564,18.892765764692122,1739502647.0896902,7.4699928760528564,-0.14225585588269696,1739502647.0896916,7.4699928760528564,0.03267993052023883,1739502647.0896928,7.4699928760528564,0.22002188423683777,1739502647.0896945,7.4699928760528564,0.05362868289763702,1739502647.089696,7.4699928760528564,2.0965082536348603,1739502647.0896978,7.4699928760528564,0.0,1739502647.0896993,7.4699928760528564,-0.008467516327307578,1739502647.089701,7.4699928760528564,6.276656278895742,1739502647.0897026,7.4699928760528564,2.104975769962168 +1739502647.109543,7.48999285697937,13.28280398584204,1739502647.109547,7.48999285697937,-0.32565431018180746,1739502647.1095517,7.48999285697937,12.688960607886452,1739502647.1095567,7.48999285697937,18.892765764692122,1739502647.1095598,7.48999285697937,-0.14225585588269696,1739502647.1095636,7.48999285697937,0.03267993052023883,1739502647.109567,7.48999285697937,0.22002188423683777,1739502647.1095705,7.48999285697937,0.05362868289763702,1739502647.1095738,7.48999285697937,2.0965082536348603,1739502647.1095774,7.48999285697937,0.0,1739502647.1095808,7.48999285697937,-0.008467516327307578,1739502647.1095843,7.48999285697937,6.276656278895742,1739502647.109588,7.48999285697937,2.104975769962168 +1739502647.1281416,7.509992837905884,13.28280398584204,1739502647.1281435,7.509992837905884,-0.32565431018180746,1739502647.1281464,7.509992837905884,12.688960607886452,1739502647.1281495,7.509992837905884,18.892765764692122,1739502647.128151,7.509992837905884,-0.14225585588269696,1739502647.1281528,7.509992837905884,0.03267993052023883,1739502647.128154,7.509992837905884,0.22002188423683777,1739502647.1281557,7.509992837905884,0.05362868289763702,1739502647.128157,7.509992837905884,2.0965082536348603,1739502647.1281588,7.509992837905884,0.0,1739502647.12816,7.509992837905884,-0.008467516327307578,1739502647.1281612,7.509992837905884,6.276656278895742,1739502647.1281629,7.509992837905884,2.104975769962168 +1739502647.148187,7.5299928188323975,13.28280398584204,1739502647.1481898,7.5299928188323975,-0.32565431018180746,1739502647.1481924,7.5299928188323975,12.688960607886452,1739502647.148195,7.5299928188323975,18.892765764692122,1739502647.1481965,7.5299928188323975,-0.14225585588269696,1739502647.1481981,7.5299928188323975,0.03267993052023883,1739502647.1481993,7.5299928188323975,0.22002188423683777,1739502647.148201,7.5299928188323975,0.05362868289763702,1739502647.148202,7.5299928188323975,2.0965082536348603,1739502647.148204,7.5299928188323975,0.0,1739502647.1482053,7.5299928188323975,-0.008467516327307578,1739502647.148207,7.5299928188323975,6.276656278895742,1739502647.1482081,7.5299928188323975,2.104975769962168 +1739502647.1682055,7.549992799758911,13.51430292254529,1739502647.1682086,7.549992799758911,-0.327077435525025,1739502647.1682115,7.549992799758911,12.714658412985855,1739502647.1682143,7.549992799758911,18.916620695082585,1739502647.1682155,7.549992799758911,-0.1416594826229354,1739502647.1682172,7.549992799758911,0.03430845888836994,1739502647.1682186,7.549992799758911,0.21615012932526323,1739502647.1682198,7.549992799758911,0.05680587610406679,1739502647.1682212,7.549992799758911,2.103012053785726,1739502647.1682227,7.549992799758911,0.0,1739502647.1682243,7.549992799758911,0.0023274116239102153,1739502647.1682255,7.549992799758911,6.277496018929604,1739502647.1682267,7.549992799758911,2.104058059358356 +1739502647.188831,7.569992780685425,13.51430292254529,1739502647.1888342,7.569992780685425,-0.327077435525025,1739502647.188838,7.569992780685425,12.714658412985855,1739502647.1888409,7.569992780685425,18.916620695082585,1739502647.1888425,7.569992780685425,-0.1416594826229354,1739502647.1888444,7.569992780685425,0.03430845888836994,1739502647.188846,7.569992780685425,0.21615012932526323,1739502647.1888475,7.569992780685425,0.05680587610406679,1739502647.188849,7.569992780685425,2.103012053785726,1739502647.1888504,7.569992780685425,0.0,1739502647.188852,7.569992780685425,-0.0010460055726300155,1739502647.1888537,7.569992780685425,6.277496018929604,1739502647.1888556,7.569992780685425,2.104058059358356 +1739502647.216932,7.599992752075195,13.51430292254529,1739502647.2169404,7.599992752075195,-0.327077435525025,1739502647.2169502,7.599992752075195,12.714658412985855,1739502647.2169607,7.599992752075195,18.916620695082585,1739502647.2169654,7.599992752075195,-0.1416594826229354,1739502647.2169719,7.599992752075195,0.03430845888836994,1739502647.2169766,7.599992752075195,0.21615012932526323,1739502647.2169812,7.599992752075195,0.05680587610406679,1739502647.216986,7.599992752075195,2.103012053785726,1739502647.2169917,7.599992752075195,0.0,1739502647.2169967,7.599992752075195,-0.0010460055726300155,1739502647.2170017,7.599992752075195,6.277496018929604,1739502647.217007,7.599992752075195,2.104058059358356 +1739502647.237715,7.609992742538452,13.51430292254529,1739502647.2377234,7.609992742538452,-0.327077435525025,1739502647.237734,7.609992742538452,12.714658412985855,1739502647.237744,7.609992742538452,18.916620695082585,1739502647.237749,7.609992742538452,-0.1416594826229354,1739502647.2377555,7.609992742538452,0.03430845888836994,1739502647.2377608,7.609992742538452,0.21615012932526323,1739502647.2377658,7.609992742538452,0.05680587610406679,1739502647.2377706,7.609992742538452,2.103012053785726,1739502647.237776,7.609992742538452,0.0,1739502647.237781,7.609992742538452,-0.0010460055726300155,1739502647.237786,7.609992742538452,6.277496018929604,1739502647.2377913,7.609992742538452,2.104058059358356 +1739502647.2602363,7.639992713928223,13.51430292254529,1739502647.260245,7.639992713928223,-0.327077435525025,1739502647.2602563,7.639992713928223,12.714658412985855,1739502647.2602665,7.639992713928223,18.916620695082585,1739502647.2602713,7.639992713928223,-0.1416594826229354,1739502647.2602777,7.639992713928223,0.03430845888836994,1739502647.2602832,7.639992713928223,0.21615012932526323,1739502647.2602885,7.639992713928223,0.05680587610406679,1739502647.260293,7.639992713928223,2.103012053785726,1739502647.2602987,7.639992713928223,0.0,1739502647.260304,7.639992713928223,-0.0010460055726300155,1739502647.2603092,7.639992713928223,6.277496018929604,1739502647.2603147,7.639992713928223,2.104058059358356 +1739502647.279501,7.659992694854736,13.745746689569607,1739502647.2795093,7.659992694854736,-0.32830585579390004,1739502647.2795198,7.659992694854736,12.936822403958931,1739502647.27953,7.659992694854736,19.138635003697292,1739502647.279535,7.659992694854736,-0.13716323250654947,1739502647.2795413,7.659992694854736,0.035428629737673446,1739502647.2795463,7.659992694854736,0.2172933450261816,1739502647.279551,7.659992694854736,0.05730159869742748,1739502647.2795558,7.659992694854736,2.1010895759231936,1739502647.2795618,7.659992694854736,0.0,1739502647.2795665,7.659992694854736,-0.0037730260155186763,1739502647.279572,7.659992694854736,6.278335758963465,1739502647.279577,7.659992694854736,2.1040104074915673 +1739502647.2996824,7.67999267578125,13.745746689569607,1739502647.29969,7.67999267578125,-0.32830585579390004,1739502647.2997005,7.67999267578125,12.936822403958931,1739502647.2997108,7.67999267578125,19.138635003697292,1739502647.2997158,7.67999267578125,-0.13716323250654947,1739502647.299722,7.67999267578125,0.035428629737673446,1739502647.299727,7.67999267578125,0.2172933450261816,1739502647.2997317,7.67999267578125,0.05730159869742748,1739502647.2997363,7.67999267578125,2.1010895759231936,1739502647.299742,7.67999267578125,0.0,1739502647.2997468,7.67999267578125,-0.0029208315683737496,1739502647.299752,7.67999267578125,6.278335758963465,1739502647.2997572,7.67999267578125,2.1040104074915673 +1739502647.3257318,7.699992656707764,13.745746689569607,1739502647.325742,7.699992656707764,-0.32830585579390004,1739502647.3257527,7.699992656707764,12.936822403958931,1739502647.3257642,7.699992656707764,19.138635003697292,1739502647.3257697,7.699992656707764,-0.13716323250654947,1739502647.3257773,7.699992656707764,0.035428629737673446,1739502647.3257837,7.699992656707764,0.2172933450261816,1739502647.3257895,7.699992656707764,0.05730159869742748,1739502647.3257954,7.699992656707764,2.1010895759231936,1739502647.325802,7.699992656707764,0.0,1739502647.325809,7.699992656707764,-0.0029208315683737496,1739502647.3258152,7.699992656707764,6.278335758963465,1739502647.3258219,7.699992656707764,2.1040104074915673 +1739502647.354194,7.729992628097534,13.745746689569607,1739502647.3541982,7.729992628097534,-0.32830585579390004,1739502647.354204,7.729992628097534,12.936822403958931,1739502647.354209,7.729992628097534,19.138635003697292,1739502647.3542116,7.729992628097534,-0.13716323250654947,1739502647.354215,7.729992628097534,0.035428629737673446,1739502647.3542175,7.729992628097534,0.2172933450261816,1739502647.3542206,7.729992628097534,0.05730159869742748,1739502647.3542228,7.729992628097534,2.1010895759231936,1739502647.3542259,7.729992628097534,0.0,1739502647.3542285,7.729992628097534,-0.0029208315683737496,1739502647.3542314,7.729992628097534,6.278335758963465,1739502647.3542337,7.729992628097534,2.1040104074915673 +1739502647.3748627,7.759992599487305,13.745746689569607,1739502647.3748662,7.759992599487305,-0.32830585579390004,1739502647.3748705,7.759992599487305,12.936822403958931,1739502647.3748744,7.759992599487305,19.138635003697292,1739502647.3748763,7.759992599487305,-0.13716323250654947,1739502647.3748786,7.759992599487305,0.035428629737673446,1739502647.3748806,7.759992599487305,0.2172933450261816,1739502647.3748822,7.759992599487305,0.05730159869742748,1739502647.3748841,7.759992599487305,2.1010895759231936,1739502647.3748865,7.759992599487305,0.0,1739502647.3748882,7.759992599487305,-0.0029208315683737496,1739502647.37489,7.759992599487305,6.278335758963465,1739502647.374892,7.759992599487305,2.1040104074915673 +1739502647.3940675,7.779992580413818,13.977167884735906,1739502647.3940706,7.779992580413818,-0.32933981997671324,1739502647.3940747,7.779992580413818,13.159872694999684,1739502647.3940783,7.779992580413818,19.360999554471785,1739502647.39408,7.779992580413818,-0.135,1739502647.394082,7.779992580413818,0.03608126893478386,1739502647.3940837,7.779992580413818,0.21592633205666625,1739502647.3940856,7.779992580413818,0.057130215964347475,1739502647.3940873,7.779992580413818,2.1033886061760496,1739502647.3940892,7.779992580413818,0.0,1739502647.394091,7.779992580413818,0.0009129761086154602,1739502647.394093,7.779992580413818,6.279175498997326,1739502647.394095,7.779992580413818,2.1036736957520064 +1739502647.4138517,7.799992561340332,13.977167884735906,1739502647.4138553,7.799992561340332,-0.32933981997671324,1739502647.4138591,7.799992561340332,13.159872694999684,1739502647.4138627,7.799992561340332,19.360999554471785,1739502647.4138644,7.799992561340332,-0.135,1739502647.4138668,7.799992561340332,0.03608126893478386,1739502647.413869,7.799992561340332,0.21592633205666625,1739502647.4138706,7.799992561340332,0.057130215964347475,1739502647.4138725,7.799992561340332,2.1033886061760496,1739502647.4138744,7.799992561340332,0.0,1739502647.4138765,7.799992561340332,-0.0002850895759567429,1739502647.4138784,7.799992561340332,6.279175498997326,1739502647.4138803,7.799992561340332,2.1036736957520064 +1739502647.4340024,7.819992542266846,13.977167884735906,1739502647.4340062,7.819992542266846,-0.32933981997671324,1739502647.4340105,7.819992542266846,13.159872694999684,1739502647.4340146,7.819992542266846,19.360999554471785,1739502647.4340162,7.819992542266846,-0.135,1739502647.4340189,7.819992542266846,0.03608126893478386,1739502647.4340208,7.819992542266846,0.21592633205666625,1739502647.4340231,7.819992542266846,0.057130215964347475,1739502647.434025,7.819992542266846,2.1033886061760496,1739502647.434027,7.819992542266846,0.0,1739502647.4340289,7.819992542266846,-0.0002850895759567429,1739502647.4340308,7.819992542266846,6.279175498997326,1739502647.4340327,7.819992542266846,2.1036736957520064 +1739502647.453857,7.839992523193359,13.977167884735906,1739502647.4538596,7.839992523193359,-0.32933981997671324,1739502647.4538624,7.839992523193359,13.159872694999684,1739502647.4538653,7.839992523193359,19.360999554471785,1739502647.4538665,7.839992523193359,-0.135,1739502647.4538684,7.839992523193359,0.03608126893478386,1739502647.4538698,7.839992523193359,0.21592633205666625,1739502647.453871,7.839992523193359,0.057130215964347475,1739502647.4538727,7.839992523193359,2.1033886061760496,1739502647.453874,7.839992523193359,0.0,1739502647.4538755,7.839992523193359,-0.0002850895759567429,1739502647.453877,7.839992523193359,6.279175498997326,1739502647.4538786,7.839992523193359,2.1036736957520064 +1739502647.47379,7.859992504119873,13.977167884735906,1739502647.473792,7.859992504119873,-0.32933981997671324,1739502647.4737947,7.859992504119873,13.159872694999684,1739502647.4737973,7.859992504119873,19.360999554471785,1739502647.4737988,7.859992504119873,-0.135,1739502647.4738,7.859992504119873,0.03608126893478386,1739502647.4738011,7.859992504119873,0.21592633205666625,1739502647.4738026,7.859992504119873,0.057130215964347475,1739502647.4738038,7.859992504119873,2.1033886061760496,1739502647.4738054,7.859992504119873,0.0,1739502647.4738064,7.859992504119873,-0.0002850895759567429,1739502647.4738076,7.859992504119873,6.279175498997326,1739502647.473809,7.859992504119873,2.1036736957520064 +1739502647.4935489,7.879992485046387,14.208568333558958,1739502647.4935517,7.879992485046387,-0.3301793696639832,1739502647.4935544,7.879992485046387,13.483313544662195,1739502647.4935575,7.879992485046387,19.684364112717045,1739502647.493559,7.879992485046387,-0.1330816520196584,1739502647.4935608,7.879992485046387,0.035978818823874,1739502647.4935622,7.879992485046387,0.2144553440078064,1739502647.4935637,7.879992485046387,0.054852055061995586,1739502647.4935648,7.879992485046387,2.1058653107728103,1739502647.4935665,7.879992485046387,0.0,1739502647.493568,7.879992485046387,0.0033657545566339623,1739502647.4935696,7.879992485046387,6.280015239031187,1739502647.4935708,7.879992485046387,2.1036404457556364 +1739502647.5133889,7.8999924659729,14.208568333558958,1739502647.5133908,7.8999924659729,-0.3301793696639832,1739502647.5133932,7.8999924659729,13.483313544662195,1739502647.5133958,7.8999924659729,19.684364112717045,1739502647.513397,7.8999924659729,-0.1330816520196584,1739502647.5133984,7.8999924659729,0.035978818823874,1739502647.5133998,7.8999924659729,0.2144553440078064,1739502647.513401,7.8999924659729,0.054852055061995586,1739502647.5134022,7.8999924659729,2.1058653107728103,1739502647.5134037,7.8999924659729,0.0,1739502647.5134046,7.8999924659729,0.0022248650171738937,1739502647.513406,7.8999924659729,6.280015239031187,1739502647.5134072,7.8999924659729,2.1036404457556364 +1739502647.53335,7.919992446899414,14.208568333558958,1739502647.533352,7.919992446899414,-0.3301793696639832,1739502647.5333548,7.919992446899414,13.483313544662195,1739502647.5333574,7.919992446899414,19.684364112717045,1739502647.5333586,7.919992446899414,-0.1330816520196584,1739502647.5333602,7.919992446899414,0.035978818823874,1739502647.5333614,7.919992446899414,0.2144553440078064,1739502647.533363,7.919992446899414,0.054852055061995586,1739502647.5333643,7.919992446899414,2.1058653107728103,1739502647.533366,7.919992446899414,0.0,1739502647.5333674,7.919992446899414,0.0022248650171738937,1739502647.5333686,7.919992446899414,6.280015239031187,1739502647.53337,7.919992446899414,2.1036404457556364 +1739502647.5532742,7.939992427825928,14.208568333558958,1739502647.553276,7.939992427825928,-0.3301793696639832,1739502647.553279,7.939992427825928,13.483313544662195,1739502647.5532815,7.939992427825928,19.684364112717045,1739502647.5532827,7.939992427825928,-0.1330816520196584,1739502647.5532846,7.939992427825928,0.035978818823874,1739502647.5532858,7.939992427825928,0.2144553440078064,1739502647.5532873,7.939992427825928,0.054852055061995586,1739502647.5532885,7.939992427825928,2.1058653107728103,1739502647.5532897,7.939992427825928,0.0,1739502647.553291,7.939992427825928,0.0022248650171738937,1739502647.5532923,7.939992427825928,6.280015239031187,1739502647.5532935,7.939992427825928,2.1036404457556364 +1739502647.5731146,7.959992408752441,14.208568333558958,1739502647.573117,7.959992408752441,-0.3301793696639832,1739502647.5731194,7.959992408752441,13.483313544662195,1739502647.5731223,7.959992408752441,19.684364112717045,1739502647.5731237,7.959992408752441,-0.1330816520196584,1739502647.5731251,7.959992408752441,0.035978818823874,1739502647.5731263,7.959992408752441,0.2144553440078064,1739502647.5731277,7.959992408752441,0.054852055061995586,1739502647.573129,7.959992408752441,2.1058653107728103,1739502647.5731306,7.959992408752441,0.0,1739502647.5731318,7.959992408752441,0.0022248650171738937,1739502647.573133,7.959992408752441,6.280015239031187,1739502647.5731347,7.959992408752441,2.1036404457556364 +1739502647.59343,7.979992389678955,14.208568333558958,1739502647.5934331,7.979992389678955,-0.3301793696639832,1739502647.5934362,7.979992389678955,13.483313544662195,1739502647.5934389,7.979992389678955,19.684364112717045,1739502647.5934403,7.979992389678955,-0.1330816520196584,1739502647.593442,7.979992389678955,0.035978818823874,1739502647.5934434,7.979992389678955,0.2144553440078064,1739502647.5934448,7.979992389678955,0.054852055061995586,1739502647.5934458,7.979992389678955,2.1058653107728103,1739502647.5934477,7.979992389678955,0.0,1739502647.5934489,7.979992389678955,0.0022248650171738937,1739502647.5934503,7.979992389678955,6.280015239031187,1739502647.5934515,7.979992389678955,2.1036404457556364 +1739502647.6133323,7.999992370605469,14.43998223845049,1739502647.6133342,7.999992370605469,-0.33082463651332006,1739502647.613337,7.999992370605469,13.809209993712091,1739502647.6133397,7.999992370605469,20.010784410196816,1739502647.6133409,7.999992370605469,-0.131,1739502647.6133428,7.999992370605469,0.03585462103522739,1739502647.613344,7.999992370605469,0.21280587911870036,1739502647.6133456,7.999992370605469,0.052590397165771186,1739502647.6133466,7.999992370605469,2.1086459857326485,1739502647.613348,7.999992370605469,0.0,1739502647.6133494,7.999992370605469,0.0058822397973677856,1739502647.6133509,7.999992370605469,6.280854979065048,1739502647.6133525,7.999992370605469,2.103906676303455 +1739502647.6333323,8.019992351531982,14.43998223845049,1739502647.6333346,8.019992351531982,-0.33082463651332006,1739502647.633337,8.019992351531982,13.809209993712091,1739502647.63334,8.019992351531982,20.010784410196816,1739502647.633341,8.019992351531982,-0.131,1739502647.633343,8.019992351531982,0.03585462103522739,1739502647.6333442,8.019992351531982,0.21280587911870036,1739502647.6333458,8.019992351531982,0.052590397165771186,1739502647.633347,8.019992351531982,2.1086459857326485,1739502647.6333487,8.019992351531982,0.0,1739502647.63335,8.019992351531982,0.00473930942919365,1739502647.633351,8.019992351531982,6.280854979065048,1739502647.6333525,8.019992351531982,2.103906676303455 +1739502647.6532967,8.039992332458496,14.43998223845049,1739502647.6532986,8.039992332458496,-0.33082463651332006,1739502647.6533015,8.039992332458496,13.809209993712091,1739502647.653304,8.039992332458496,20.010784410196816,1739502647.6533055,8.039992332458496,-0.131,1739502647.6533077,8.039992332458496,0.03585462103522739,1739502647.6533089,8.039992332458496,0.21280587911870036,1739502647.6533103,8.039992332458496,0.052590397165771186,1739502647.6533115,8.039992332458496,2.1086459857326485,1739502647.653313,8.039992332458496,0.0,1739502647.6533144,8.039992332458496,0.00473930942919365,1739502647.6533155,8.039992332458496,6.280854979065048,1739502647.6533172,8.039992332458496,2.103906676303455 +1739502647.6732855,8.05999231338501,14.43998223845049,1739502647.6732876,8.05999231338501,-0.33082463651332006,1739502647.6732905,8.05999231338501,13.809209993712091,1739502647.6732936,8.05999231338501,20.010784410196816,1739502647.6732948,8.05999231338501,-0.131,1739502647.6732967,8.05999231338501,0.03585462103522739,1739502647.6732981,8.05999231338501,0.21280587911870036,1739502647.6732998,8.05999231338501,0.052590397165771186,1739502647.673301,8.05999231338501,2.1086459857326485,1739502647.6733024,8.05999231338501,0.0,1739502647.673304,8.05999231338501,0.00473930942919365,1739502647.6733055,8.05999231338501,6.280854979065048,1739502647.6733072,8.05999231338501,2.103906676303455 +1739502647.693611,8.079992294311523,14.43998223845049,1739502647.6936135,8.079992294311523,-0.33082463651332006,1739502647.693617,8.079992294311523,13.809209993712091,1739502647.6936202,8.079992294311523,20.010784410196816,1739502647.6936219,8.079992294311523,-0.131,1739502647.6936238,8.079992294311523,0.03585462103522739,1739502647.6936257,8.079992294311523,0.21280587911870036,1739502647.693627,8.079992294311523,0.052590397165771186,1739502647.6936288,8.079992294311523,2.1086459857326485,1739502647.6936305,8.079992294311523,0.0,1739502647.693632,8.079992294311523,0.00473930942919365,1739502647.6936338,8.079992294311523,6.280854979065048,1739502647.6936357,8.079992294311523,2.103906676303455 +1739502647.7134705,8.099992275238037,14.671436928797736,1739502647.7134733,8.099992275238037,-0.33127565214739096,1739502647.713477,8.099992275238037,13.835364824736965,1739502647.71348,8.099992275238037,20.037972149227382,1739502647.7134817,8.099992275238037,-0.131,1739502647.7134836,8.099992275238037,0.037302047709496355,1739502647.7134852,8.099992275238037,0.20827472012781748,1739502647.713487,8.099992275238037,0.05545694003291201,1739502647.7134883,8.099992275238037,2.11630354456766,1739502647.7134902,8.099992275238037,0.0,1739502647.7134917,8.099992275238037,0.015126374098842318,1739502647.7134936,8.099992275238037,6.281694719098909,1739502647.713495,8.099992275238037,2.1044231303063 +1739502647.7333891,8.11999225616455,14.671436928797736,1739502647.7333915,8.11999225616455,-0.33127565214739096,1739502647.7333949,8.11999225616455,13.835364824736965,1739502647.7333984,8.11999225616455,20.037972149227382,1739502647.7334,8.11999225616455,-0.131,1739502647.733402,8.11999225616455,0.037302047709496355,1739502647.733404,8.11999225616455,0.20827472012781748,1739502647.7334054,8.11999225616455,0.05545694003291201,1739502647.7334068,8.11999225616455,2.11630354456766,1739502647.7334087,8.11999225616455,0.0,1739502647.7334101,8.11999225616455,0.011880414261359995,1739502647.7334118,8.11999225616455,6.281694719098909,1739502647.7334135,8.11999225616455,2.1044231303063 +1739502647.753446,8.139992237091064,14.671436928797736,1739502647.753449,8.139992237091064,-0.33127565214739096,1739502647.7534523,8.139992237091064,13.835364824736965,1739502647.7534554,8.139992237091064,20.037972149227382,1739502647.7534568,8.139992237091064,-0.131,1739502647.7534587,8.139992237091064,0.037302047709496355,1739502647.7534604,8.139992237091064,0.20827472012781748,1739502647.753462,8.139992237091064,0.05545694003291201,1739502647.7534635,8.139992237091064,2.11630354456766,1739502647.7534654,8.139992237091064,0.0,1739502647.7534668,8.139992237091064,0.011880414261359995,1739502647.7534685,8.139992237091064,6.281694719098909,1739502647.75347,8.139992237091064,2.1044231303063 +1739502647.7733994,8.159992218017578,14.671436928797736,1739502647.7734017,8.159992218017578,-0.33127565214739096,1739502647.773405,8.159992218017578,13.835364824736965,1739502647.7734082,8.159992218017578,20.037972149227382,1739502647.7734098,8.159992218017578,-0.131,1739502647.7734118,8.159992218017578,0.037302047709496355,1739502647.7734134,8.159992218017578,0.20827472012781748,1739502647.7734149,8.159992218017578,0.05545694003291201,1739502647.7734165,8.159992218017578,2.11630354456766,1739502647.7734182,8.159992218017578,0.0,1739502647.7734199,8.159992218017578,0.011880414261359995,1739502647.7734213,8.159992218017578,6.281694719098909,1739502647.773423,8.159992218017578,2.1044231303063 +1739502647.7934287,8.179992198944092,14.671436928797736,1739502647.7934313,8.179992198944092,-0.33127565214739096,1739502647.7934346,8.179992198944092,13.835364824736965,1739502647.7934377,8.179992198944092,20.037972149227382,1739502647.7934394,8.179992198944092,-0.131,1739502647.7934418,8.179992198944092,0.037302047709496355,1739502647.7934434,8.179992198944092,0.20827472012781748,1739502647.793445,8.179992198944092,0.05545694003291201,1739502647.7934463,8.179992198944092,2.11630354456766,1739502647.7934482,8.179992198944092,0.0,1739502647.7934496,8.179992198944092,0.011880414261359995,1739502647.7934515,8.179992198944092,6.281694719098909,1739502647.7934532,8.179992198944092,2.1044231303063 +1739502647.8133576,8.199992179870605,14.671436928797736,1739502647.8133602,8.199992179870605,-0.33127565214739096,1739502647.8133636,8.199992179870605,13.835364824736965,1739502647.813367,8.199992179870605,20.037972149227382,1739502647.8133683,8.199992179870605,-0.131,1739502647.8133705,8.199992179870605,0.037302047709496355,1739502647.813372,8.199992179870605,0.20827472012781748,1739502647.8133733,8.199992179870605,0.05545694003291201,1739502647.813375,8.199992179870605,2.11630354456766,1739502647.8133774,8.199992179870605,0.0,1739502647.8133788,8.199992179870605,0.011880414261359995,1739502647.8133802,8.199992179870605,6.281694719098909,1739502647.8133821,8.199992179870605,2.1044231303063 +1739502647.8334408,8.21999216079712,14.902994629275767,1739502647.8334434,8.21999216079712,-0.33153241354556684,1739502647.833447,8.21999216079712,14.264076197394687,1739502647.83345,8.21999216079712,20.469407446651097,1739502647.8334517,8.21999216079712,-0.129,1739502647.8334537,8.21999216079712,0.036368684292866695,1739502647.8334553,8.21999216079712,0.20615525930305734,1739502647.833457,8.21999216079712,0.05102562983853716,1739502647.8334584,8.21999216079712,2.1198949263892795,1739502647.8334603,8.21999216079712,0.0,1739502647.833462,8.21999216079712,0.015118501151973128,1739502647.8334637,8.21999216079712,6.282534459132771,1739502647.833465,8.21999216079712,2.105788328054078 +1739502647.8534353,8.239992141723633,14.902994629275767,1739502647.853438,8.239992141723633,-0.33153241354556684,1739502647.8534412,8.239992141723633,14.264076197394687,1739502647.8534446,8.239992141723633,20.469407446651097,1739502647.8534462,8.239992141723633,-0.129,1739502647.8534482,8.239992141723633,0.036368684292866695,1739502647.8534498,8.239992141723633,0.20615525930305734,1739502647.8534513,8.239992141723633,0.05102562983853716,1739502647.8534527,8.239992141723633,2.1198949263892795,1739502647.8534546,8.239992141723633,0.0,1739502647.853456,8.239992141723633,0.014106598335201337,1739502647.853458,8.239992141723633,6.282534459132771,1739502647.8534594,8.239992141723633,2.105788328054078 +1739502647.8739035,8.259992122650146,14.902994629275767,1739502647.8739069,8.259992122650146,-0.33153241354556684,1739502647.8739104,8.259992122650146,14.264076197394687,1739502647.8739145,8.259992122650146,20.469407446651097,1739502647.8739161,8.259992122650146,-0.129,1739502647.8739185,8.259992122650146,0.036368684292866695,1739502647.8739202,8.259992122650146,0.20615525930305734,1739502647.873922,8.259992122650146,0.05102562983853716,1739502647.8739235,8.259992122650146,2.1198949263892795,1739502647.8739257,8.259992122650146,0.0,1739502647.8739274,8.259992122650146,0.014106598335201337,1739502647.8739297,8.259992122650146,6.282534459132771,1739502647.8739314,8.259992122650146,2.105788328054078 +1739502647.8936174,8.27999210357666,14.902994629275767,1739502647.8936203,8.27999210357666,-0.33153241354556684,1739502647.893624,8.27999210357666,14.264076197394687,1739502647.8936274,8.27999210357666,20.469407446651097,1739502647.893629,8.27999210357666,-0.129,1739502647.8936312,8.27999210357666,0.036368684292866695,1739502647.8936327,8.27999210357666,0.20615525930305734,1739502647.8936346,8.27999210357666,0.05102562983853716,1739502647.893636,8.27999210357666,2.1198949263892795,1739502647.8936381,8.27999210357666,0.0,1739502647.89364,8.27999210357666,0.014106598335201337,1739502647.8936417,8.27999210357666,6.282534459132771,1739502647.8936436,8.27999210357666,2.105788328054078 +1739502647.9135902,8.299992084503174,14.902994629275767,1739502647.9135933,8.299992084503174,-0.33153241354556684,1739502647.9135973,8.299992084503174,14.264076197394687,1739502647.9136007,8.299992084503174,20.469407446651097,1739502647.9136026,8.299992084503174,-0.129,1739502647.913605,8.299992084503174,0.036368684292866695,1739502647.9136066,8.299992084503174,0.20615525930305734,1739502647.9136086,8.299992084503174,0.05102562983853716,1739502647.9136102,8.299992084503174,2.1198949263892795,1739502647.9136124,8.299992084503174,0.0,1739502647.9136138,8.299992084503174,0.014106598335201337,1739502647.9136157,8.299992084503174,6.282534459132771,1739502647.9136174,8.299992084503174,2.105788328054078 +1739502647.933788,8.319992065429688,15.134708074566767,1739502647.9337916,8.319992065429688,-0.3315947668949466,1739502647.933796,8.319992065429688,14.290491592511207,1739502647.9337997,8.319992065429688,20.498905590841467,1739502647.9338014,8.319992065429688,-0.129,1739502647.9338036,8.319992065429688,0.03775001206423186,1739502647.9338055,8.319992065429688,0.20158150935890923,1739502647.9338074,8.319992065429688,0.05372011388960295,1739502647.9338088,8.319992065429688,2.127665830028334,1739502647.933811,8.319992065429688,0.0,1739502647.9338124,8.319992065429688,0.023167734275093763,1739502647.9338143,8.319992065429688,0.00018889198704552008,1739502647.933816,8.319992065429688,2.1073297025910027 +1739502647.9536054,8.339992046356201,15.134708074566767,1739502647.9536104,8.339992046356201,-0.3315947668949466,1739502647.9536154,8.339992046356201,14.290491592511207,1739502647.95362,8.339992046356201,20.498905590841467,1739502647.9536223,8.339992046356201,-0.129,1739502647.9536252,8.339992046356201,0.03775001206423186,1739502647.9536276,8.339992046356201,0.20158150935890923,1739502647.9536302,8.339992046356201,0.05372011388960295,1739502647.9536324,8.339992046356201,2.127665830028334,1739502647.9536345,8.339992046356201,0.0,1739502647.953637,8.339992046356201,0.020336127437331264,1739502647.9536393,8.339992046356201,0.00018889198704552008,1739502647.9536414,8.339992046356201,2.1073297025910027 +1739502647.973616,8.359992027282715,15.134708074566767,1739502647.9736187,8.359992027282715,-0.3315947668949466,1739502647.9736223,8.359992027282715,14.290491592511207,1739502647.9736261,8.359992027282715,20.498905590841467,1739502647.9736278,8.359992027282715,-0.129,1739502647.9736302,8.359992027282715,0.03775001206423186,1739502647.973632,8.359992027282715,0.20158150935890923,1739502647.9736338,8.359992027282715,0.05372011388960295,1739502647.9736357,8.359992027282715,2.127665830028334,1739502647.9736373,8.359992027282715,0.0,1739502647.973639,8.359992027282715,0.020336127437331264,1739502647.973641,8.359992027282715,0.00018889198704552008,1739502647.9736428,8.359992027282715,2.1073297025910027 +1739502647.9937298,8.379992008209229,15.134708074566767,1739502647.9937332,8.379992008209229,-0.3315947668949466,1739502647.993737,8.379992008209229,14.290491592511207,1739502647.9937403,8.379992008209229,20.498905590841467,1739502647.993742,8.379992008209229,-0.129,1739502647.9937441,8.379992008209229,0.03775001206423186,1739502647.9937458,8.379992008209229,0.20158150935890923,1739502647.9937477,8.379992008209229,0.05372011388960295,1739502647.9937491,8.379992008209229,2.127665830028334,1739502647.9937515,8.379992008209229,0.0,1739502647.9937534,8.379992008209229,0.020336127437331264,1739502647.993755,8.379992008209229,0.00018889198704552008,1739502647.993757,8.379992008209229,2.1073297025910027 +1739502648.0135887,8.399991989135742,15.134708074566767,1739502648.0135915,8.399991989135742,-0.3315947668949466,1739502648.0135953,8.399991989135742,14.290491592511207,1739502648.0135992,8.399991989135742,20.498905590841467,1739502648.013601,8.399991989135742,-0.129,1739502648.013603,8.399991989135742,0.03775001206423186,1739502648.0136049,8.399991989135742,0.20158150935890923,1739502648.0136065,8.399991989135742,0.05372011388960295,1739502648.0136082,8.399991989135742,2.127665830028334,1739502648.0136101,8.399991989135742,0.0,1739502648.013612,8.399991989135742,0.020336127437331264,1739502648.013614,8.399991989135742,0.00018889198704552008,1739502648.0136156,8.399991989135742,2.1073297025910027 +1739502648.0337517,8.419991970062256,15.134708074566767,1739502648.0337553,8.419991970062256,-0.3315947668949466,1739502648.0337596,8.419991970062256,14.290491592511207,1739502648.0337632,8.419991970062256,20.498905590841467,1739502648.0337648,8.419991970062256,-0.129,1739502648.033767,8.419991970062256,0.03775001206423186,1739502648.033769,8.419991970062256,0.20158150935890923,1739502648.0337708,8.419991970062256,0.05372011388960295,1739502648.0337722,8.419991970062256,2.127665830028334,1739502648.0337744,8.419991970062256,0.0,1739502648.033776,8.419991970062256,0.020336127437331264,1739502648.033778,8.419991970062256,0.00018889198704552008,1739502648.0337799,8.419991970062256,2.1073297025910027 +1739502648.0534499,8.43999195098877,15.3666311963349,1739502648.0534525,8.43999195098877,-0.3314624160970876,1739502648.0534558,8.43999195098877,14.718883599438227,1739502648.053459,8.43999195098877,20.931858128073326,1739502648.0534601,8.43999195098877,-0.12774706452398912,1739502648.0534623,8.43999195098877,0.03658870323191038,1739502648.0534637,8.43999195098877,0.19799067418306202,1739502648.0534654,8.43999195098877,0.049025270852730854,1739502648.0534668,8.43999195098877,2.1337866952703246,1739502648.0534687,8.43999195098877,0.0,1739502648.05347,8.43999195098877,0.02591872203484396,1739502648.0534718,8.43999195098877,0.0010286320209066762,1739502648.0534732,8.43999195098877,2.1096125351910273 +1739502648.0734313,8.459991931915283,15.3666311963349,1739502648.073434,8.459991931915283,-0.3314624160970876,1739502648.0734372,8.459991931915283,14.718883599438227,1739502648.0734403,8.459991931915283,20.931858128073326,1739502648.073442,8.459991931915283,-0.12774706452398912,1739502648.073444,8.459991931915283,0.03658870323191038,1739502648.0734456,8.459991931915283,0.19799067418306202,1739502648.0734472,8.459991931915283,0.049025270852730854,1739502648.0734484,8.459991931915283,2.1337866952703246,1739502648.0734506,8.459991931915283,0.0,1739502648.073452,8.459991931915283,0.02417416007929729,1739502648.073454,8.459991931915283,0.0010286320209066762,1739502648.0734553,8.459991931915283,2.1096125351910273 +1739502648.0935516,8.479991912841797,15.3666311963349,1739502648.093555,8.479991912841797,-0.3314624160970876,1739502648.0935585,8.479991912841797,14.718883599438227,1739502648.0935614,8.479991912841797,20.931858128073326,1739502648.0935626,8.479991912841797,-0.12774706452398912,1739502648.0935647,8.479991912841797,0.03658870323191038,1739502648.0935662,8.479991912841797,0.19799067418306202,1739502648.0935678,8.479991912841797,0.049025270852730854,1739502648.0935693,8.479991912841797,2.1337866952703246,1739502648.0935712,8.479991912841797,0.0,1739502648.0935726,8.479991912841797,0.02417416007929729,1739502648.0935748,8.479991912841797,0.0010286320209066762,1739502648.0935767,8.479991912841797,2.1096125351910273 +1739502648.113419,8.49999189376831,15.3666311963349,1739502648.1134217,8.49999189376831,-0.3314624160970876,1739502648.1134245,8.49999189376831,14.718883599438227,1739502648.1134276,8.49999189376831,20.931858128073326,1739502648.113429,8.49999189376831,-0.12774706452398912,1739502648.1134312,8.49999189376831,0.03658870323191038,1739502648.113433,8.49999189376831,0.19799067418306202,1739502648.1134343,8.49999189376831,0.049025270852730854,1739502648.113436,8.49999189376831,2.1337866952703246,1739502648.1134377,8.49999189376831,0.0,1739502648.1134393,8.49999189376831,0.02417416007929729,1739502648.1134408,8.49999189376831,0.0010286320209066762,1739502648.1134427,8.49999189376831,2.1096125351910273 +1739502648.1336672,8.519991874694824,15.3666311963349,1739502648.1336703,8.519991874694824,-0.3314624160970876,1739502648.1336737,8.519991874694824,14.718883599438227,1739502648.133677,8.519991874694824,20.931858128073326,1739502648.1336787,8.519991874694824,-0.12774706452398912,1739502648.1336806,8.519991874694824,0.03658870323191038,1739502648.1336825,8.519991874694824,0.19799067418306202,1739502648.133684,8.519991874694824,0.049025270852730854,1739502648.1336854,8.519991874694824,2.1337866952703246,1739502648.133687,8.519991874694824,0.0,1739502648.1336887,8.519991874694824,0.02417416007929729,1739502648.1336904,8.519991874694824,0.0010286320209066762,1739502648.1336923,8.519991874694824,2.1096125351910273 +1739502648.1534438,8.539991855621338,15.598819852072186,1739502648.1534464,8.539991855621338,-0.3311349324384123,1739502648.1534498,8.539991855621338,14.951939730631413,1739502648.1534529,8.539991855621338,21.170194072788068,1739502648.1534543,8.539991855621338,-0.127,1739502648.1534564,8.539991855621338,0.03662357766454231,1739502648.1534579,8.539991855621338,0.193725182295535,1739502648.1534595,8.539991855621338,0.047863355590919525,1739502648.1534607,8.539991855621338,2.1410804526485703,1739502648.1534624,8.539991855621338,0.0,1739502648.153464,8.539991855621338,0.03094117267530242,1739502648.1534655,8.539991855621338,0.0018683720547678334,1739502648.1534672,8.539991855621338,2.11225397279602 +1739502648.1734095,8.559991836547852,15.598819852072186,1739502648.173412,8.559991836547852,-0.3311349324384123,1739502648.1734152,8.559991836547852,14.951939730631413,1739502648.1734183,8.559991836547852,21.170194072788068,1739502648.1734197,8.559991836547852,-0.127,1739502648.1734216,8.559991836547852,0.03662357766454231,1739502648.173423,8.559991836547852,0.193725182295535,1739502648.1734247,8.559991836547852,0.047863355590919525,1739502648.1734262,8.559991836547852,2.1410804526485703,1739502648.173428,8.559991836547852,0.0,1739502648.1734293,8.559991836547852,0.028826479852550158,1739502648.1734312,8.559991836547852,0.0018683720547678334,1739502648.1734326,8.559991836547852,2.11225397279602 +1739502648.1935277,8.579991817474365,15.598819852072186,1739502648.1935308,8.579991817474365,-0.3311349324384123,1739502648.1935341,8.579991817474365,14.951939730631413,1739502648.1935372,8.579991817474365,21.170194072788068,1739502648.193539,8.579991817474365,-0.127,1739502648.1935408,8.579991817474365,0.03662357766454231,1739502648.1935425,8.579991817474365,0.193725182295535,1739502648.1935441,8.579991817474365,0.047863355590919525,1739502648.1935456,8.579991817474365,2.1410804526485703,1739502648.1935475,8.579991817474365,0.0,1739502648.1935492,8.579991817474365,0.028826479852550158,1739502648.1935506,8.579991817474365,0.0018683720547678334,1739502648.1935525,8.579991817474365,2.11225397279602 +1739502648.21338,8.599991798400879,15.598819852072186,1739502648.2133827,8.599991798400879,-0.3311349324384123,1739502648.2133858,8.599991798400879,14.951939730631413,1739502648.2133892,8.599991798400879,21.170194072788068,1739502648.2133906,8.599991798400879,-0.127,1739502648.2133927,8.599991798400879,0.03662357766454231,1739502648.2133944,8.599991798400879,0.193725182295535,1739502648.213396,8.599991798400879,0.047863355590919525,1739502648.2133973,8.599991798400879,2.1410804526485703,1739502648.213399,8.599991798400879,0.0,1739502648.2134006,8.599991798400879,0.028826479852550158,1739502648.2134023,8.599991798400879,0.0018683720547678334,1739502648.2134037,8.599991798400879,2.11225397279602 +1739502648.2335467,8.619991779327393,15.598819852072186,1739502648.2335496,8.619991779327393,-0.3311349324384123,1739502648.2335532,8.619991779327393,14.951939730631413,1739502648.233556,8.619991779327393,21.170194072788068,1739502648.2335577,8.619991779327393,-0.127,1739502648.2335598,8.619991779327393,0.03662357766454231,1739502648.2335613,8.619991779327393,0.193725182295535,1739502648.2335627,8.619991779327393,0.047863355590919525,1739502648.2335641,8.619991779327393,2.1410804526485703,1739502648.2335663,8.619991779327393,0.0,1739502648.2335677,8.619991779327393,0.028826479852550158,1739502648.2335694,8.619991779327393,0.0018683720547678334,1739502648.233571,8.619991779327393,2.11225397279602 +1739502648.253409,8.639991760253906,15.598819852072186,1739502648.2534113,8.639991760253906,-0.3311349324384123,1739502648.2534146,8.639991760253906,14.951939730631413,1739502648.2534177,8.639991760253906,21.170194072788068,1739502648.253419,8.639991760253906,-0.127,1739502648.253421,8.639991760253906,0.03662357766454231,1739502648.2534225,8.639991760253906,0.193725182295535,1739502648.2534242,8.639991760253906,0.047863355590919525,1739502648.2534254,8.639991760253906,2.1410804526485703,1739502648.2534273,8.639991760253906,0.0,1739502648.2534287,8.639991760253906,0.028826479852550158,1739502648.2534304,8.639991760253906,0.0018683720547678334,1739502648.2534318,8.639991760253906,2.11225397279602 +1739502648.2735016,8.65999174118042,15.831329303447621,1739502648.2735045,8.65999174118042,-0.3306117442033729,1739502648.2735078,8.65999174118042,14.97867779435135,1739502648.273511,8.65999174118042,21.203328635505027,1739502648.2735124,8.65999174118042,-0.127,1739502648.2735143,8.65999174118042,0.03788427979556988,1739502648.273516,8.65999174118042,0.18906303902359334,1739502648.2735176,8.65999174118042,0.05023794881371051,1739502648.2735188,8.65999174118042,2.149080982281873,1739502648.2735207,8.65999174118042,0.0,1739502648.273522,8.65999174118042,0.035811616675797575,1739502648.2735238,8.65999174118042,0.0027081120886289904,1739502648.2735252,8.65999174118042,2.1154522222945324 +1739502648.2933815,8.679991722106934,15.831329303447621,1739502648.2933838,8.679991722106934,-0.3306117442033729,1739502648.2933872,8.679991722106934,14.97867779435135,1739502648.2933903,8.679991722106934,21.203328635505027,1739502648.293392,8.679991722106934,-0.127,1739502648.2933936,8.679991722106934,0.03788427979556988,1739502648.2933953,8.679991722106934,0.18906303902359334,1739502648.2933967,8.679991722106934,0.05023794881371051,1739502648.293398,8.679991722106934,2.149080982281873,1739502648.2933998,8.679991722106934,0.0,1739502648.2934012,8.679991722106934,0.033628759987340384,1739502648.293403,8.679991722106934,0.0027081120886289904,1739502648.2934046,8.679991722106934,2.1154522222945324 +1739502648.3134208,8.699991703033447,15.831329303447621,1739502648.3134239,8.699991703033447,-0.3306117442033729,1739502648.3134272,8.699991703033447,14.97867779435135,1739502648.3134305,8.699991703033447,21.203328635505027,1739502648.313432,8.699991703033447,-0.127,1739502648.3134341,8.699991703033447,0.03788427979556988,1739502648.3134356,8.699991703033447,0.18906303902359334,1739502648.3134375,8.699991703033447,0.05023794881371051,1739502648.313439,8.699991703033447,2.149080982281873,1739502648.3134408,8.699991703033447,0.0,1739502648.3134422,8.699991703033447,0.033628759987340384,1739502648.3134441,8.699991703033447,0.0027081120886289904,1739502648.3134458,8.699991703033447,2.1154522222945324 +1739502648.3332846,8.719991683959961,15.831329303447621,1739502648.3332872,8.719991683959961,-0.3306117442033729,1739502648.33329,8.719991683959961,14.97867779435135,1739502648.3332925,8.719991683959961,21.203328635505027,1739502648.3332942,8.719991683959961,-0.127,1739502648.3332956,8.719991683959961,0.03788427979556988,1739502648.3332973,8.719991683959961,0.18906303902359334,1739502648.3332984,8.719991683959961,0.05023794881371051,1739502648.3332999,8.719991683959961,2.149080982281873,1739502648.3333015,8.719991683959961,0.0,1739502648.3333027,8.719991683959961,0.033628759987340384,1739502648.3333044,8.719991683959961,0.0027081120886289904,1739502648.3333056,8.719991683959961,2.1154522222945324 +1739502648.3532665,8.739991664886475,15.831329303447621,1739502648.3532686,8.739991664886475,-0.3306117442033729,1739502648.3532715,8.739991664886475,14.97867779435135,1739502648.3532743,8.739991664886475,21.203328635505027,1739502648.3532755,8.739991664886475,-0.127,1739502648.3532774,8.739991664886475,0.03788427979556988,1739502648.3532789,8.739991664886475,0.18906303902359334,1739502648.3532803,8.739991664886475,0.05023794881371051,1739502648.3532815,8.739991664886475,2.149080982281873,1739502648.3532832,8.739991664886475,0.0,1739502648.3532844,8.739991664886475,0.033628759987340384,1739502648.3532858,8.739991664886475,0.0027081120886289904,1739502648.3532872,8.739991664886475,2.1154522222945324 +1739502648.3733964,8.759991645812988,16.064210997905523,1739502648.3733988,8.759991645812988,-0.3298921529563037,1739502648.3734016,8.759991645812988,15.596616587220048,1739502648.3734045,8.759991645812988,21.828609118798653,1739502648.3734057,8.759991645812988,-0.125,1739502648.3734076,8.759991645812988,0.03552945628146186,1739502648.3734088,8.759991645812988,0.18443967423882898,1739502648.37341,8.759991645812988,0.042572595932455035,1739502648.3734114,8.759991645812988,2.1570444887478786,1739502648.3734133,8.759991645812988,0.0,1739502648.3734145,8.759991645812988,0.03986667160889012,1739502648.373416,8.759991645812988,0.0035478521224901476,1739502648.3734174,8.759991645812988,2.1191271657988153 +1739502648.393486,8.779991626739502,16.064210997905523,1739502648.3934886,8.779991626739502,-0.3298921529563037,1739502648.3934915,8.779991626739502,15.596616587220048,1739502648.3934944,8.779991626739502,21.828609118798653,1739502648.3934956,8.779991626739502,-0.125,1739502648.393497,8.779991626739502,0.03552945628146186,1739502648.3934987,8.779991626739502,0.18443967423882898,1739502648.3935,8.779991626739502,0.042572595932455035,1739502648.3935015,8.779991626739502,2.1570444887478786,1739502648.393503,8.779991626739502,0.0,1739502648.3935041,8.779991626739502,0.03791732294906325,1739502648.3935058,8.779991626739502,0.0035478521224901476,1739502648.3935072,8.779991626739502,2.1191271657988153 +1739502648.4132805,8.799991607666016,16.064210997905523,1739502648.4132829,8.799991607666016,-0.3298921529563037,1739502648.4132857,8.799991607666016,15.596616587220048,1739502648.4132884,8.799991607666016,21.828609118798653,1739502648.41329,8.799991607666016,-0.125,1739502648.4132915,8.799991607666016,0.03552945628146186,1739502648.413293,8.799991607666016,0.18443967423882898,1739502648.413294,8.799991607666016,0.042572595932455035,1739502648.4132955,8.799991607666016,2.1570444887478786,1739502648.4132972,8.799991607666016,0.0,1739502648.4132984,8.799991607666016,0.03791732294906325,1739502648.4133,8.799991607666016,0.0035478521224901476,1739502648.4133015,8.799991607666016,2.1191271657988153 +1739502648.4335065,8.81999158859253,16.064210997905523,1739502648.433509,8.81999158859253,-0.3298921529563037,1739502648.4335117,8.81999158859253,15.596616587220048,1739502648.4335146,8.81999158859253,21.828609118798653,1739502648.4335158,8.81999158859253,-0.125,1739502648.4335172,8.81999158859253,0.03552945628146186,1739502648.433519,8.81999158859253,0.18443967423882898,1739502648.4335203,8.81999158859253,0.042572595932455035,1739502648.4335215,8.81999158859253,2.1570444887478786,1739502648.4335232,8.81999158859253,0.0,1739502648.4335241,8.81999158859253,0.03791732294906325,1739502648.4335258,8.81999158859253,0.0035478521224901476,1739502648.4335275,8.81999158859253,2.1191271657988153 +1739502648.4533565,8.839991569519043,16.064210997905523,1739502648.4533591,8.839991569519043,-0.3298921529563037,1739502648.4533627,8.839991569519043,15.596616587220048,1739502648.4533658,8.839991569519043,21.828609118798653,1739502648.453367,8.839991569519043,-0.125,1739502648.453369,8.839991569519043,0.03552945628146186,1739502648.45337,8.839991569519043,0.18443967423882898,1739502648.4533718,8.839991569519043,0.042572595932455035,1739502648.4533727,8.839991569519043,2.1570444887478786,1739502648.4533744,8.839991569519043,0.0,1739502648.453376,8.839991569519043,0.03791732294906325,1739502648.4533775,8.839991569519043,0.0035478521224901476,1739502648.453379,8.839991569519043,2.1191271657988153 +1739502648.4734483,8.859991550445557,16.064210997905523,1739502648.4734507,8.859991550445557,-0.3298921529563037,1739502648.4734535,8.859991550445557,15.596616587220048,1739502648.4734564,8.859991550445557,21.828609118798653,1739502648.4734576,8.859991550445557,-0.125,1739502648.4734595,8.859991550445557,0.03552945628146186,1739502648.473461,8.859991550445557,0.18443967423882898,1739502648.4734623,8.859991550445557,0.042572595932455035,1739502648.4734635,8.859991550445557,2.1570444887478786,1739502648.4734652,8.859991550445557,0.0,1739502648.4734664,8.859991550445557,0.03791732294906325,1739502648.4734676,8.859991550445557,0.0035478521224901476,1739502648.4734693,8.859991550445557,2.1191271657988153 +1739502648.4934576,8.87999153137207,16.2975248353152,1739502648.4934602,8.87999153137207,-0.328975297434285,1739502648.493463,8.87999153137207,15.639778730285318,1739502648.4934657,8.87999153137207,21.880151244848854,1739502648.493467,8.87999153137207,-0.12480033393939141,1739502648.4934688,8.87999153137207,0.03655698704755603,1739502648.4934702,8.87999153137207,0.17967878895890965,1739502648.4934719,8.87999153137207,0.04421492849139795,1739502648.493473,8.87999153137207,2.1652757070356143,1739502648.4934745,8.87999153137207,0.0,1739502648.4934762,8.87999153137207,0.04379497547214489,1739502648.4934776,8.87999153137207,0.004387592156351304,1739502648.4934793,8.87999153137207,2.123317499181211 +1739502648.52271,8.899991512298584,16.2975248353152,1739502648.5227191,8.899991512298584,-0.328975297434285,1739502648.5227299,8.899991512298584,15.639778730285318,1739502648.5227394,8.899991512298584,21.880151244848854,1739502648.5227442,8.899991512298584,-0.12480033393939141,1739502648.5227504,8.899991512298584,0.03655698704755603,1739502648.5227554,8.899991512298584,0.17967878895890965,1739502648.52276,8.899991512298584,0.04421492849139795,1739502648.5227644,8.899991512298584,2.1652757070356143,1739502648.52277,8.899991512298584,0.0,1739502648.5227747,8.899991512298584,0.041958207854403184,1739502648.52278,8.899991512298584,0.004387592156351304,1739502648.522785,8.899991512298584,2.123317499181211 +1739502648.563303,8.939991474151611,16.2975248353152,1739502648.5633094,8.939991474151611,-0.328975297434285,1739502648.563316,8.939991474151611,15.639778730285318,1739502648.5633216,8.939991474151611,21.880151244848854,1739502648.5633242,8.939991474151611,-0.12480033393939141,1739502648.5633278,8.939991474151611,0.03655698704755603,1739502648.5633314,8.939991474151611,0.17967878895890965,1739502648.563334,8.939991474151611,0.04421492849139795,1739502648.5633364,8.939991474151611,2.1652757070356143,1739502648.56334,8.939991474151611,0.0,1739502648.5633426,8.939991474151611,0.041958207854403184,1739502648.5633457,8.939991474151611,0.004387592156351304,1739502648.563349,8.939991474151611,2.123317499181211 +1739502648.5804315,8.959991455078125,16.2975248353152,1739502648.5804374,8.959991455078125,-0.328975297434285,1739502648.5804446,8.959991455078125,15.639778730285318,1739502648.5804522,8.959991455078125,21.880151244848854,1739502648.5804572,8.959991455078125,-0.12480033393939141,1739502648.5804644,8.959991455078125,0.03655698704755603,1739502648.5804706,8.959991455078125,0.17967878895890965,1739502648.580477,8.959991455078125,0.04421492849139795,1739502648.580482,8.959991455078125,2.1652757070356143,1739502648.580486,8.959991455078125,0.0,1739502648.5804904,8.959991455078125,0.041958207854403184,1739502648.5804944,8.959991455078125,0.004387592156351304,1739502648.5804987,8.959991455078125,2.123317499181211 +1739502648.600592,8.979991436004639,16.531315927187865,1739502648.6005964,8.979991436004639,-0.3278602357413485,1739502648.6006014,8.979991436004639,15.774074010691326,1739502648.6006067,8.979991436004639,22.02361716529274,1739502648.60061,8.979991436004639,-0.124,1739502648.6006157,8.979991436004639,0.03710042192523559,1739502648.6006193,8.979991436004639,0.17514749819707767,1739502648.6006227,8.979991436004639,0.044527329456923934,1739502648.600626,8.979991436004639,2.1731391460825575,1739502648.6006298,8.979991436004639,0.0,1739502648.6006331,8.979991436004639,0.046724389070108535,1739502648.600637,8.979991436004639,0.0052273321902124616,1739502648.6006405,8.979991436004639,2.127904189618905 +1739502648.6191697,8.999991416931152,16.531315927187865,1739502648.6191735,8.999991416931152,-0.3278602357413485,1739502648.6191778,8.999991416931152,15.774074010691326,1739502648.619182,8.999991416931152,22.02361716529274,1739502648.619184,8.999991416931152,-0.124,1739502648.6191869,8.999991416931152,0.03710042192523559,1739502648.6191897,8.999991416931152,0.17514749819707767,1739502648.6191921,8.999991416931152,0.044527329456923934,1739502648.619194,8.999991416931152,2.1731391460825575,1739502648.6191967,8.999991416931152,0.0,1739502648.619199,8.999991416931152,0.0452349564636525,1739502648.619201,8.999991416931152,0.0052273321902124616,1739502648.6192033,8.999991416931152,2.127904189618905 +1739502648.639216,9.019991397857666,16.531315927187865,1739502648.6392183,9.019991397857666,-0.3278602357413485,1739502648.6392214,9.019991397857666,15.774074010691326,1739502648.6392245,9.019991397857666,22.02361716529274,1739502648.639226,9.019991397857666,-0.124,1739502648.6392283,9.019991397857666,0.03710042192523559,1739502648.6392298,9.019991397857666,0.17514749819707767,1739502648.6392312,9.019991397857666,0.044527329456923934,1739502648.6392324,9.019991397857666,2.1731391460825575,1739502648.639234,9.019991397857666,0.0,1739502648.6392353,9.019991397857666,0.0452349564636525,1739502648.6392367,9.019991397857666,0.0052273321902124616,1739502648.639238,9.019991397857666,2.127904189618905 +1739502648.6597111,9.03999137878418,16.531315927187865,1739502648.6597145,9.03999137878418,-0.3278602357413485,1739502648.6597192,9.03999137878418,15.774074010691326,1739502648.659725,9.03999137878418,22.02361716529274,1739502648.6597278,9.03999137878418,-0.124,1739502648.6597316,9.03999137878418,0.03710042192523559,1739502648.6597352,9.03999137878418,0.17514749819707767,1739502648.6597388,9.03999137878418,0.044527329456923934,1739502648.659742,9.03999137878418,2.1731391460825575,1739502648.6597457,9.03999137878418,0.0,1739502648.6597493,9.03999137878418,0.0452349564636525,1739502648.6597528,9.03999137878418,0.0052273321902124616,1739502648.6597562,9.03999137878418,2.127904189618905 +1739502648.6795387,9.059991359710693,16.531315927187865,1739502648.6795423,9.059991359710693,-0.3278602357413485,1739502648.6795468,9.059991359710693,15.774074010691326,1739502648.6795523,9.059991359710693,22.02361716529274,1739502648.6795552,9.059991359710693,-0.124,1739502648.679559,9.059991359710693,0.03710042192523559,1739502648.6795628,9.059991359710693,0.17514749819707767,1739502648.6795661,9.059991359710693,0.044527329456923934,1739502648.6795695,9.059991359710693,2.1731391460825575,1739502648.6795728,9.059991359710693,0.0,1739502648.6795764,9.059991359710693,0.0452349564636525,1739502648.67958,9.059991359710693,0.0052273321902124616,1739502648.6795833,9.059991359710693,2.127904189618905 +1739502648.7002532,9.079991340637207,16.531315927187865,1739502648.700257,9.079991340637207,-0.3278602357413485,1739502648.7002623,9.079991340637207,15.774074010691326,1739502648.7002676,9.079991340637207,22.02361716529274,1739502648.7002704,9.079991340637207,-0.124,1739502648.700274,9.079991340637207,0.03710042192523559,1739502648.7002773,9.079991340637207,0.17514749819707767,1739502648.7002807,9.079991340637207,0.044527329456923934,1739502648.7002838,9.079991340637207,2.1731391460825575,1739502648.7002873,9.079991340637207,0.0,1739502648.7002904,9.079991340637207,0.0452349564636525,1739502648.7002943,9.079991340637207,0.0052273321902124616,1739502648.7002974,9.079991340637207,2.127904189618905 +1739502648.7182207,9.09999132156372,16.76563261632459,1739502648.718223,9.09999132156372,-0.326545894117066,1739502648.718226,9.09999132156372,15.904780379247509,1739502648.7182288,9.09999132156372,22.164288336033852,1739502648.71823,9.09999132156372,-0.124,1739502648.7182314,9.09999132156372,0.037500250260539596,1739502648.7182329,9.09999132156372,0.16978833311337133,1739502648.718234,9.09999132156372,0.044673997723277674,1739502648.7182355,9.09999132156372,2.18247611627332,1739502648.7182372,9.09999132156372,0.0,1739502648.7182384,9.09999132156372,0.051568877039744575,1739502648.71824,9.09999132156372,0.006067072224073619,1739502648.7182417,9.09999132156372,2.1328865907113683 +1739502648.7380915,9.119991302490234,16.76563261632459,1739502648.7380939,9.119991302490234,-0.326545894117066,1739502648.7380965,9.119991302490234,15.904780379247509,1739502648.7380986,9.119991302490234,22.164288336033852,1739502648.7381,9.119991302490234,-0.124,1739502648.7381015,9.119991302490234,0.037500250260539596,1739502648.7381027,9.119991302490234,0.16978833311337133,1739502648.738104,9.119991302490234,0.044673997723277674,1739502648.7381053,9.119991302490234,2.18247611627332,1739502648.7381067,9.119991302490234,0.0,1739502648.738108,9.119991302490234,0.04958952556195184,1739502648.738109,9.119991302490234,0.006067072224073619,1739502648.7381108,9.119991302490234,2.1328865907113683 +1739502648.758157,9.139991283416748,16.76563261632459,1739502648.7581594,9.139991283416748,-0.326545894117066,1739502648.7581623,9.139991283416748,15.904780379247509,1739502648.7581646,9.139991283416748,22.164288336033852,1739502648.7581663,9.139991283416748,-0.124,1739502648.7581682,9.139991283416748,0.037500250260539596,1739502648.7581697,9.139991283416748,0.16978833311337133,1739502648.758171,9.139991283416748,0.044673997723277674,1739502648.7581723,9.139991283416748,2.18247611627332,1739502648.7581737,9.139991283416748,0.0,1739502648.758175,9.139991283416748,0.04958952556195184,1739502648.7581766,9.139991283416748,0.006067072224073619,1739502648.7581778,9.139991283416748,2.1328865907113683 +1739502648.7780929,9.159991264343262,16.76563261632459,1739502648.7780948,9.159991264343262,-0.326545894117066,1739502648.7780976,9.159991264343262,15.904780379247509,1739502648.7781003,9.159991264343262,22.164288336033852,1739502648.7781014,9.159991264343262,-0.124,1739502648.7781034,9.159991264343262,0.037500250260539596,1739502648.7781045,9.159991264343262,0.16978833311337133,1739502648.778106,9.159991264343262,0.044673997723277674,1739502648.7781072,9.159991264343262,2.18247611627332,1739502648.7781086,9.159991264343262,0.0,1739502648.77811,9.159991264343262,0.04958952556195184,1739502648.7781112,9.159991264343262,0.006067072224073619,1739502648.7781124,9.159991264343262,2.1328865907113683 +1739502648.798185,9.179991245269775,16.76563261632459,1739502648.7981875,9.179991245269775,-0.326545894117066,1739502648.7981904,9.179991245269775,15.904780379247509,1739502648.798193,9.179991245269775,22.164288336033852,1739502648.7981944,9.179991245269775,-0.124,1739502648.798196,9.179991245269775,0.037500250260539596,1739502648.7981977,9.179991245269775,0.16978833311337133,1739502648.798199,9.179991245269775,0.044673997723277674,1739502648.7982001,9.179991245269775,2.18247611627332,1739502648.7982018,9.179991245269775,0.0,1739502648.7982032,9.179991245269775,0.04958952556195184,1739502648.7982044,9.179991245269775,0.006067072224073619,1739502648.7982056,9.179991245269775,2.1328865907113683 +1739502648.8181663,9.199991226196289,17.000515792780938,1739502648.8181684,9.199991226196289,-0.32503112340723117,1739502648.818171,9.199991226196289,16.11537984765894,1739502648.8181736,9.199991226196289,22.385729515020287,1739502648.8181753,9.199991226196289,-0.12383146735755864,1739502648.818177,9.199991226196289,0.03734412927429915,1739502648.8181784,9.199991226196289,0.1640004926225866,1739502648.8181796,9.199991226196289,0.04336750437571474,1739502648.8181808,9.199991226196289,2.192605006846808,1739502648.8181827,9.199991226196289,0.0,1739502648.818184,9.199991226196289,0.056437080687229885,1739502648.8181853,9.199991226196289,0.006906812257934776,1739502648.8181865,9.199991226196289,2.1383077885392305 +1739502648.838196,9.219991207122803,17.000515792780938,1739502648.838198,9.219991207122803,-0.32503112340723117,1739502648.838201,9.219991207122803,16.11537984765894,1739502648.8382037,9.219991207122803,22.385729515020287,1739502648.8382049,9.219991207122803,-0.12383146735755864,1739502648.8382068,9.219991207122803,0.03734412927429915,1739502648.8382082,9.219991207122803,0.1640004926225866,1739502648.8382094,9.219991207122803,0.04336750437571474,1739502648.8382106,9.219991207122803,2.192605006846808,1739502648.838212,9.219991207122803,0.0,1739502648.8382134,9.219991207122803,0.05429721830757739,1739502648.8382149,9.219991207122803,0.006906812257934776,1739502648.8382165,9.219991207122803,2.1383077885392305 +1739502648.858158,9.239991188049316,17.000515792780938,1739502648.85816,9.239991188049316,-0.32503112340723117,1739502648.8581629,9.239991188049316,16.11537984765894,1739502648.8581657,9.239991188049316,22.385729515020287,1739502648.858167,9.239991188049316,-0.12383146735755864,1739502648.8581686,9.239991188049316,0.03734412927429915,1739502648.85817,9.239991188049316,0.1640004926225866,1739502648.8581715,9.239991188049316,0.04336750437571474,1739502648.8581727,9.239991188049316,2.192605006846808,1739502648.8581746,9.239991188049316,0.0,1739502648.8581758,9.239991188049316,0.05429721830757739,1739502648.858177,9.239991188049316,0.006906812257934776,1739502648.8581784,9.239991188049316,2.1383077885392305 +1739502648.8782184,9.25999116897583,17.000515792780938,1739502648.8782206,9.25999116897583,-0.32503112340723117,1739502648.8782234,9.25999116897583,16.11537984765894,1739502648.8782258,9.25999116897583,22.385729515020287,1739502648.8782272,9.25999116897583,-0.12383146735755864,1739502648.8782287,9.25999116897583,0.03734412927429915,1739502648.87823,9.25999116897583,0.1640004926225866,1739502648.8782315,9.25999116897583,0.04336750437571474,1739502648.8782327,9.25999116897583,2.192605006846808,1739502648.8782341,9.25999116897583,0.0,1739502648.8782353,9.25999116897583,0.05429721830757739,1739502648.8782368,9.25999116897583,0.006906812257934776,1739502648.8782382,9.25999116897583,2.1383077885392305 +1739502648.9057703,9.279991149902344,17.000515792780938,1739502648.9057827,9.279991149902344,-0.32503112340723117,1739502648.9058,9.279991149902344,16.11537984765894,1739502648.90582,9.279991149902344,22.385729515020287,1739502648.9058306,9.279991149902344,-0.12383146735755864,1739502648.905845,9.279991149902344,0.03734412927429915,1739502648.9058576,9.279991149902344,0.1640004926225866,1739502648.9058702,9.279991149902344,0.04336750437571474,1739502648.9058826,9.279991149902344,2.192605006846808,1739502648.9058955,9.279991149902344,0.0,1739502648.905908,9.279991149902344,0.05429721830757739,1739502648.9059212,9.279991149902344,0.006906812257934776,1739502648.905934,9.279991149902344,2.1383077885392305 +1739502648.925946,9.299991130828857,17.000515792780938,1739502648.9259553,9.299991130828857,-0.32503112340723117,1739502648.9259675,9.299991130828857,16.11537984765894,1739502648.9259813,9.299991130828857,22.385729515020287,1739502648.925989,9.299991130828857,-0.12383146735755864,1739502648.925999,9.299991130828857,0.03734412927429915,1739502648.9260075,9.299991130828857,0.1640004926225866,1739502648.9260163,9.299991130828857,0.04336750437571474,1739502648.926025,9.299991130828857,2.192605006846808,1739502648.926034,9.299991130828857,0.0,1739502648.9260426,9.299991130828857,0.05429721830757739,1739502648.9260516,9.299991130828857,0.006906812257934776,1739502648.9260612,9.299991130828857,2.1383077885392305 +1739502648.9406605,9.319991111755371,17.23602524136425,1739502648.940665,9.319991111755371,-0.32331453387254605,1739502648.9406807,9.319991111755371,16.372177316377147,1739502648.9406893,9.319991111755371,22.65449429677763,1739502648.9406936,9.319991111755371,-0.12191218785235301,1739502648.9406989,9.319991111755371,0.03715250002525894,1739502648.9407034,9.319991111755371,0.15942226899393913,1739502648.9407082,9.319991111755371,0.04164180245632709,1739502648.9407127,9.319991111755371,2.20065031999077,1739502648.9407175,9.319991111755371,0.0,1739502648.9407222,9.319991111755371,0.05729043418758249,1739502648.9407268,9.319991111755371,0.007746552291795933,1739502648.9407313,9.319991111755371,2.1442952663789723 +1739502648.960358,9.339991092681885,17.23602524136425,1739502648.9603617,9.339991092681885,-0.32331453387254605,1739502648.960366,9.339991092681885,16.372177316377147,1739502648.9603713,9.339991092681885,22.65449429677763,1739502648.960374,9.339991092681885,-0.12191218785235301,1739502648.9603777,9.339991092681885,0.03715250002525894,1739502648.960381,9.339991092681885,0.15942226899393913,1739502648.960384,9.339991092681885,0.04164180245632709,1739502648.9603872,9.339991092681885,2.20065031999077,1739502648.9603906,9.339991092681885,0.0,1739502648.960394,9.339991092681885,0.0563550536117976,1739502648.9603972,9.339991092681885,0.007746552291795933,1739502648.9604006,9.339991092681885,2.1442952663789723 +1739502648.9783869,9.359991073608398,17.23602524136425,1739502648.9783893,9.359991073608398,-0.32331453387254605,1739502648.978392,9.359991073608398,16.372177316377147,1739502648.9783943,9.359991073608398,22.65449429677763,1739502648.9783957,9.359991073608398,-0.12191218785235301,1739502648.9783971,9.359991073608398,0.03715250002525894,1739502648.9783986,9.359991073608398,0.15942226899393913,1739502648.9784002,9.359991073608398,0.04164180245632709,1739502648.9784012,9.359991073608398,2.20065031999077,1739502648.9784029,9.359991073608398,0.0,1739502648.978404,9.359991073608398,0.0563550536117976,1739502648.9784055,9.359991073608398,0.007746552291795933,1739502648.978407,9.359991073608398,2.1442952663789723 +1739502648.9988844,9.379991054534912,17.23602524136425,1739502648.9988866,9.379991054534912,-0.32331453387254605,1739502648.9988894,9.379991054534912,16.372177316377147,1739502648.9988923,9.379991054534912,22.65449429677763,1739502648.9988933,9.379991054534912,-0.12191218785235301,1739502648.9988952,9.379991054534912,0.03715250002525894,1739502648.9988966,9.379991054534912,0.15942226899393913,1739502648.998898,9.379991054534912,0.04164180245632709,1739502648.9988992,9.379991054534912,2.20065031999077,1739502648.9989007,9.379991054534912,0.0,1739502648.998902,9.379991054534912,0.0563550536117976,1739502648.9989033,9.379991054534912,0.007746552291795933,1739502648.998905,9.379991054534912,2.1442952663789723 +1739502649.0263739,9.399991035461426,17.23602524136425,1739502649.0263827,9.399991035461426,-0.32331453387254605,1739502649.0263934,9.399991035461426,16.372177316377147,1739502649.026404,9.399991035461426,22.65449429677763,1739502649.0264087,9.399991035461426,-0.12191218785235301,1739502649.0264153,9.399991035461426,0.03715250002525894,1739502649.0264206,9.399991035461426,0.15942226899393913,1739502649.0264263,9.399991035461426,0.04164180245632709,1739502649.0264416,9.399991035461426,2.20065031999077,1739502649.0264573,9.399991035461426,0.0,1739502649.0264657,9.399991035461426,0.0563550536117976,1739502649.026478,9.399991035461426,0.007746552291795933,1739502649.026493,9.399991035461426,2.1442952663789723 +1739502649.048539,9.429991006851196,17.47219798369533,1739502649.0485427,9.429991006851196,-0.3213947727784241,1739502649.0485468,9.429991006851196,16.605548527229885,1739502649.0485506,9.429991006851196,22.900189452250707,1739502649.0485525,9.429991006851196,-0.121,1739502649.048555,9.429991006851196,0.036902011101122754,1739502649.0485568,9.429991006851196,0.15378163700835906,1739502649.0485585,9.429991006851196,0.04002856992896764,1739502649.0485606,9.429991006851196,2.210603206196326,1739502649.0485625,9.429991006851196,0.0,1739502649.0485644,9.429991006851196,0.06186761767216422,1739502649.0485663,9.429991006851196,0.00858629232565709,1739502649.048568,9.429991006851196,2.1504582659225018 +1739502649.0687244,9.44999098777771,17.47219798369533,1739502649.0687268,9.44999098777771,-0.3213947727784241,1739502649.0687304,9.44999098777771,16.605548527229885,1739502649.068733,9.44999098777771,22.900189452250707,1739502649.0687344,9.44999098777771,-0.121,1739502649.068736,9.44999098777771,0.036902011101122754,1739502649.0687616,9.44999098777771,0.15378163700835906,1739502649.0687628,9.44999098777771,0.04002856992896764,1739502649.0687642,9.44999098777771,2.210603206196326,1739502649.0687656,9.44999098777771,0.0,1739502649.068767,9.44999098777771,0.06014494027382433,1739502649.0687685,9.44999098777771,0.00858629232565709,1739502649.06877,9.44999098777771,2.1504582659225018 +1739502649.090777,9.469990968704224,17.47219798369533,1739502649.090781,9.469990968704224,-0.3213947727784241,1739502649.0907855,9.469990968704224,16.605548527229885,1739502649.090791,9.469990968704224,22.900189452250707,1739502649.0907936,9.469990968704224,-0.121,1739502649.090798,9.469990968704224,0.036902011101122754,1739502649.0908194,9.469990968704224,0.15378163700835906,1739502649.0908227,9.469990968704224,0.04002856992896764,1739502649.0908263,9.469990968704224,2.210603206196326,1739502649.0908296,9.469990968704224,0.0,1739502649.090833,9.469990968704224,0.06014494027382433,1739502649.0908365,9.469990968704224,0.00858629232565709,1739502649.09084,9.469990968704224,2.1504582659225018 +1739502649.1095407,9.489990949630737,17.47219798369533,1739502649.1095445,9.489990949630737,-0.3213947727784241,1739502649.109549,9.489990949630737,16.605548527229885,1739502649.1095538,9.489990949630737,22.900189452250707,1739502649.1095567,9.489990949630737,-0.121,1739502649.1095603,9.489990949630737,0.036902011101122754,1739502649.1095636,9.489990949630737,0.15378163700835906,1739502649.109567,9.489990949630737,0.04002856992896764,1739502649.1095703,9.489990949630737,2.210603206196326,1739502649.1095736,9.489990949630737,0.0,1739502649.109577,9.489990949630737,0.06014494027382433,1739502649.1095803,9.489990949630737,0.00858629232565709,1739502649.1095836,9.489990949630737,2.1504582659225018 +1739502649.129565,9.509990930557251,17.47219798369533,1739502649.1295714,9.509990930557251,-0.3213947727784241,1739502649.1295767,9.509990930557251,16.605548527229885,1739502649.1295831,9.509990930557251,22.900189452250707,1739502649.1295872,9.509990930557251,-0.121,1739502649.1295924,9.509990930557251,0.036902011101122754,1739502649.1295965,9.509990930557251,0.15378163700835906,1739502649.1296008,9.509990930557251,0.04002856992896764,1739502649.1296048,9.509990930557251,2.210603206196326,1739502649.1296084,9.509990930557251,0.0,1739502649.1296124,9.509990930557251,0.06014494027382433,1739502649.1296165,9.509990930557251,0.00858629232565709,1739502649.1296206,9.509990930557251,2.1504582659225018 +1739502649.1496406,9.529990911483765,17.70906730956616,1739502649.1496441,9.529990911483765,-0.31927042312120335,1739502649.1496484,9.529990911483765,16.903044074807163,1739502649.1496532,9.529990911483765,23.210834524041204,1739502649.149656,9.529990911483765,-0.12,1739502649.1496596,9.529990911483765,0.03620352276430119,1739502649.149663,9.529990911483765,0.1474025027465181,1739502649.1496665,9.529990911483765,0.03734821635069992,1739502649.1496696,9.529990911483765,2.221913429143492,1739502649.1496732,9.529990911483765,0.0,1739502649.1496766,9.529990911483765,0.06703078344003381,1739502649.14968,9.529990911483765,0.009426032359518248,1739502649.1496832,9.529990911483765,2.1570344731037467 +1739502649.1682904,9.549990892410278,17.70906730956616,1739502649.1682932,9.549990892410278,-0.31927042312120335,1739502649.1682959,9.549990892410278,16.903044074807163,1739502649.1682987,9.549990892410278,23.210834524041204,1739502649.1683,9.549990892410278,-0.12,1739502649.1683018,9.549990892410278,0.03620352276430119,1739502649.1683033,9.549990892410278,0.1474025027465181,1739502649.168305,9.549990892410278,0.03734821635069992,1739502649.1683059,9.549990892410278,2.221913429143492,1739502649.168308,9.549990892410278,0.0,1739502649.168309,9.549990892410278,0.06487895603974536,1739502649.1683106,9.549990892410278,0.009426032359518248,1739502649.1683118,9.549990892410278,2.1570344731037467 +1739502649.1886618,9.569990873336792,17.70906730956616,1739502649.1886647,9.569990873336792,-0.31927042312120335,1739502649.1886675,9.569990873336792,16.903044074807163,1739502649.1886811,9.569990873336792,23.210834524041204,1739502649.1886847,9.569990873336792,-0.12,1739502649.1886868,9.569990873336792,0.03620352276430119,1739502649.1886883,9.569990873336792,0.1474025027465181,1739502649.18869,9.569990873336792,0.03734821635069992,1739502649.1886911,9.569990873336792,2.221913429143492,1739502649.1886928,9.569990873336792,0.0,1739502649.188694,9.569990873336792,0.06487895603974536,1739502649.1886957,9.569990873336792,0.009426032359518248,1739502649.1886969,9.569990873336792,2.1570344731037467 +1739502649.2087286,9.589990854263306,17.70906730956616,1739502649.208731,9.589990854263306,-0.31927042312120335,1739502649.2087343,9.589990854263306,16.903044074807163,1739502649.2087371,9.589990854263306,23.210834524041204,1739502649.2087386,9.589990854263306,-0.12,1739502649.20874,9.589990854263306,0.03620352276430119,1739502649.2087417,9.589990854263306,0.1474025027465181,1739502649.2087429,9.589990854263306,0.03734821635069992,1739502649.2087443,9.589990854263306,2.221913429143492,1739502649.2087457,9.589990854263306,0.0,1739502649.2087471,9.589990854263306,0.06487895603974536,1739502649.2087488,9.589990854263306,0.009426032359518248,1739502649.2087502,9.589990854263306,2.1570344731037467 +1739502649.229136,9.60999083518982,17.70906730956616,1739502649.2291389,9.60999083518982,-0.31927042312120335,1739502649.229142,9.60999083518982,16.903044074807163,1739502649.2291453,9.60999083518982,23.210834524041204,1739502649.229147,9.60999083518982,-0.12,1739502649.2291486,9.60999083518982,0.03620352276430119,1739502649.2291505,9.60999083518982,0.1474025027465181,1739502649.229152,9.60999083518982,0.03734821635069992,1739502649.2291536,9.60999083518982,2.221913429143492,1739502649.2291553,9.60999083518982,0.0,1739502649.229157,9.60999083518982,0.06487895603974536,1739502649.2291584,9.60999083518982,0.009426032359518248,1739502649.2291603,9.60999083518982,2.1570344731037467 +1739502649.248302,9.629990816116333,17.70906730956616,1739502649.2483046,9.629990816116333,-0.31927042312120335,1739502649.2483077,9.629990816116333,16.903044074807163,1739502649.2483108,9.629990816116333,23.210834524041204,1739502649.2483122,9.629990816116333,-0.12,1739502649.2483141,9.629990816116333,0.03620352276430119,1739502649.2483158,9.629990816116333,0.1474025027465181,1739502649.2483175,9.629990816116333,0.03734821635069992,1739502649.2483187,9.629990816116333,2.221913429143492,1739502649.2483206,9.629990816116333,0.0,1739502649.248322,9.629990816116333,0.06487895603974536,1739502649.2483237,9.629990816116333,0.009426032359518248,1739502649.248325,9.629990816116333,2.1570344731037467 +1739502649.2686515,9.649990797042847,17.946689576017263,1739502649.268654,9.649990797042847,-0.3169397583136062,1739502649.2686572,9.649990797042847,17.179385043531553,1739502649.2686605,9.649990797042847,23.50146379369435,1739502649.268662,9.649990797042847,-0.119,1739502649.2686641,9.649990797042847,0.03561909691219017,1739502649.2686656,9.649990797042847,0.14090628212692993,1739502649.2686672,9.649990797042847,0.03502578725411877,1739502649.2686687,9.649990797042847,2.2334907184030963,1739502649.2686808,9.649990797042847,0.0,1739502649.2686844,9.649990797042847,0.07132420350019908,1739502649.268686,9.649990797042847,0.010265772393379405,1739502649.2686877,9.649990797042847,2.164180656054863 +1739502649.2884061,9.66999077796936,17.946689576017263,1739502649.2884085,9.66999077796936,-0.3169397583136062,1739502649.2884119,9.66999077796936,17.179385043531553,1739502649.288415,9.66999077796936,23.50146379369435,1739502649.2884166,9.66999077796936,-0.119,1739502649.2884185,9.66999077796936,0.03561909691219017,1739502649.2884202,9.66999077796936,0.14090628212692993,1739502649.2884219,9.66999077796936,0.03502578725411877,1739502649.288423,9.66999077796936,2.2334907184030963,1739502649.2884252,9.66999077796936,0.0,1739502649.2884266,9.66999077796936,0.06931006234823345,1739502649.2884283,9.66999077796936,0.010265772393379405,1739502649.2884297,9.66999077796936,2.164180656054863 +1739502649.308241,9.689990758895874,17.946689576017263,1739502649.3082442,9.689990758895874,-0.3169397583136062,1739502649.3082478,9.689990758895874,17.179385043531553,1739502649.3082511,9.689990758895874,23.50146379369435,1739502649.3082526,9.689990758895874,-0.119,1739502649.3082547,9.689990758895874,0.03561909691219017,1739502649.3082566,9.689990758895874,0.14090628212692993,1739502649.308258,9.689990758895874,0.03502578725411877,1739502649.3082595,9.689990758895874,2.2334907184030963,1739502649.3082614,9.689990758895874,0.0,1739502649.3082628,9.689990758895874,0.06931006234823345,1739502649.3082647,9.689990758895874,0.010265772393379405,1739502649.3082662,9.689990758895874,2.164180656054863 +1739502649.3282976,9.709990739822388,17.946689576017263,1739502649.3283007,9.709990739822388,-0.3169397583136062,1739502649.3283043,9.709990739822388,17.179385043531553,1739502649.3283076,9.709990739822388,23.50146379369435,1739502649.3283098,9.709990739822388,-0.119,1739502649.328312,9.709990739822388,0.03561909691219017,1739502649.3283134,9.709990739822388,0.14090628212692993,1739502649.328315,9.709990739822388,0.03502578725411877,1739502649.3283167,9.709990739822388,2.2334907184030963,1739502649.3283188,9.709990739822388,0.0,1739502649.3283203,9.709990739822388,0.06931006234823345,1739502649.328322,9.709990739822388,0.010265772393379405,1739502649.3283236,9.709990739822388,2.164180656054863 +1739502649.3485837,9.729990720748901,17.946689576017263,1739502649.3485863,9.729990720748901,-0.3169397583136062,1739502649.3485897,9.729990720748901,17.179385043531553,1739502649.348593,9.729990720748901,23.50146379369435,1739502649.3485944,9.729990720748901,-0.119,1739502649.3485963,9.729990720748901,0.03561909691219017,1739502649.348598,9.729990720748901,0.14090628212692993,1739502649.3485994,9.729990720748901,0.03502578725411877,1739502649.3486009,9.729990720748901,2.2334907184030963,1739502649.3486025,9.729990720748901,0.0,1739502649.3486042,9.729990720748901,0.06931006234823345,1739502649.348606,9.729990720748901,0.010265772393379405,1739502649.3486078,9.729990720748901,2.164180656054863 +1739502649.368371,9.749990701675415,18.185114401325777,1739502649.3683743,9.749990701675415,-0.31440098253542104,1739502649.368378,9.749990701675415,17.41655106410047,1739502649.3683813,9.749990701675415,23.75378088587902,1739502649.3683827,9.749990701675415,-0.11773348873269089,1739502649.3683848,9.749990701675415,0.03530213009431217,1739502649.3683863,9.749990701675415,0.13481374254005413,1739502649.3683884,9.749990701675415,0.033345231411683114,1739502649.3683896,9.749990701675415,2.244403395661785,1739502649.3683918,9.749990701675415,0.0,1739502649.3683932,9.749990701675415,0.0741603673194695,1739502649.368395,9.749990701675415,0.011105512427240562,1739502649.3683965,9.749990701675415,2.171758749639611 +1739502649.3887508,9.769990682601929,18.185114401325777,1739502649.3887534,9.769990682601929,-0.31440098253542104,1739502649.3887568,9.769990682601929,17.41655106410047,1739502649.38876,9.769990682601929,23.75378088587902,1739502649.3887613,9.769990682601929,-0.11773348873269089,1739502649.3887637,9.769990682601929,0.03530213009431217,1739502649.388765,9.769990682601929,0.13481374254005413,1739502649.3887668,9.769990682601929,0.033345231411683114,1739502649.3887682,9.769990682601929,2.244403395661785,1739502649.38877,9.769990682601929,0.0,1739502649.3887715,9.769990682601929,0.07264464602217391,1739502649.3887734,9.769990682601929,0.011105512427240562,1739502649.3887749,9.769990682601929,2.171758749639611 +1739502649.415644,9.789990663528442,18.185114401325777,1739502649.4156525,9.789990663528442,-0.31440098253542104,1739502649.4156632,9.789990663528442,17.41655106410047,1739502649.415674,9.789990663528442,23.75378088587902,1739502649.415679,9.789990663528442,-0.11773348873269089,1739502649.4156852,9.789990663528442,0.03530213009431217,1739502649.41569,9.789990663528442,0.13481374254005413,1739502649.4156945,9.789990663528442,0.033345231411683114,1739502649.415699,9.789990663528442,2.244403395661785,1739502649.4157045,9.789990663528442,0.0,1739502649.4157095,9.789990663528442,0.07264464602217391,1739502649.4157145,9.789990663528442,0.011105512427240562,1739502649.4157197,9.789990663528442,2.171758749639611 +1739502649.4360926,9.809990644454956,18.185114401325777,1739502649.4361057,9.809990644454956,-0.31440098253542104,1739502649.4361227,9.809990644454956,17.41655106410047,1739502649.4361424,9.809990644454956,23.75378088587902,1739502649.4361534,9.809990644454956,-0.11773348873269089,1739502649.4361675,9.809990644454956,0.03530213009431217,1739502649.43618,9.809990644454956,0.13481374254005413,1739502649.4361928,9.809990644454956,0.033345231411683114,1739502649.4362054,9.809990644454956,2.244403395661785,1739502649.4362183,9.809990644454956,0.0,1739502649.4362311,9.809990644454956,0.07264464602217391,1739502649.436244,9.809990644454956,0.011105512427240562,1739502649.436257,9.809990644454956,2.171758749639611 +1739502649.4596076,9.839990615844727,18.185114401325777,1739502649.4596143,9.839990615844727,-0.31440098253542104,1739502649.4596236,9.839990615844727,17.41655106410047,1739502649.459634,9.839990615844727,23.75378088587902,1739502649.4596398,9.839990615844727,-0.11773348873269089,1739502649.4596474,9.839990615844727,0.03530213009431217,1739502649.4596543,9.839990615844727,0.13481374254005413,1739502649.459661,9.839990615844727,0.033345231411683114,1739502649.4596677,9.839990615844727,2.244403395661785,1739502649.4596746,9.839990615844727,0.0,1739502649.4596813,9.839990615844727,0.07264464602217391,1739502649.4596882,9.839990615844727,0.011105512427240562,1739502649.4596949,9.839990615844727,2.171758749639611 +1739502649.4772632,9.85999059677124,18.424393363773532,1739502649.4772673,9.85999059677124,-0.3116521524436626,1739502649.477272,9.85999059677124,17.548861981669305,1739502649.4772775,9.85999059677124,23.902056241694744,1739502649.4772806,9.85999059677124,-0.117,1739502649.4772844,9.85999059677124,0.03552067450985021,1739502649.477288,9.85999059677124,0.12920775533143383,1739502649.4772916,9.85999059677124,0.03302885977744354,1739502649.477295,9.85999059677124,2.254491678047158,1739502649.4772987,9.85999059677124,0.0,1739502649.4773023,9.85999059677124,0.07570584323383328,1739502649.477306,9.85999059677124,0.01194525246110172,1739502649.4773097,9.85999059677124,2.1797424595691806 +1739502649.496779,9.879990577697754,18.424393363773532,1739502649.4967828,9.879990577697754,-0.3116521524436626,1739502649.4967875,9.879990577697754,17.548861981669305,1739502649.4967923,9.879990577697754,23.902056241694744,1739502649.4967952,9.879990577697754,-0.117,1739502649.4967988,9.879990577697754,0.03552067450985021,1739502649.496802,9.879990577697754,0.12920775533143383,1739502649.4968054,9.879990577697754,0.03302885977744354,1739502649.4968085,9.879990577697754,2.254491678047158,1739502649.4968119,9.879990577697754,0.0,1739502649.496815,9.879990577697754,0.07474921847797766,1739502649.496818,9.879990577697754,0.01194525246110172,1739502649.4968214,9.879990577697754,2.1797424595691806 +1739502649.5196214,9.899990558624268,18.424393363773532,1739502649.5196285,9.899990558624268,-0.3116521524436626,1739502649.519638,9.899990558624268,17.548861981669305,1739502649.5196493,9.899990558624268,23.902056241694744,1739502649.5196555,9.899990558624268,-0.117,1739502649.5196633,9.899990558624268,0.03552067450985021,1739502649.5196707,9.899990558624268,0.12920775533143383,1739502649.519678,9.899990558624268,0.03302885977744354,1739502649.5196853,9.899990558624268,2.254491678047158,1739502649.519693,9.899990558624268,0.0,1739502649.5197003,9.899990558624268,0.07474921847797766,1739502649.5197077,9.899990558624268,0.01194525246110172,1739502649.5197148,9.899990558624268,2.1797424595691806 +1739502649.5378625,9.919990539550781,18.424393363773532,1739502649.5378664,9.919990539550781,-0.3116521524436626,1739502649.5378711,9.919990539550781,17.548861981669305,1739502649.5378768,9.919990539550781,23.902056241694744,1739502649.5378797,9.919990539550781,-0.117,1739502649.537884,9.919990539550781,0.03552067450985021,1739502649.5378876,9.919990539550781,0.12920775533143383,1739502649.5378914,9.919990539550781,0.03302885977744354,1739502649.537895,9.919990539550781,2.254491678047158,1739502649.5378988,9.919990539550781,0.0,1739502649.5379024,9.919990539550781,0.07474921847797766,1739502649.5379062,9.919990539550781,0.01194525246110172,1739502649.5379097,9.919990539550781,2.1797424595691806 +1739502649.555763,9.939990520477295,18.424393363773532,1739502649.5557663,9.939990520477295,-0.3116521524436626,1739502649.5557706,9.939990520477295,17.548861981669305,1739502649.5557756,9.939990520477295,23.902056241694744,1739502649.5557783,9.939990520477295,-0.117,1739502649.5557818,9.939990520477295,0.03552067450985021,1739502649.5557852,9.939990520477295,0.12920775533143383,1739502649.5557885,9.939990520477295,0.03302885977744354,1739502649.5557916,9.939990520477295,2.254491678047158,1739502649.555795,9.939990520477295,0.0,1739502649.5557983,9.939990520477295,0.07474921847797766,1739502649.5558016,9.939990520477295,0.01194525246110172,1739502649.555805,9.939990520477295,2.1797424595691806 +1739502649.5762033,9.959990501403809,18.424393363773532,1739502649.5762064,9.959990501403809,-0.3116521524436626,1739502649.5762105,9.959990501403809,17.548861981669305,1739502649.5762153,9.959990501403809,23.902056241694744,1739502649.576218,9.959990501403809,-0.117,1739502649.5762212,9.959990501403809,0.03552067450985021,1739502649.5762243,9.959990501403809,0.12920775533143383,1739502649.5762274,9.959990501403809,0.03302885977744354,1739502649.5762303,9.959990501403809,2.254491678047158,1739502649.5762334,9.959990501403809,0.0,1739502649.5762365,9.959990501403809,0.07474921847797766,1739502649.5762398,9.959990501403809,0.01194525246110172,1739502649.576243,9.959990501403809,2.1797424595691806 +1739502649.596105,9.979990482330322,18.66455855678383,1739502649.596108,9.979990482330322,-0.3086914349488854,1739502649.5961108,9.979990482330322,17.80814317171334,1739502649.5961134,9.979990482330322,24.177743401064358,1739502649.5961149,9.979990482330322,-0.117,1739502649.5961165,9.979990482330322,0.03475563568412437,1739502649.596118,9.979990482330322,0.12119166195607603,1739502649.5961194,9.979990482330322,0.030583634503862964,1739502649.5961206,9.979990482330322,2.2689959078884865,1739502649.596122,9.979990482330322,0.0,1739502649.5961235,9.979990482330322,0.08391466874191737,1739502649.596125,9.979990482330322,0.012784992494962876,1739502649.5961277,9.979990482330322,2.1879454442319695 +1739502649.6155643,9.999990463256836,18.66455855678383,1739502649.6155665,9.999990463256836,-0.3086914349488854,1739502649.615569,9.999990463256836,17.80814317171334,1739502649.615572,9.999990463256836,24.177743401064358,1739502649.6155732,9.999990463256836,-0.117,1739502649.615575,9.999990463256836,0.03475563568412437,1739502649.6155763,9.999990463256836,0.12119166195607603,1739502649.6155777,9.999990463256836,0.030583634503862964,1739502649.615579,9.999990463256836,2.2689959078884865,1739502649.6155803,9.999990463256836,0.0,1739502649.6155818,9.999990463256836,0.08105046365651702,1739502649.6155832,9.999990463256836,0.012784992494962876,1739502649.6155846,9.999990463256836,2.1879454442319695 +1739502649.635594,10.01999044418335,18.66455855678383,1739502649.635597,10.01999044418335,-0.3086914349488854,1739502649.6356003,10.01999044418335,17.80814317171334,1739502649.635603,10.01999044418335,24.177743401064358,1739502649.6356044,10.01999044418335,-0.117,1739502649.6356065,10.01999044418335,0.03475563568412437,1739502649.635608,10.01999044418335,0.12119166195607603,1739502649.6356094,10.01999044418335,0.030583634503862964,1739502649.6356106,10.01999044418335,2.2689959078884865,1739502649.6356125,10.01999044418335,0.0,1739502649.635614,10.01999044418335,0.08105046365651702,1739502649.6356156,10.01999044418335,0.012784992494962876,1739502649.635617,10.01999044418335,2.1879454442319695 +1739502649.655471,10.039990425109863,18.66455855678383,1739502649.6554735,10.039990425109863,-0.3086914349488854,1739502649.6554763,10.039990425109863,17.80814317171334,1739502649.655479,10.039990425109863,24.177743401064358,1739502649.6554806,10.039990425109863,-0.117,1739502649.6554823,10.039990425109863,0.03475563568412437,1739502649.6554837,10.039990425109863,0.12119166195607603,1739502649.6554852,10.039990425109863,0.030583634503862964,1739502649.6554863,10.039990425109863,2.2689959078884865,1739502649.655488,10.039990425109863,0.0,1739502649.6554892,10.039990425109863,0.08105046365651702,1739502649.6554909,10.039990425109863,0.012784992494962876,1739502649.655492,10.039990425109863,2.1879454442319695 +1739502649.6752975,10.059990406036377,18.66455855678383,1739502649.6753,10.059990406036377,-0.3086914349488854,1739502649.6753027,10.059990406036377,17.80814317171334,1739502649.6753054,10.059990406036377,24.177743401064358,1739502649.6753068,10.059990406036377,-0.117,1739502649.6753085,10.059990406036377,0.03475563568412437,1739502649.67531,10.059990406036377,0.12119166195607603,1739502649.6753113,10.059990406036377,0.030583634503862964,1739502649.6753123,10.059990406036377,2.2689959078884865,1739502649.675314,10.059990406036377,0.0,1739502649.6753151,10.059990406036377,0.08105046365651702,1739502649.6753168,10.059990406036377,0.012784992494962876,1739502649.675318,10.059990406036377,2.1879454442319695 +1739502649.6957378,10.07999038696289,18.90565398542263,1739502649.6957407,10.07999038696289,-0.30551675414854795,1739502649.695744,10.07999038696289,18.131946140306823,1739502649.6957474,10.07999038696289,24.519257627701712,1739502649.6957488,10.07999038696289,-0.11452636075039259,1739502649.695751,10.07999038696289,0.034009659943140924,1739502649.6957524,10.07999038696289,0.11449118473487227,1739502649.6957543,10.07999038696289,0.027869864567734888,1739502649.6957557,10.07999038696289,2.281191248845433,1739502649.6957576,10.07999038696289,0.0,1739502649.6957593,10.07999038696289,0.08590093882792349,1739502649.695761,10.07999038696289,0.013624732528824034,1739502649.6957626,10.07999038696289,2.196806084502393 +1739502649.7167768,10.099990367889404,18.90565398542263,1739502649.7167928,10.099990367889404,-0.30551675414854795,1739502649.716799,10.099990367889404,18.131946140306823,1739502649.7168176,10.099990367889404,24.519257627701712,1739502649.716826,10.099990367889404,-0.11452636075039259,1739502649.7168312,10.099990367889404,0.034009659943140924,1739502649.7168357,10.099990367889404,0.11449118473487227,1739502649.716838,10.099990367889404,0.027869864567734888,1739502649.7168393,10.099990367889404,2.281191248845433,1739502649.7168412,10.099990367889404,0.0,1739502649.7168427,10.099990367889404,0.08438516434303978,1739502649.7168446,10.099990367889404,0.013624732528824034,1739502649.7168462,10.099990367889404,2.196806084502393 +1739502649.735878,10.119990348815918,18.90565398542263,1739502649.7358801,10.119990348815918,-0.30551675414854795,1739502649.735883,10.119990348815918,18.131946140306823,1739502649.7358856,10.119990348815918,24.519257627701712,1739502649.7358868,10.119990348815918,-0.11452636075039259,1739502649.7358885,10.119990348815918,0.034009659943140924,1739502649.73589,10.119990348815918,0.11449118473487227,1739502649.735891,10.119990348815918,0.027869864567734888,1739502649.7358923,10.119990348815918,2.281191248845433,1739502649.7358937,10.119990348815918,0.0,1739502649.7358954,10.119990348815918,0.08438516434303978,1739502649.7358966,10.119990348815918,0.013624732528824034,1739502649.7358978,10.119990348815918,2.196806084502393 +1739502649.7577293,10.139990329742432,18.90565398542263,1739502649.7577362,10.139990329742432,-0.30551675414854795,1739502649.757744,10.139990329742432,18.131946140306823,1739502649.7577515,10.139990329742432,24.519257627701712,1739502649.7577553,10.139990329742432,-0.11452636075039259,1739502649.7577603,10.139990329742432,0.034009659943140924,1739502649.757764,10.139990329742432,0.11449118473487227,1739502649.757768,10.139990329742432,0.027869864567734888,1739502649.7577715,10.139990329742432,2.281191248845433,1739502649.7577758,10.139990329742432,0.0,1739502649.7577794,10.139990329742432,0.08438516434303978,1739502649.7577834,10.139990329742432,0.013624732528824034,1739502649.7577875,10.139990329742432,2.196806084502393 +1739502649.7786663,10.159990310668945,18.90565398542263,1739502649.7786725,10.159990310668945,-0.30551675414854795,1739502649.77868,10.159990310668945,18.131946140306823,1739502649.7786875,10.159990310668945,24.519257627701712,1739502649.7786913,10.159990310668945,-0.11452636075039259,1739502649.7786956,10.159990310668945,0.034009659943140924,1739502649.7786996,10.159990310668945,0.11449118473487227,1739502649.7787032,10.159990310668945,0.027869864567734888,1739502649.7787066,10.159990310668945,2.281191248845433,1739502649.7787106,10.159990310668945,0.0,1739502649.7787144,10.159990310668945,0.08438516434303978,1739502649.7787182,10.159990310668945,0.013624732528824034,1739502649.7787218,10.159990310668945,2.196806084502393 +1739502649.8002417,10.169990301132202,18.90565398542263,1739502649.8002496,10.169990301132202,-0.30551675414854795,1739502649.8002605,10.169990301132202,18.131946140306823,1739502649.8002737,10.169990301132202,24.519257627701712,1739502649.800282,10.169990301132202,-0.11452636075039259,1739502649.800289,10.169990301132202,0.034009659943140924,1739502649.8002932,10.169990301132202,0.11449118473487227,1739502649.8002975,10.169990301132202,0.027869864567734888,1739502649.8003016,10.169990301132202,2.281191248845433,1739502649.800306,10.169990301132202,0.0,1739502649.8003104,10.169990301132202,0.08438516434303978,1739502649.8003147,10.169990301132202,0.013624732528824034,1739502649.8003192,10.169990301132202,2.196806084502393 +1739502649.8173885,10.199990272521973,19.147744578853096,1739502649.817393,10.199990272521973,-0.3021256360977782,1739502649.8173988,10.199990272521973,18.47875913777556,1739502649.817405,10.199990272521973,24.884606309131488,1739502649.8174078,10.199990272521973,-0.114,1739502649.8174112,10.199990272521973,0.03278068309649638,1739502649.8174138,10.199990272521973,0.10512817095303835,1739502649.8174164,10.199990272521973,0.02450502440160241,1739502649.817419,10.199990272521973,2.298342463560086,1739502649.8174224,10.199990272521973,0.0,1739502649.8174253,10.199990272521973,0.0958503356332191,1739502649.8174279,10.199990272521973,0.014464472562685191,1739502649.8174307,10.199990272521973,2.2060749963041597 +1739502649.8383417,10.219990253448486,19.147744578853096,1739502649.8383467,10.219990253448486,-0.3021256360977782,1739502649.8383527,10.219990253448486,18.47875913777556,1739502649.8383586,10.219990253448486,24.884606309131488,1739502649.838361,10.219990253448486,-0.114,1739502649.8383646,10.219990253448486,0.03278068309649638,1739502649.8383675,10.219990253448486,0.10512817095303835,1739502649.8383703,10.219990253448486,0.02450502440160241,1739502649.8383732,10.219990253448486,2.298342463560086,1739502649.8383763,10.219990253448486,0.0,1739502649.8383787,10.219990253448486,0.0922674672559265,1739502649.8383818,10.219990253448486,0.014464472562685191,1739502649.8383849,10.219990253448486,2.2060749963041597 +1739502649.8569722,10.239990234375,19.147744578853096,1739502649.856976,10.239990234375,-0.3021256360977782,1739502649.8569803,10.239990234375,18.47875913777556,1739502649.8569841,10.239990234375,24.884606309131488,1739502649.8569858,10.239990234375,-0.114,1739502649.8569887,10.239990234375,0.03278068309649638,1739502649.8569908,10.239990234375,0.10512817095303835,1739502649.8569927,10.239990234375,0.02450502440160241,1739502649.8569949,10.239990234375,2.298342463560086,1739502649.856997,10.239990234375,0.0,1739502649.8569992,10.239990234375,0.0922674672559265,1739502649.8570013,10.239990234375,0.014464472562685191,1739502649.8570032,10.239990234375,2.2060749963041597 +1739502649.8760037,10.259990215301514,19.147744578853096,1739502649.876006,10.259990215301514,-0.3021256360977782,1739502649.876009,10.259990215301514,18.47875913777556,1739502649.8760116,10.259990215301514,24.884606309131488,1739502649.8760128,10.259990215301514,-0.114,1739502649.8760147,10.259990215301514,0.03278068309649638,1739502649.876016,10.259990215301514,0.10512817095303835,1739502649.876017,10.259990215301514,0.02450502440160241,1739502649.8760185,10.259990215301514,2.298342463560086,1739502649.8760197,10.259990215301514,0.0,1739502649.876021,10.259990215301514,0.0922674672559265,1739502649.8760226,10.259990215301514,0.014464472562685191,1739502649.8760238,10.259990215301514,2.2060749963041597 +1739502649.8963404,10.279990196228027,19.147744578853096,1739502649.896343,10.279990196228027,-0.3021256360977782,1739502649.8963459,10.279990196228027,18.47875913777556,1739502649.8963485,10.279990196228027,24.884606309131488,1739502649.8963497,10.279990196228027,-0.114,1739502649.8963516,10.279990196228027,0.03278068309649638,1739502649.8963528,10.279990196228027,0.10512817095303835,1739502649.896354,10.279990196228027,0.02450502440160241,1739502649.8963552,10.279990196228027,2.298342463560086,1739502649.8963566,10.279990196228027,0.0,1739502649.8963578,10.279990196228027,0.0922674672559265,1739502649.8963592,10.279990196228027,0.014464472562685191,1739502649.8963604,10.279990196228027,2.2060749963041597 +1739502649.916037,10.299990177154541,19.390889414743697,1739502649.9160392,10.299990177154541,-0.2985155232670609,1739502649.916042,10.299990177154541,18.613556403817512,1739502649.9160442,10.299990177154541,25.039573002785524,1739502649.9160457,10.299990177154541,-0.113304284530199,1739502649.916047,10.299990177154541,0.03277664723553212,1739502649.9160483,10.299990177154541,0.09874426926201947,1739502649.9160497,10.299990177154541,0.023741213162283604,1739502649.916051,10.299990177154541,2.310110401998376,1739502649.9160526,10.299990177154541,0.0,1739502649.9160535,10.299990177154541,0.0947137379482898,1739502649.916055,10.299990177154541,0.015304212596546348,1739502649.9160564,10.299990177154541,2.2161611241426686 +1739502649.9376156,10.319990158081055,19.390889414743697,1739502649.937618,10.319990158081055,-0.2985155232670609,1739502649.9376204,10.319990158081055,18.613556403817512,1739502649.9376233,10.319990158081055,25.039573002785524,1739502649.937625,10.319990158081055,-0.113304284530199,1739502649.9376264,10.319990158081055,0.03277664723553212,1739502649.9376276,10.319990158081055,0.09874426926201947,1739502649.937629,10.319990158081055,0.023741213162283604,1739502649.9376302,10.319990158081055,2.310110401998376,1739502649.9376318,10.319990158081055,0.0,1739502649.937633,10.319990158081055,0.09394927785570717,1739502649.9376342,10.319990158081055,0.015304212596546348,1739502649.9376357,10.319990158081055,2.2161611241426686 +1739502649.957347,10.339990139007568,19.390889414743697,1739502649.957349,10.339990139007568,-0.2985155232670609,1739502649.9573517,10.339990139007568,18.613556403817512,1739502649.9573545,10.339990139007568,25.039573002785524,1739502649.9573555,10.339990139007568,-0.113304284530199,1739502649.9573574,10.339990139007568,0.03277664723553212,1739502649.9573586,10.339990139007568,0.09874426926201947,1739502649.9573598,10.339990139007568,0.023741213162283604,1739502649.957361,10.339990139007568,2.310110401998376,1739502649.9573624,10.339990139007568,0.0,1739502649.9573636,10.339990139007568,0.09394927785570717,1739502649.957365,10.339990139007568,0.015304212596546348,1739502649.9573665,10.339990139007568,2.2161611241426686 +1739502649.9759574,10.359990119934082,19.390889414743697,1739502649.9759598,10.359990119934082,-0.2985155232670609,1739502649.9759626,10.359990119934082,18.613556403817512,1739502649.9759655,10.359990119934082,25.039573002785524,1739502649.9759667,10.359990119934082,-0.113304284530199,1739502649.9759686,10.359990119934082,0.03277664723553212,1739502649.97597,10.359990119934082,0.09874426926201947,1739502649.9759712,10.359990119934082,0.023741213162283604,1739502649.9759727,10.359990119934082,2.310110401998376,1739502649.975974,10.359990119934082,0.0,1739502649.9759755,10.359990119934082,0.09394927785570717,1739502649.975977,10.359990119934082,0.015304212596546348,1739502649.9759781,10.359990119934082,2.2161611241426686 +1739502649.9959676,10.379990100860596,19.390889414743697,1739502649.99597,10.379990100860596,-0.2985155232670609,1739502649.9959729,10.379990100860596,18.613556403817512,1739502649.9959755,10.379990100860596,25.039573002785524,1739502649.9959767,10.379990100860596,-0.113304284530199,1739502649.9959784,10.379990100860596,0.03277664723553212,1739502649.9959798,10.379990100860596,0.09874426926201947,1739502649.995981,10.379990100860596,0.023741213162283604,1739502649.9959822,10.379990100860596,2.310110401998376,1739502649.9959836,10.379990100860596,0.0,1739502649.9959848,10.379990100860596,0.09394927785570717,1739502649.9959862,10.379990100860596,0.015304212596546348,1739502649.9959874,10.379990100860596,2.2161611241426686 +1739502650.0159106,10.39999008178711,19.390889414743697,1739502650.0159128,10.39999008178711,-0.2985155232670609,1739502650.0159156,10.39999008178711,18.613556403817512,1739502650.015918,10.39999008178711,25.039573002785524,1739502650.0159194,10.39999008178711,-0.113304284530199,1739502650.0159209,10.39999008178711,0.03277664723553212,1739502650.015922,10.39999008178711,0.09874426926201947,1739502650.0159237,10.39999008178711,0.023741213162283604,1739502650.0159247,10.39999008178711,2.310110401998376,1739502650.0159264,10.39999008178711,0.0,1739502650.0159276,10.39999008178711,0.09394927785570717,1739502650.015929,10.39999008178711,0.015304212596546348,1739502650.0159304,10.39999008178711,2.2161611241426686 +1739502650.0359356,10.419990062713623,19.63515378414241,1739502650.0359378,10.419990062713623,-0.29468362078968724,1739502650.035941,10.419990062713623,19.382224832344857,1739502650.0359435,10.419990062713623,25.82883295570972,1739502650.035945,10.419990062713623,-0.113,1739502650.0359468,10.419990062713623,0.029325305966770535,1739502650.035948,10.419990062713623,0.08167382561880875,1739502650.0359492,10.419990062713623,0.01633687098393416,1739502650.0359507,10.419990062713623,2.3418744866921877,1739502650.035952,10.419990062713623,0.0,1739502650.0359535,10.419990062713623,0.1251684091470225,1739502650.035955,10.419990062713623,0.016143952630407493,1739502650.0359561,10.419990062713623,2.2264620624702234 +1739502650.055877,10.439990043640137,19.63515378414241,1739502650.055879,10.439990043640137,-0.29468362078968724,1739502650.0558817,10.439990043640137,19.382224832344857,1739502650.0558846,10.439990043640137,25.82883295570972,1739502650.055886,10.439990043640137,-0.113,1739502650.0558877,10.439990043640137,0.029325305966770535,1739502650.055889,10.439990043640137,0.08167382561880875,1739502650.0558903,10.439990043640137,0.01633687098393416,1739502650.0558918,10.439990043640137,2.3418744866921877,1739502650.0558932,10.439990043640137,0.0,1739502650.0558946,10.439990043640137,0.1154124242219643,1739502650.0558958,10.439990043640137,0.016143952630407493,1739502650.055897,10.439990043640137,2.2264620624702234 +1739502650.078777,10.45999002456665,19.63515378414241,1739502650.0787852,10.45999002456665,-0.29468362078968724,1739502650.0787952,10.45999002456665,19.382224832344857,1739502650.0788052,10.45999002456665,25.82883295570972,1739502650.0788097,10.45999002456665,-0.113,1739502650.078816,10.45999002456665,0.029325305966770535,1739502650.078821,10.45999002456665,0.08167382561880875,1739502650.0788257,10.45999002456665,0.01633687098393416,1739502650.0788302,10.45999002456665,2.3418744866921877,1739502650.0788357,10.45999002456665,0.0,1739502650.0788403,10.45999002456665,0.1154124242219643,1739502650.0788457,10.45999002456665,0.016143952630407493,1739502650.0788512,10.45999002456665,2.2264620624702234 +1739502650.0994198,10.479990005493164,19.63515378414241,1739502650.0994287,10.479990005493164,-0.29468362078968724,1739502650.0994394,10.479990005493164,19.382224832344857,1739502650.0994496,10.479990005493164,25.82883295570972,1739502650.0994549,10.479990005493164,-0.113,1739502650.0994613,10.479990005493164,0.029325305966770535,1739502650.0994666,10.479990005493164,0.08167382561880875,1739502650.0994716,10.479990005493164,0.01633687098393416,1739502650.0994763,10.479990005493164,2.3418744866921877,1739502650.099482,10.479990005493164,0.0,1739502650.0994873,10.479990005493164,0.1154124242219643,1739502650.0994923,10.479990005493164,0.016143952630407493,1739502650.0994978,10.479990005493164,2.2264620624702234 +1739502650.1228666,10.499989986419678,19.63515378414241,1739502650.1228738,10.499989986419678,-0.29468362078968724,1739502650.1228817,10.499989986419678,19.382224832344857,1739502650.1228888,10.499989986419678,25.82883295570972,1739502650.1228921,10.499989986419678,-0.113,1739502650.1228964,10.499989986419678,0.029325305966770535,1739502650.1229,10.499989986419678,0.08167382561880875,1739502650.1229033,10.499989986419678,0.01633687098393416,1739502650.1229067,10.499989986419678,2.3418744866921877,1739502650.1229107,10.499989986419678,0.0,1739502650.122914,10.499989986419678,0.1154124242219643,1739502650.1229181,10.499989986419678,0.016143952630407493,1739502650.122922,10.499989986419678,2.2264620624702234 +1739502650.1462939,10.519989967346191,19.880658231328745,1739502650.146299,10.519989967346191,-0.29062603297262424,1739502650.1463048,10.519989967346191,19.411439861560034,1739502650.1463103,10.519989967346191,25.883261570945447,1739502650.146313,10.519989967346191,-0.113,1739502650.1463163,10.519989967346191,0.029582866577266817,1739502650.1463192,10.519989967346191,0.07565894646976323,1739502650.1463218,10.519989967346191,0.016112313974982487,1739502650.1463242,10.519989967346191,2.353170516212839,1739502650.1463275,10.519989967346191,0.0,1739502650.14633,10.519989967346191,0.11350585857794684,1739502650.146333,10.519989967346191,0.01698369266426863,1739502650.1463358,10.519989967346191,2.2390688554804985 +1739502650.1659904,10.549989938735962,19.880658231328745,1739502650.1659944,10.549989938735962,-0.29062603297262424,1739502650.1659994,10.549989938735962,19.411439861560034,1739502650.166004,10.549989938735962,25.883261570945447,1739502650.166006,10.549989938735962,-0.113,1739502650.166009,10.549989938735962,0.029582866577266817,1739502650.1660109,10.549989938735962,0.07565894646976323,1739502650.1660132,10.549989938735962,0.016112313974982487,1739502650.1660151,10.549989938735962,2.353170516212839,1739502650.1660178,10.549989938735962,0.0,1739502650.16602,10.549989938735962,0.11410166073234063,1739502650.166022,10.549989938735962,0.01698369266426863,1739502650.1660244,10.549989938735962,2.2390688554804985 +1739502650.1855135,10.569989919662476,19.880658231328745,1739502650.1855178,10.569989919662476,-0.29062603297262424,1739502650.1855235,10.569989919662476,19.411439861560034,1739502650.18553,10.569989919662476,25.883261570945447,1739502650.1855333,10.569989919662476,-0.113,1739502650.1855378,10.569989919662476,0.029582866577266817,1739502650.1855416,10.569989919662476,0.07565894646976323,1739502650.1855457,10.569989919662476,0.016112313974982487,1739502650.1855497,10.569989919662476,2.353170516212839,1739502650.185554,10.569989919662476,0.0,1739502650.1855578,10.569989919662476,0.11410166073234063,1739502650.185562,10.569989919662476,0.01698369266426863,1739502650.1855662,10.569989919662476,2.2390688554804985 +1739502650.2051442,10.58998990058899,19.880658231328745,1739502650.205147,10.58998990058899,-0.29062603297262424,1739502650.2051513,10.58998990058899,19.411439861560034,1739502650.205155,10.58998990058899,25.883261570945447,1739502650.2051566,10.58998990058899,-0.113,1739502650.2051587,10.58998990058899,0.029582866577266817,1739502650.2051601,10.58998990058899,0.07565894646976323,1739502650.205162,10.58998990058899,0.016112313974982487,1739502650.2051635,10.58998990058899,2.353170516212839,1739502650.205166,10.58998990058899,0.0,1739502650.2051675,10.58998990058899,0.11410166073234063,1739502650.2051694,10.58998990058899,0.01698369266426863,1739502650.205171,10.58998990058899,2.2390688554804985 +1739502650.224493,10.609989881515503,19.880658231328745,1739502650.2244961,10.609989881515503,-0.29062603297262424,1739502650.2244997,10.609989881515503,19.411439861560034,1739502650.2245033,10.609989881515503,25.883261570945447,1739502650.224505,10.609989881515503,-0.113,1739502650.2245069,10.609989881515503,0.029582866577266817,1739502650.2245088,10.609989881515503,0.07565894646976323,1739502650.2245104,10.609989881515503,0.016112313974982487,1739502650.2245119,10.609989881515503,2.353170516212839,1739502650.2245138,10.609989881515503,0.0,1739502650.2245154,10.609989881515503,0.11410166073234063,1739502650.2245169,10.609989881515503,0.01698369266426863,1739502650.2245185,10.609989881515503,2.2390688554804985 +1739502650.2452815,10.629989862442017,20.127542741543518,1739502650.2452846,10.629989862442017,-0.2863382601996527,1739502650.2452884,10.629989862442017,19.44081911827559,1739502650.245292,10.629989862442017,25.937589025491313,1739502650.2452936,10.629989862442017,-0.113,1739502650.2452958,10.629989862442017,0.029825383619450075,1739502650.2452974,10.629989862442017,0.06976124213181809,1739502650.245299,10.629989862442017,0.01585717469055172,1739502650.2453005,10.629989862442017,2.36429939266608,1739502650.2453024,10.629989862442017,0.0,1739502650.245304,10.629989862442017,0.11214497293187184,1739502650.2453055,10.629989862442017,0.01782343269812977,1739502650.2453074,10.629989862442017,2.2515429543956538 +1739502650.2645304,10.64998984336853,20.127542741543518,1739502650.264534,10.64998984336853,-0.2863382601996527,1739502650.2645376,10.64998984336853,19.44081911827559,1739502650.264541,10.64998984336853,25.937589025491313,1739502650.2645428,10.64998984336853,-0.113,1739502650.2645447,10.64998984336853,0.029825383619450075,1739502650.2645464,10.64998984336853,0.06976124213181809,1739502650.264548,10.64998984336853,0.01585717469055172,1739502650.2645497,10.64998984336853,2.36429939266608,1739502650.2645514,10.64998984336853,0.0,1739502650.2645533,10.64998984336853,0.11275643827042625,1739502650.264555,10.64998984336853,0.01782343269812977,1739502650.2645566,10.64998984336853,2.2515429543956538 +1739502650.284646,10.669989824295044,20.127542741543518,1739502650.2846491,10.669989824295044,-0.2863382601996527,1739502650.2846527,10.669989824295044,19.44081911827559,1739502650.284656,10.669989824295044,25.937589025491313,1739502650.2846577,10.669989824295044,-0.113,1739502650.2846596,10.669989824295044,0.029825383619450075,1739502650.2846615,10.669989824295044,0.06976124213181809,1739502650.284663,10.669989824295044,0.01585717469055172,1739502650.2846646,10.669989824295044,2.36429939266608,1739502650.2846663,10.669989824295044,0.0,1739502650.284668,10.669989824295044,0.11275643827042625,1739502650.2846696,10.669989824295044,0.01782343269812977,1739502650.284683,10.669989824295044,2.2515429543956538 +1739502650.3062046,10.689989805221558,20.127542741543518,1739502650.3062074,10.689989805221558,-0.2863382601996527,1739502650.3062108,10.689989805221558,19.44081911827559,1739502650.306214,10.689989805221558,25.937589025491313,1739502650.306216,10.689989805221558,-0.113,1739502650.3062177,10.689989805221558,0.029825383619450075,1739502650.3062196,10.689989805221558,0.06976124213181809,1739502650.306221,10.689989805221558,0.01585717469055172,1739502650.3062227,10.689989805221558,2.36429939266608,1739502650.3062243,10.689989805221558,0.0,1739502650.306226,10.689989805221558,0.11275643827042625,1739502650.3062274,10.689989805221558,0.01782343269812977,1739502650.3062294,10.689989805221558,2.2515429543956538 +1739502650.326856,10.709989786148071,20.127542741543518,1739502650.3268602,10.709989786148071,-0.2863382601996527,1739502650.3268664,10.709989786148071,19.44081911827559,1739502650.3268728,10.709989786148071,25.937589025491313,1739502650.3268766,10.709989786148071,-0.113,1739502650.3268816,10.709989786148071,0.029825383619450075,1739502650.3268857,10.709989786148071,0.06976124213181809,1739502650.3268895,10.709989786148071,0.01585717469055172,1739502650.3268936,10.709989786148071,2.36429939266608,1739502650.3268976,10.709989786148071,0.0,1739502650.3269017,10.709989786148071,0.11275643827042625,1739502650.326906,10.709989786148071,0.01782343269812977,1739502650.32691,10.709989786148071,2.2515429543956538 +1739502650.3457959,10.729989767074585,20.127542741543518,1739502650.3457994,10.729989767074585,-0.2863382601996527,1739502650.3458037,10.729989767074585,19.44081911827559,1739502650.345807,10.729989767074585,25.937589025491313,1739502650.345809,10.729989767074585,-0.113,1739502650.345811,10.729989767074585,0.029825383619450075,1739502650.3458128,10.729989767074585,0.06976124213181809,1739502650.3458145,10.729989767074585,0.01585717469055172,1739502650.3458161,10.729989767074585,2.36429939266608,1739502650.3458185,10.729989767074585,0.0,1739502650.3458207,10.729989767074585,0.11275643827042625,1739502650.3458228,10.729989767074585,0.01782343269812977,1739502650.3458247,10.729989767074585,2.2515429543956538 +1739502650.3669438,10.749989748001099,20.375788551839143,1739502650.3669462,10.749989748001099,-0.28181831870070884,1739502650.3669496,10.749989748001099,19.995454773791042,1739502650.366953,10.749989748001099,26.516877593199755,1739502650.3669546,10.749989748001099,-0.11032689960905201,1739502650.3669565,10.749989748001099,0.027917990008161316,1739502650.3669581,10.749989748001099,0.056856001375021635,1739502650.3669596,10.749989748001099,0.011569272540760008,1739502650.3669612,10.749989748001099,2.3888353138229794,1739502650.366963,10.749989748001099,0.0,1739502650.3669643,10.749989748001099,0.13050720335135102,1739502650.366966,10.749989748001099,0.018663172731990908,1739502650.3669674,10.749989748001099,2.263875228196391 +1739502650.3854697,10.769989728927612,20.375788551839143,1739502650.385474,10.769989728927612,-0.28181831870070884,1739502650.3854775,10.769989728927612,19.995454773791042,1739502650.3854809,10.769989728927612,26.516877593199755,1739502650.3854825,10.769989728927612,-0.11032689960905201,1739502650.3854845,10.769989728927612,0.027917990008161316,1739502650.3854861,10.769989728927612,0.056856001375021635,1739502650.3854878,10.769989728927612,0.011569272540760008,1739502650.3854895,10.769989728927612,2.3888353138229794,1739502650.3854914,10.769989728927612,0.0,1739502650.3854933,10.769989728927612,0.12496008562658822,1739502650.385495,10.769989728927612,0.018663172731990908,1739502650.385497,10.769989728927612,2.263875228196391 +1739502650.4054167,10.789989709854126,20.375788551839143,1739502650.405421,10.789989709854126,-0.28181831870070884,1739502650.4054263,10.789989709854126,19.995454773791042,1739502650.4054315,10.789989709854126,26.516877593199755,1739502650.4054346,10.789989709854126,-0.11032689960905201,1739502650.4054384,10.789989709854126,0.027917990008161316,1739502650.405442,10.789989709854126,0.056856001375021635,1739502650.4054456,10.789989709854126,0.011569272540760008,1739502650.4054492,10.789989709854126,2.3888353138229794,1739502650.4054527,10.789989709854126,0.0,1739502650.4054563,10.789989709854126,0.12496008562658822,1739502650.40546,10.789989709854126,0.018663172731990908,1739502650.4054637,10.789989709854126,2.263875228196391 +1739502650.4291272,10.80998969078064,20.375788551839143,1739502650.4291363,10.80998969078064,-0.28181831870070884,1739502650.4291441,10.80998969078064,19.995454773791042,1739502650.4291508,10.80998969078064,26.516877593199755,1739502650.4291546,10.80998969078064,-0.11032689960905201,1739502650.4291594,10.80998969078064,0.027917990008161316,1739502650.4291642,10.80998969078064,0.056856001375021635,1739502650.429168,10.80998969078064,0.011569272540760008,1739502650.4291735,10.80998969078064,2.3888353138229794,1739502650.4291768,10.80998969078064,0.0,1739502650.4291818,10.80998969078064,0.12496008562658822,1739502650.429185,10.80998969078064,0.018663172731990908,1739502650.4291902,10.80998969078064,2.263875228196391 +1739502650.4660597,10.829989671707153,20.375788551839143,1739502650.4660654,10.829989671707153,-0.28181831870070884,1739502650.466071,10.829989671707153,19.995454773791042,1739502650.4660769,10.829989671707153,26.516877593199755,1739502650.4660802,10.829989671707153,-0.11032689960905201,1739502650.466085,10.829989671707153,0.027917990008161316,1739502650.4660888,10.829989671707153,0.056856001375021635,1739502650.4660926,10.829989671707153,0.011569272540760008,1739502650.466096,10.829989671707153,2.3888353138229794,1739502650.4661002,10.829989671707153,0.0,1739502650.4661038,10.829989671707153,0.12496008562658822,1739502650.4661078,10.829989671707153,0.018663172731990908,1739502650.466112,10.829989671707153,2.263875228196391 +1739502650.4757292,10.859989643096924,20.625450928566682,1739502650.4757338,10.859989643096924,-0.2770628506720332,1739502650.4757395,10.859989643096924,20.02516459662162,1739502650.475745,10.859989643096924,26.573900845442335,1739502650.475748,10.859989643096924,-0.10983007442729809,1739502650.4757524,10.859989643096924,0.028106269766632663,1739502650.4757557,10.859989643096924,0.051196227124608036,1739502650.4757593,10.859989643096924,0.011103156311173224,1739502650.4757626,10.859989643096924,2.399676052634227,1739502650.4757662,10.859989643096924,0.0,1739502650.4757695,10.859989643096924,0.12086254136111625,1739502650.4757729,10.859989643096924,0.019502912765852046,1739502650.4757767,10.859989643096924,2.2775330278506005 +1739502650.5182474,10.899989604949951,20.625450928566682,1739502650.5182514,10.899989604949951,-0.2770628506720332,1739502650.518256,10.899989604949951,20.02516459662162,1739502650.5182607,10.899989604949951,26.573900845442335,1739502650.5182633,10.899989604949951,-0.10983007442729809,1739502650.5182664,10.899989604949951,0.028106269766632663,1739502650.5182686,10.899989604949951,0.051196227124608036,1739502650.5182712,10.899989604949951,0.011103156311173224,1739502650.5182736,10.899989604949951,2.399676052634227,1739502650.5182765,10.899989604949951,0.0,1739502650.5182786,10.899989604949951,0.1221430247836266,1739502650.518281,10.899989604949951,0.019502912765852046,1739502650.5182838,10.899989604949951,2.2775330278506005 +1739502650.5324616,10.909989595413208,20.625450928566682,1739502650.5324664,10.909989595413208,-0.2770628506720332,1739502650.5324717,10.909989595413208,20.02516459662162,1739502650.5324771,10.909989595413208,26.573900845442335,1739502650.5324805,10.909989595413208,-0.10983007442729809,1739502650.5324843,10.909989595413208,0.028106269766632663,1739502650.5324876,10.909989595413208,0.051196227124608036,1739502650.532491,10.909989595413208,0.011103156311173224,1739502650.5324945,10.909989595413208,2.399676052634227,1739502650.5324981,10.909989595413208,0.0,1739502650.5325015,10.909989595413208,0.1221430247836266,1739502650.5325055,10.909989595413208,0.019502912765852046,1739502650.5325093,10.909989595413208,2.2775330278506005 +1739502650.5526133,10.929989576339722,20.625450928566682,1739502650.5526178,10.929989576339722,-0.2770628506720332,1739502650.552623,10.929989576339722,20.02516459662162,1739502650.552629,10.929989576339722,26.573900845442335,1739502650.5526323,10.929989576339722,-0.10983007442729809,1739502650.5526364,10.929989576339722,0.028106269766632663,1739502650.55264,10.929989576339722,0.051196227124608036,1739502650.5526433,10.929989576339722,0.011103156311173224,1739502650.5526469,10.929989576339722,2.399676052634227,1739502650.5526505,10.929989576339722,0.0,1739502650.5526543,10.929989576339722,0.1221430247836266,1739502650.5526578,10.929989576339722,0.019502912765852046,1739502650.5526614,10.929989576339722,2.2775330278506005 +1739502650.5725684,10.949989557266235,20.625450928566682,1739502650.5725727,10.949989557266235,-0.2770628506720332,1739502650.572578,10.949989557266235,20.02516459662162,1739502650.572584,10.949989557266235,26.573900845442335,1739502650.5725873,10.949989557266235,-0.10983007442729809,1739502650.5725915,10.949989557266235,0.028106269766632663,1739502650.5725951,10.949989557266235,0.051196227124608036,1739502650.5725987,10.949989557266235,0.011103156311173224,1739502650.572602,10.949989557266235,2.399676052634227,1739502650.5726058,10.949989557266235,0.0,1739502650.5726094,10.949989557266235,0.1221430247836266,1739502650.572613,10.949989557266235,0.019502912765852046,1739502650.5726168,10.949989557266235,2.2775330278506005 +1739502650.5927565,10.969989538192749,20.87659743430749,1739502650.592763,10.969989538192749,-0.2720681396318998,1739502650.5927699,10.969989538192749,20.055051030804776,1739502650.5927763,10.969989538192749,26.630457034223646,1739502650.5927796,10.969989538192749,-0.1093702680144419,1739502650.592784,10.969989538192749,0.028268769497933225,1739502650.5927875,10.969989538192749,0.04562351333098947,1739502650.592791,10.969989538192749,0.010575052331152987,1739502650.5927944,10.969989538192749,2.4103981015104337,1739502650.5927985,10.969989538192749,0.0,1739502650.5928018,10.969989538192749,0.118341186598505,1739502650.5928056,10.969989538192749,0.020342652799713184,1739502650.5928094,10.969989538192749,2.2908688397001153 +1739502650.6122756,10.989989519119263,20.87659743430749,1739502650.6122808,10.989989519119263,-0.2720681396318998,1739502650.6122859,10.989989519119263,20.055051030804776,1739502650.6122916,10.989989519119263,26.630457034223646,1739502650.6122947,10.989989519119263,-0.1093702680144419,1739502650.6122997,10.989989519119263,0.028268769497933225,1739502650.6123033,10.989989519119263,0.04562351333098947,1739502650.6123068,10.989989519119263,0.010575052331152987,1739502650.6123102,10.989989519119263,2.4103981015104337,1739502650.6123142,10.989989519119263,0.0,1739502650.6123183,10.989989519119263,0.11952926181031831,1739502650.612322,10.989989519119263,0.020342652799713184,1739502650.6123254,10.989989519119263,2.2908688397001153 +1739502650.633454,11.009989500045776,20.87659743430749,1739502650.633459,11.009989500045776,-0.2720681396318998,1739502650.6334667,11.009989500045776,20.055051030804776,1739502650.6334722,11.009989500045776,26.630457034223646,1739502650.6334755,11.009989500045776,-0.1093702680144419,1739502650.6334798,11.009989500045776,0.028268769497933225,1739502650.633484,11.009989500045776,0.04562351333098947,1739502650.6334882,11.009989500045776,0.010575052331152987,1739502650.6334918,11.009989500045776,2.4103981015104337,1739502650.6334956,11.009989500045776,0.0,1739502650.6334991,11.009989500045776,0.11952926181031831,1739502650.6335034,11.009989500045776,0.020342652799713184,1739502650.6335082,11.009989500045776,2.2908688397001153 +1739502650.6524687,11.02998948097229,20.87659743430749,1739502650.6524727,11.02998948097229,-0.2720681396318998,1739502650.6524775,11.02998948097229,20.055051030804776,1739502650.6524832,11.02998948097229,26.630457034223646,1739502650.652486,11.02998948097229,-0.1093702680144419,1739502650.6524897,11.02998948097229,0.028268769497933225,1739502650.6524932,11.02998948097229,0.04562351333098947,1739502650.6524966,11.02998948097229,0.010575052331152987,1739502650.6524997,11.02998948097229,2.4103981015104337,1739502650.652503,11.02998948097229,0.0,1739502650.6525068,11.02998948097229,0.11952926181031831,1739502650.6525104,11.02998948097229,0.020342652799713184,1739502650.652514,11.02998948097229,2.2908688397001153 +1739502650.6735601,11.049989461898804,20.87659743430749,1739502650.6735637,11.049989461898804,-0.2720681396318998,1739502650.673568,11.049989461898804,20.055051030804776,1739502650.6735735,11.049989461898804,26.630457034223646,1739502650.673576,11.049989461898804,-0.1093702680144419,1739502650.6735797,11.049989461898804,0.028268769497933225,1739502650.6735833,11.049989461898804,0.04562351333098947,1739502650.6735864,11.049989461898804,0.010575052331152987,1739502650.6735897,11.049989461898804,2.4103981015104337,1739502650.6735933,11.049989461898804,0.0,1739502650.6735966,11.049989461898804,0.11952926181031831,1739502650.6736002,11.049989461898804,0.020342652799713184,1739502650.6736035,11.049989461898804,2.2908688397001153 +1739502650.6912222,11.069989442825317,21.1291935858373,1739502650.6912248,11.069989442825317,-0.26683239845520035,1739502650.6912277,11.069989442825317,20.20511974877661,1739502650.6912303,11.069989442825317,26.806657804513254,1739502650.6912313,11.069989442825317,-0.10693774142672151,1739502650.691233,11.069989442825317,0.028155598543519518,1739502650.6912344,11.069989442825317,0.039605502410531006,1739502650.6912355,11.069989442825317,0.009428924930683903,1739502650.6912365,11.069989442825317,2.422030722816374,1739502650.6912382,11.069989442825317,0.0,1739502650.6912394,11.069989442825317,0.11743120518288443,1739502650.6912408,11.069989442825317,0.021182392833574322,1739502650.691242,11.069989442825317,2.3039438745075436 +1739502650.7116797,11.089989423751831,21.1291935858373,1739502650.7116826,11.089989423751831,-0.26683239845520035,1739502650.711686,11.089989423751831,20.20511974877661,1739502650.7116885,11.089989423751831,26.806657804513254,1739502650.7116897,11.089989423751831,-0.10693774142672151,1739502650.7116916,11.089989423751831,0.028155598543519518,1739502650.7116928,11.089989423751831,0.039605502410531006,1739502650.711694,11.089989423751831,0.009428924930683903,1739502650.7116954,11.089989423751831,2.422030722816374,1739502650.7116969,11.089989423751831,0.0,1739502650.7116983,11.089989423751831,0.11808684830883065,1739502650.7116995,11.089989423751831,0.021182392833574322,1739502650.7117012,11.089989423751831,2.3039438745075436 +1739502650.730735,11.109989404678345,21.1291935858373,1739502650.7307374,11.109989404678345,-0.26683239845520035,1739502650.7307403,11.109989404678345,20.20511974877661,1739502650.7307427,11.109989404678345,26.806657804513254,1739502650.7307441,11.109989404678345,-0.10693774142672151,1739502650.7307458,11.109989404678345,0.028155598543519518,1739502650.7307472,11.109989404678345,0.039605502410531006,1739502650.7307484,11.109989404678345,0.009428924930683903,1739502650.7307496,11.109989404678345,2.422030722816374,1739502650.7307513,11.109989404678345,0.0,1739502650.7307525,11.109989404678345,0.11808684830883065,1739502650.7307541,11.109989404678345,0.021182392833574322,1739502650.7307553,11.109989404678345,2.3039438745075436 +1739502650.7508538,11.129989385604858,21.1291935858373,1739502650.7508562,11.129989385604858,-0.26683239845520035,1739502650.750859,11.129989385604858,20.20511974877661,1739502650.7508621,11.129989385604858,26.806657804513254,1739502650.7508633,11.129989385604858,-0.10693774142672151,1739502650.750865,11.129989385604858,0.028155598543519518,1739502650.7508664,11.129989385604858,0.039605502410531006,1739502650.7508676,11.129989385604858,0.009428924930683903,1739502650.750869,11.129989385604858,2.422030722816374,1739502650.7508705,11.129989385604858,0.0,1739502650.750872,11.129989385604858,0.11808684830883065,1739502650.7508733,11.129989385604858,0.021182392833574322,1739502650.7508745,11.129989385604858,2.3039438745075436 +1739502650.7708187,11.149989366531372,21.1291935858373,1739502650.7708216,11.149989366531372,-0.26683239845520035,1739502650.7708247,11.149989366531372,20.20511974877661,1739502650.7708275,11.149989366531372,26.806657804513254,1739502650.770829,11.149989366531372,-0.10693774142672151,1739502650.7708309,11.149989366531372,0.028155598543519518,1739502650.7708323,11.149989366531372,0.039605502410531006,1739502650.7708337,11.149989366531372,0.009428924930683903,1739502650.770835,11.149989366531372,2.422030722816374,1739502650.7708366,11.149989366531372,0.0,1739502650.7708378,11.149989366531372,0.11808684830883065,1739502650.7708392,11.149989366531372,0.021182392833574322,1739502650.770841,11.149989366531372,2.3039438745075436 +1739502650.7912114,11.169989347457886,21.1291935858373,1739502650.7912138,11.169989347457886,-0.26683239845520035,1739502650.791217,11.169989347457886,20.20511974877661,1739502650.79122,11.169989347457886,26.806657804513254,1739502650.7912219,11.169989347457886,-0.10693774142672151,1739502650.7912235,11.169989347457886,0.028155598543519518,1739502650.7912252,11.169989347457886,0.039605502410531006,1739502650.7912264,11.169989347457886,0.009428924930683903,1739502650.7912276,11.169989347457886,2.422030722816374,1739502650.7912292,11.169989347457886,0.0,1739502650.7912304,11.169989347457886,0.11808684830883065,1739502650.7912323,11.169989347457886,0.021182392833574322,1739502650.7912335,11.169989347457886,2.3039438745075436 +1739502650.810886,11.1899893283844,21.383214697320167,1739502650.8108888,11.1899893283844,-0.2613537157082444,1739502650.810892,11.1899893283844,20.539191170530167,1739502650.810895,11.1899893283844,27.166525003227324,1739502650.8108962,11.1899893283844,-0.10301334838708302,1739502650.8108978,11.1899893283844,0.027372008881869473,1739502650.8108993,11.1899893283844,0.03095143960119451,1739502650.8109007,11.1899893283844,0.0071017085684173635,1739502650.8109016,11.1899893283844,2.4388572274589406,1739502650.8109035,11.1899893283844,0.0,1739502650.8109047,11.1899893283844,0.12377735126613194,1739502650.8109062,11.1899893283844,0.02202213286743546,1739502650.8109074,11.1899893283844,2.3168581595328988 +1739502650.830833,11.209989309310913,21.383214697320167,1739502650.8308358,11.209989309310913,-0.2613537157082444,1739502650.8308387,11.209989309310913,20.539191170530167,1739502650.8308415,11.209989309310913,27.166525003227324,1739502650.830843,11.209989309310913,-0.10301334838708302,1739502650.8308444,11.209989309310913,0.027372008881869473,1739502650.8308456,11.209989309310913,0.03095143960119451,1739502650.8308473,11.209989309310913,0.0071017085684173635,1739502650.8308485,11.209989309310913,2.4388572274589406,1739502650.8308501,11.209989309310913,0.0,1739502650.8308513,11.209989309310913,0.12199906792604187,1739502650.8308525,11.209989309310913,0.02202213286743546,1739502650.8308547,11.209989309310913,2.3168581595328988 +1739502650.8522534,11.229989290237427,21.383214697320167,1739502650.852257,11.229989290237427,-0.2613537157082444,1739502650.8522618,11.229989290237427,20.539191170530167,1739502650.852267,11.229989290237427,27.166525003227324,1739502650.85227,11.229989290237427,-0.10301334838708302,1739502650.8522735,11.229989290237427,0.027372008881869473,1739502650.852277,11.229989290237427,0.03095143960119451,1739502650.8522804,11.229989290237427,0.0071017085684173635,1739502650.8522837,11.229989290237427,2.4388572274589406,1739502650.8522873,11.229989290237427,0.0,1739502650.8522906,11.229989290237427,0.12199906792604187,1739502650.852294,11.229989290237427,0.02202213286743546,1739502650.8522975,11.229989290237427,2.3168581595328988 +1739502650.8722546,11.24998927116394,21.383214697320167,1739502650.8722591,11.24998927116394,-0.2613537157082444,1739502650.872264,11.24998927116394,20.539191170530167,1739502650.8722696,11.24998927116394,27.166525003227324,1739502650.8722725,11.24998927116394,-0.10301334838708302,1739502650.8722763,11.24998927116394,0.027372008881869473,1739502650.8722801,11.24998927116394,0.03095143960119451,1739502650.8722835,11.24998927116394,0.0071017085684173635,1739502650.8722868,11.24998927116394,2.4388572274589406,1739502650.8722904,11.24998927116394,0.0,1739502650.8722937,11.24998927116394,0.12199906792604187,1739502650.8722973,11.24998927116394,0.02202213286743546,1739502650.8723009,11.24998927116394,2.3168581595328988 +1739502650.8924582,11.269989252090454,21.383214697320167,1739502650.892462,11.269989252090454,-0.2613537157082444,1739502650.8924673,11.269989252090454,20.539191170530167,1739502650.8924723,11.269989252090454,27.166525003227324,1739502650.8924751,11.269989252090454,-0.10301334838708302,1739502650.892479,11.269989252090454,0.027372008881869473,1739502650.8924823,11.269989252090454,0.03095143960119451,1739502650.8924856,11.269989252090454,0.0071017085684173635,1739502650.892489,11.269989252090454,2.4388572274589406,1739502650.8924923,11.269989252090454,0.0,1739502650.8924959,11.269989252090454,0.12199906792604187,1739502650.8924992,11.269989252090454,0.02202213286743546,1739502650.8925028,11.269989252090454,2.3168581595328988 +1739502650.9108293,11.289989233016968,21.638671898580018,1739502650.9108315,11.289989233016968,-0.25562943539525396,1739502650.910834,11.289989233016968,20.890148804871746,1739502650.910837,11.289989233016968,27.544137438443165,1739502650.9108384,11.289989233016968,-0.099,1739502650.9108398,11.289989233016968,0.026516575602032258,1739502650.9108417,11.289989233016968,0.021590262734296498,1739502650.910843,11.289989233016968,0.004751219604896879,1739502650.910844,11.289989233016968,2.457190248324032,1739502650.9108458,11.289989233016968,0.0,1739502650.9108467,11.289989233016968,0.1292622149657221,1739502650.9108481,11.289989233016968,0.022861872901296598,1739502650.9108498,11.289989233016968,2.3301977682963644 +1739502650.9308589,11.309989213943481,21.638671898580018,1739502650.9308615,11.309989213943481,-0.25562943539525396,1739502650.9308648,11.309989213943481,20.890148804871746,1739502650.9308677,11.309989213943481,27.544137438443165,1739502650.9308693,11.309989213943481,-0.099,1739502650.9308708,11.309989213943481,0.026516575602032258,1739502650.9308722,11.309989213943481,0.021590262734296498,1739502650.9308739,11.309989213943481,0.004751219604896879,1739502650.930875,11.309989213943481,2.457190248324032,1739502650.930877,11.309989213943481,0.0,1739502650.9308782,11.309989213943481,0.12699248002766783,1739502650.9308798,11.309989213943481,0.022861872901296598,1739502650.930881,11.309989213943481,2.3301977682963644 +1739502650.9516969,11.329989194869995,21.638671898580018,1739502650.9517012,11.329989194869995,-0.25562943539525396,1739502650.951706,11.329989194869995,20.890148804871746,1739502650.9517112,11.329989194869995,27.544137438443165,1739502650.951714,11.329989194869995,-0.099,1739502650.9517179,11.329989194869995,0.026516575602032258,1739502650.9517212,11.329989194869995,0.021590262734296498,1739502650.9517248,11.329989194869995,0.004751219604896879,1739502650.951728,11.329989194869995,2.457190248324032,1739502650.9517317,11.329989194869995,0.0,1739502650.951735,11.329989194869995,0.12699248002766783,1739502650.9517386,11.329989194869995,0.022861872901296598,1739502650.9517422,11.329989194869995,2.3301977682963644 +1739502650.9729111,11.349989175796509,21.638671898580018,1739502650.9729137,11.349989175796509,-0.25562943539525396,1739502650.9729168,11.349989175796509,20.890148804871746,1739502650.9729195,11.349989175796509,27.544137438443165,1739502650.972921,11.349989175796509,-0.099,1739502650.9729226,11.349989175796509,0.026516575602032258,1739502650.9729242,11.349989175796509,0.021590262734296498,1739502650.9729254,11.349989175796509,0.004751219604896879,1739502650.9729266,11.349989175796509,2.457190248324032,1739502650.9729285,11.349989175796509,0.0,1739502650.9729297,11.349989175796509,0.12699248002766783,1739502650.9729314,11.349989175796509,0.022861872901296598,1739502650.9729328,11.349989175796509,2.3301977682963644 +1739502650.9929175,11.369989156723022,21.638671898580018,1739502650.9929204,11.369989156723022,-0.25562943539525396,1739502650.9929235,11.369989156723022,20.890148804871746,1739502650.9929261,11.369989156723022,27.544137438443165,1739502650.9929278,11.369989156723022,-0.099,1739502650.9929292,11.369989156723022,0.026516575602032258,1739502650.9929307,11.369989156723022,0.021590262734296498,1739502650.992932,11.369989156723022,0.004751219604896879,1739502650.9929338,11.369989156723022,2.457190248324032,1739502650.9929354,11.369989156723022,0.0,1739502650.9929366,11.369989156723022,0.12699248002766783,1739502650.9929383,11.369989156723022,0.022861872901296598,1739502650.9929395,11.369989156723022,2.3301977682963644 +1739502651.012698,11.389989137649536,21.638671898580018,1739502651.012702,11.389989137649536,-0.25562943539525396,1739502651.0127082,11.389989137649536,20.890148804871746,1739502651.012714,11.389989137649536,27.544137438443165,1739502651.0127172,11.389989137649536,-0.099,1739502651.0127213,11.389989137649536,0.026516575602032258,1739502651.0127246,11.389989137649536,0.021590262734296498,1739502651.0127282,11.389989137649536,0.004751219604896879,1739502651.0127316,11.389989137649536,2.457190248324032,1739502651.0127351,11.389989137649536,0.0,1739502651.0127385,11.389989137649536,0.12699248002766783,1739502651.012742,11.389989137649536,0.022861872901296598,1739502651.0127454,11.389989137649536,2.3301977682963644 +1739502651.0319798,11.40998911857605,21.895624948068637,1739502651.0319834,11.40998911857605,-0.2496557461988358,1739502651.0319877,11.40998911857605,21.134841222151692,1739502651.031992,11.40998911857605,27.816710146491594,1739502651.0319943,11.40998911857605,-0.09646812769932367,1739502651.0319974,11.40998911857605,0.02586577443987509,1739502651.032,11.40998911857605,0.01281846243184968,1739502651.0320022,11.40998911857605,0.002806104342610208,1739502651.0320046,11.40998911857605,2.474494077338036,1739502651.0320072,11.40998911857605,0.0,1739502651.0320098,11.40998911857605,0.13187541570401973,1739502651.032012,11.40998911857605,0.023701612935157736,1739502651.0320146,11.40998911857605,2.3441445800333462 +1739502651.0524242,11.429989099502563,21.895624948068637,1739502651.0524275,11.429989099502563,-0.2496557461988358,1739502651.0524318,11.429989099502563,21.134841222151692,1739502651.052436,11.429989099502563,27.816710146491594,1739502651.0524385,11.429989099502563,-0.09646812769932367,1739502651.0524414,11.429989099502563,0.02586577443987509,1739502651.052444,11.429989099502563,0.01281846243184968,1739502651.0524466,11.429989099502563,0.002806104342610208,1739502651.052449,11.429989099502563,2.474494077338036,1739502651.0524516,11.429989099502563,0.0,1739502651.0524542,11.429989099502563,0.1303494973046897,1739502651.0524566,11.429989099502563,0.023701612935157736,1739502651.0524592,11.429989099502563,2.3441445800333462 +1739502651.0731058,11.449989080429077,21.895624948068637,1739502651.0731103,11.449989080429077,-0.2496557461988358,1739502651.0731163,11.449989080429077,21.134841222151692,1739502651.0731218,11.449989080429077,27.816710146491594,1739502651.0731256,11.449989080429077,-0.09646812769932367,1739502651.0731297,11.449989080429077,0.02586577443987509,1739502651.0731335,11.449989080429077,0.01281846243184968,1739502651.0731366,11.449989080429077,0.002806104342610208,1739502651.0731394,11.449989080429077,2.474494077338036,1739502651.073144,11.449989080429077,0.0,1739502651.073148,11.449989080429077,0.1303494973046897,1739502651.0731506,11.449989080429077,0.023701612935157736,1739502651.0731542,11.449989080429077,2.3441445800333462 +1739502651.0927248,11.46998906135559,21.895624948068637,1739502651.0927289,11.46998906135559,-0.2496557461988358,1739502651.0927346,11.46998906135559,21.134841222151692,1739502651.0927408,11.46998906135559,27.816710146491594,1739502651.092744,11.46998906135559,-0.09646812769932367,1739502651.092748,11.46998906135559,0.02586577443987509,1739502651.0927527,11.46998906135559,0.01281846243184968,1739502651.0927558,11.46998906135559,0.002806104342610208,1739502651.09276,11.46998906135559,2.474494077338036,1739502651.092764,11.46998906135559,0.0,1739502651.0927675,11.46998906135559,0.1303494973046897,1739502651.0927715,11.46998906135559,0.023701612935157736,1739502651.0927749,11.46998906135559,2.3441445800333462 +1739502651.1116788,11.489989042282104,21.895624948068637,1739502651.1116812,11.489989042282104,-0.2496557461988358,1739502651.111684,11.489989042282104,21.134841222151692,1739502651.1116867,11.489989042282104,27.816710146491594,1739502651.111688,11.489989042282104,-0.09646812769932367,1739502651.1116896,11.489989042282104,0.02586577443987509,1739502651.111691,11.489989042282104,0.01281846243184968,1739502651.1116922,11.489989042282104,0.002806104342610208,1739502651.1116936,11.489989042282104,2.474494077338036,1739502651.111695,11.489989042282104,0.0,1739502651.1116965,11.489989042282104,0.1303494973046897,1739502651.1116977,11.489989042282104,0.023701612935157736,1739502651.111699,11.489989042282104,2.3441445800333462 +1739502651.1310074,11.509989023208618,22.15411859962384,1739502651.13101,11.509989023208618,-0.24342904974543256,1739502651.1310132,11.509989023208618,21.411668548118183,1739502651.131016,11.509989023208618,28.12202224804098,1739502651.1310172,11.509989023208618,-0.09306099746896958,1739502651.1310186,11.509989023208618,0.025190796152971456,1739502651.1310203,11.509989023208618,0.003877044149438408,1739502651.1310215,11.509989023208618,0.0008354928305452005,1739502651.131023,11.509989023208618,2.492257924455256,1739502651.1310246,11.509989023208618,0.0,1739502651.131026,11.509989023208618,0.1354565008374714,1739502651.1310275,11.509989023208618,0.024541352969018874,1739502651.131029,11.509989023208618,2.3583973632681583 +1739502651.151003,11.529989004135132,22.15411859962384,1739502651.1510053,11.529989004135132,-0.24342904974543256,1739502651.151008,11.529989004135132,21.411668548118183,1739502651.1510108,11.529989004135132,28.12202224804098,1739502651.1510122,11.529989004135132,-0.09306099746896958,1739502651.1510136,11.529989004135132,0.025190796152971456,1739502651.1510153,11.529989004135132,0.003877044149438408,1739502651.1510165,11.529989004135132,0.0008354928305452005,1739502651.1510177,11.529989004135132,2.492257924455256,1739502651.1510193,11.529989004135132,0.0,1739502651.1510205,11.529989004135132,0.13386056118709755,1739502651.1510217,11.529989004135132,0.024541352969018874,1739502651.1510231,11.529989004135132,2.3583973632681583 +1739502651.170843,11.549988985061646,22.15411859962384,1739502651.1708455,11.549988985061646,-0.24342904974543256,1739502651.170849,11.549988985061646,21.411668548118183,1739502651.170852,11.549988985061646,28.12202224804098,1739502651.1708536,11.549988985061646,-0.09306099746896958,1739502651.1708553,11.549988985061646,0.025190796152971456,1739502651.1708567,11.549988985061646,0.003877044149438408,1739502651.170858,11.549988985061646,0.0008354928305452005,1739502651.1708596,11.549988985061646,2.492257924455256,1739502651.170861,11.549988985061646,0.0,1739502651.1708624,11.549988985061646,0.13386056118709755,1739502651.1708639,11.549988985061646,0.024541352969018874,1739502651.1708653,11.549988985061646,2.3583973632681583 +1739502651.1924162,11.56998896598816,22.15411859962384,1739502651.19242,11.56998896598816,-0.24342904974543256,1739502651.1924248,11.56998896598816,21.411668548118183,1739502651.1924298,11.56998896598816,28.12202224804098,1739502651.1924326,11.56998896598816,-0.09306099746896958,1739502651.1924365,11.56998896598816,0.025190796152971456,1739502651.1924398,11.56998896598816,0.003877044149438408,1739502651.1924431,11.56998896598816,0.0008354928305452005,1739502651.1924465,11.56998896598816,2.492257924455256,1739502651.19245,11.56998896598816,0.0,1739502651.1924531,11.56998896598816,0.13386056118709755,1739502651.1924567,11.56998896598816,0.024541352969018874,1739502651.1924603,11.56998896598816,2.3583973632681583 +1739502651.2109153,11.589988946914673,22.15411859962384,1739502651.210918,11.589988946914673,-0.24342904974543256,1739502651.2109208,11.589988946914673,21.411668548118183,1739502651.2109232,11.589988946914673,28.12202224804098,1739502651.2109246,11.589988946914673,-0.09306099746896958,1739502651.2109263,11.589988946914673,0.025190796152971456,1739502651.2109277,11.589988946914673,0.003877044149438408,1739502651.210929,11.589988946914673,0.0008354928305452005,1739502651.21093,11.589988946914673,2.492257924455256,1739502651.2109318,11.589988946914673,0.0,1739502651.210933,11.589988946914673,0.13386056118709755,1739502651.2109342,11.589988946914673,0.024541352969018874,1739502651.2109356,11.589988946914673,2.3583973632681583 +1739502651.2321844,11.609988927841187,22.15411859962384,1739502651.2321877,11.609988927841187,-0.24342904974543256,1739502651.232192,11.609988927841187,21.411668548118183,1739502651.232197,11.609988927841187,28.12202224804098,1739502651.2322,11.609988927841187,-0.09306099746896958,1739502651.2322037,11.609988927841187,0.025190796152971456,1739502651.232207,11.609988927841187,0.003877044149438408,1739502651.2322102,11.609988927841187,0.0008354928305452005,1739502651.2322135,11.609988927841187,2.492257924455256,1739502651.2322168,11.609988927841187,0.0,1739502651.2322202,11.609988927841187,0.13386056118709755,1739502651.2322237,11.609988927841187,0.024541352969018874,1739502651.232227,11.609988927841187,2.3583973632681583 +1739502651.25234,11.6299889087677,22.414198612209045,1739502651.252344,11.6299889087677,-0.23694560724358915,1739502651.252349,11.6299889087677,21.82405926401551,1739502651.252354,11.6299889087677,28.563757224174793,1739502651.2523568,11.6299889087677,-0.08864425020996103,1739502651.2523608,11.6299889087677,0.024111099216442864,1739502651.2523637,11.6299889087677,-0.007812169800446219,1739502651.252367,11.6299889087677,-0.0015855957172596523,1739502651.2523704,11.6299889087677,2.4844243828430583,1739502651.2523737,11.6299889087677,0.0,1739502651.2523773,11.6299889087677,0.10110647180466138,1739502651.2523806,11.6299889087677,0.025381093002880013,1739502651.2523842,11.6299889087677,2.373082251395364 +1739502651.2707767,11.649988889694214,22.414198612209045,1739502651.270779,11.649988889694214,-0.23694560724358915,1739502651.2707818,11.649988889694214,21.82405926401551,1739502651.2707841,11.649988889694214,28.563757224174793,1739502651.2707858,11.649988889694214,-0.08864425020996103,1739502651.2707872,11.649988889694214,0.024111099216442864,1739502651.2707887,11.649988889694214,-0.007812169800446219,1739502651.27079,11.649988889694214,-0.0015855957172596523,1739502651.2707915,11.649988889694214,2.4844243828430583,1739502651.270793,11.649988889694214,0.0,1739502651.2707942,11.649988889694214,0.11134213144769411,1739502651.2707956,11.649988889694214,0.025381093002880013,1739502651.270797,11.649988889694214,2.373082251395364 +1739502651.2919126,11.669988870620728,22.414198612209045,1739502651.291916,11.669988870620728,-0.23694560724358915,1739502651.2919204,11.669988870620728,21.82405926401551,1739502651.2919252,11.669988870620728,28.563757224174793,1739502651.291928,11.669988870620728,-0.08864425020996103,1739502651.2919316,11.669988870620728,0.024111099216442864,1739502651.291935,11.669988870620728,-0.007812169800446219,1739502651.291938,11.669988870620728,-0.0015855957172596523,1739502651.2919414,11.669988870620728,2.4844243828430583,1739502651.291945,11.669988870620728,0.0,1739502651.291948,11.669988870620728,0.11134213144769411,1739502651.2919514,11.669988870620728,0.025381093002880013,1739502651.2919548,11.669988870620728,2.373082251395364 +1739502651.3107903,11.689988851547241,22.414198612209045,1739502651.3107927,11.689988851547241,-0.23694560724358915,1739502651.3107955,11.689988851547241,21.82405926401551,1739502651.3107984,11.689988851547241,28.563757224174793,1739502651.3108,11.689988851547241,-0.08864425020996103,1739502651.3108017,11.689988851547241,0.024111099216442864,1739502651.310803,11.689988851547241,-0.007812169800446219,1739502651.3108041,11.689988851547241,-0.0015855957172596523,1739502651.3108056,11.689988851547241,2.4844243828430583,1739502651.310807,11.689988851547241,0.0,1739502651.3108084,11.689988851547241,0.11134213144769411,1739502651.3108096,11.689988851547241,0.025381093002880013,1739502651.3108108,11.689988851547241,2.373082251395364 +1739502651.3307664,11.709988832473755,22.414198612209045,1739502651.3307683,11.709988832473755,-0.23694560724358915,1739502651.3307712,11.709988832473755,21.82405926401551,1739502651.3307738,11.709988832473755,28.563757224174793,1739502651.3307753,11.709988832473755,-0.08864425020996103,1739502651.3307772,11.709988832473755,0.024111099216442864,1739502651.3307784,11.709988832473755,-0.007812169800446219,1739502651.3307796,11.709988832473755,-0.0015855957172596523,1739502651.3307807,11.709988832473755,2.4844243828430583,1739502651.3307822,11.709988832473755,0.0,1739502651.3307836,11.709988832473755,0.11134213144769411,1739502651.3307848,11.709988832473755,0.025381093002880013,1739502651.330786,11.709988832473755,2.373082251395364 +1739502651.3521314,11.729988813400269,22.675765076082964,1739502651.3521347,11.729988813400269,-0.23020534102783063,1739502651.352139,11.729988813400269,21.849692777475155,1739502651.3521442,11.729988813400269,28.613776887001112,1739502651.3521469,11.729988813400269,-0.08823758628454381,1739502651.3521507,11.729988813400269,0.023903743985297758,1739502651.352154,11.729988813400269,-0.013762821617782865,1739502651.3521574,11.729988813400269,-0.002995975570183642,1739502651.3521607,11.729988813400269,2.47262533436278,1739502651.3521643,11.729988813400269,0.0,1739502651.352168,11.729988813400269,0.0764432851158919,1739502651.3521721,11.729988813400269,0.02622083303674115,1739502651.3521762,11.729988813400269,2.385276152617737 +1739502651.3707635,11.749988794326782,22.675765076082964,1739502651.370766,11.749988794326782,-0.23020534102783063,1739502651.3707683,11.749988794326782,21.849692777475155,1739502651.3707712,11.749988794326782,28.613776887001112,1739502651.3707724,11.749988794326782,-0.08823758628454381,1739502651.370774,11.749988794326782,0.023903743985297758,1739502651.3707755,11.749988794326782,-0.013762821617782865,1739502651.370777,11.749988794326782,-0.002995975570183642,1739502651.370778,11.749988794326782,2.47262533436278,1739502651.3707798,11.749988794326782,0.0,1739502651.370781,11.749988794326782,0.08734918174504314,1739502651.3707821,11.749988794326782,0.02622083303674115,1739502651.3707838,11.749988794326782,2.385276152617737 +1739502651.3923016,11.769988775253296,22.675765076082964,1739502651.392305,11.769988775253296,-0.23020534102783063,1739502651.3923097,11.769988775253296,21.849692777475155,1739502651.392315,11.769988775253296,28.613776887001112,1739502651.3923178,11.769988775253296,-0.08823758628454381,1739502651.3923218,11.769988775253296,0.023903743985297758,1739502651.3923252,11.769988775253296,-0.013762821617782865,1739502651.3923285,11.769988775253296,-0.002995975570183642,1739502651.3923318,11.769988775253296,2.47262533436278,1739502651.3923354,11.769988775253296,0.0,1739502651.392339,11.769988775253296,0.08734918174504314,1739502651.3923423,11.769988775253296,0.02622083303674115,1739502651.3923461,11.769988775253296,2.385276152617737 +1739502651.4109635,11.78998875617981,22.675765076082964,1739502651.4109666,11.78998875617981,-0.23020534102783063,1739502651.41097,11.78998875617981,21.849692777475155,1739502651.4109726,11.78998875617981,28.613776887001112,1739502651.410974,11.78998875617981,-0.08823758628454381,1739502651.4109757,11.78998875617981,0.023903743985297758,1739502651.4109774,11.78998875617981,-0.013762821617782865,1739502651.4109788,11.78998875617981,-0.002995975570183642,1739502651.4109797,11.78998875617981,2.47262533436278,1739502651.4109814,11.78998875617981,0.0,1739502651.4109828,11.78998875617981,0.08734918174504314,1739502651.4109845,11.78998875617981,0.02622083303674115,1739502651.4109857,11.78998875617981,2.385276152617737 +1739502651.4309435,11.809988737106323,22.675765076082964,1739502651.4309468,11.809988737106323,-0.23020534102783063,1739502651.4309504,11.809988737106323,21.849692777475155,1739502651.4309533,11.809988737106323,28.613776887001112,1739502651.4309547,11.809988737106323,-0.08823758628454381,1739502651.4309566,11.809988737106323,0.023903743985297758,1739502651.430958,11.809988737106323,-0.013762821617782865,1739502651.4309595,11.809988737106323,-0.002995975570183642,1739502651.430961,11.809988737106323,2.47262533436278,1739502651.430963,11.809988737106323,0.0,1739502651.4309642,11.809988737106323,0.08734918174504314,1739502651.4309654,11.809988737106323,0.02622083303674115,1739502651.430967,11.809988737106323,2.385276152617737 +1739502651.450977,11.829988718032837,22.675765076082964,1739502651.4509802,11.829988718032837,-0.23020534102783063,1739502651.4509835,11.829988718032837,21.849692777475155,1739502651.4509861,11.829988718032837,28.613776887001112,1739502651.450988,11.829988718032837,-0.08823758628454381,1739502651.4509897,11.829988718032837,0.023903743985297758,1739502651.4509914,11.829988718032837,-0.013762821617782865,1739502651.4509928,11.829988718032837,-0.002995975570183642,1739502651.4509945,11.829988718032837,2.47262533436278,1739502651.4509964,11.829988718032837,0.0,1739502651.450998,11.829988718032837,0.08734918174504314,1739502651.4509995,11.829988718032837,0.02622083303674115,1739502651.4510014,11.829988718032837,2.385276152617737 +1739502651.470941,11.84998869895935,22.938510823365796,1739502651.470944,11.84998869895935,-0.22321391737107632,1739502651.4709473,11.84998869895935,22.11907105591039,1739502651.4709504,11.84998869895935,28.901825189049955,1739502651.4709518,11.84998869895935,-0.08497876539680405,1739502651.4709532,11.84998869895935,0.023176775700999356,1739502651.4709547,11.84998869895935,-0.023166468228535166,1739502651.4709563,11.84998869895935,-0.005000482720860932,1739502651.4709575,11.84998869895935,2.45409377159194,1739502651.4709594,11.84998869895935,0.0,1739502651.470961,11.84998869895935,0.04680074570495025,1739502651.4709628,11.84998869895935,0.02706057307060229,1739502651.4709642,11.84998869895935,2.394621631316447 +1739502651.491166,11.869988679885864,22.938510823365796,1739502651.4911685,11.869988679885864,-0.22321391737107632,1739502651.4911714,11.869988679885864,22.11907105591039,1739502651.4911742,11.869988679885864,28.901825189049955,1739502651.4911754,11.869988679885864,-0.08497876539680405,1739502651.4911773,11.869988679885864,0.023176775700999356,1739502651.4911788,11.869988679885864,-0.023166468228535166,1739502651.4911802,11.869988679885864,-0.005000482720860932,1739502651.4911816,11.869988679885864,2.45409377159194,1739502651.491183,11.869988679885864,0.0,1739502651.4911845,11.869988679885864,0.05947214027549297,1739502651.4911857,11.869988679885864,0.02706057307060229,1739502651.491187,11.869988679885864,2.394621631316447 +1739502651.5110164,11.889988660812378,22.938510823365796,1739502651.511019,11.889988660812378,-0.22321391737107632,1739502651.511022,11.889988660812378,22.11907105591039,1739502651.511025,11.889988660812378,28.901825189049955,1739502651.5110261,11.889988660812378,-0.08497876539680405,1739502651.5110278,11.889988660812378,0.023176775700999356,1739502651.5110292,11.889988660812378,-0.023166468228535166,1739502651.5110304,11.889988660812378,-0.005000482720860932,1739502651.5110319,11.889988660812378,2.45409377159194,1739502651.5110333,11.889988660812378,0.0,1739502651.5110347,11.889988660812378,0.05947214027549297,1739502651.5110364,11.889988660812378,0.02706057307060229,1739502651.5110376,11.889988660812378,2.394621631316447 +1739502651.53117,11.909988641738892,22.938510823365796,1739502651.5311728,11.909988641738892,-0.22321391737107632,1739502651.531176,11.909988641738892,22.11907105591039,1739502651.5311792,11.909988641738892,28.901825189049955,1739502651.5311809,11.909988641738892,-0.08497876539680405,1739502651.5311825,11.909988641738892,0.023176775700999356,1739502651.531184,11.909988641738892,-0.023166468228535166,1739502651.5311854,11.909988641738892,-0.005000482720860932,1739502651.5311873,11.909988641738892,2.45409377159194,1739502651.531189,11.909988641738892,0.0,1739502651.5311902,11.909988641738892,0.05947214027549297,1739502651.5311918,11.909988641738892,0.02706057307060229,1739502651.5311935,11.909988641738892,2.394621631316447 +1739502651.5514576,11.929988622665405,22.938510823365796,1739502651.55146,11.929988622665405,-0.22321391737107632,1739502651.5514631,11.929988622665405,22.11907105591039,1739502651.5514662,11.929988622665405,28.901825189049955,1739502651.5514677,11.929988622665405,-0.08497876539680405,1739502651.5514696,11.929988622665405,0.023176775700999356,1739502651.551471,11.929988622665405,-0.023166468228535166,1739502651.5514727,11.929988622665405,-0.005000482720860932,1739502651.5514739,11.929988622665405,2.45409377159194,1739502651.5514758,11.929988622665405,0.0,1739502651.551477,11.929988622665405,0.05947214027549297,1739502651.5514786,11.929988622665405,0.02706057307060229,1739502651.55148,11.929988622665405,2.394621631316447 +1739502651.571066,11.949988603591919,23.20215141180437,1739502651.5710688,11.949988603591919,-0.21597715491761527,1739502651.571072,11.949988603591919,22.36636384828833,1739502651.571075,11.949988603591919,29.16216345747928,1739502651.5710766,11.949988603591919,-0.08345792032227176,1739502651.5710783,11.949988603591919,0.02223106289634112,1739502651.5710802,11.949988603591919,-0.03379696976097072,1739502651.5710816,11.949988603591919,-0.007303469088007369,1739502651.5710833,11.949988603591919,2.4333116684390266,1739502651.5710852,11.949988603591919,0.0,1739502651.571087,11.949988603591919,0.01975172944463971,1739502651.5710883,11.949988603591919,0.027900313104463427,1739502651.5710902,11.949988603591919,2.4011473024713865 +1739502651.5915797,11.969988584518433,23.20215141180437,1739502651.591583,11.969988584518433,-0.21597715491761527,1739502651.591587,11.969988584518433,22.36636384828833,1739502651.5915904,11.969988584518433,29.16216345747928,1739502651.5915916,11.969988584518433,-0.08345792032227176,1739502651.5915937,11.969988584518433,0.02223106289634112,1739502651.5915952,11.969988584518433,-0.03379696976097072,1739502651.5915968,11.969988584518433,-0.007303469088007369,1739502651.5915983,11.969988584518433,2.4333116684390266,1739502651.5916004,11.969988584518433,0.0,1739502651.5916018,11.969988584518433,0.03216436596764005,1739502651.5916035,11.969988584518433,0.027900313104463427,1739502651.591605,11.969988584518433,2.4011473024713865 +1739502651.610995,11.989988565444946,23.20215141180437,1739502651.6109986,11.989988565444946,-0.21597715491761527,1739502651.611002,11.989988565444946,22.36636384828833,1739502651.6110048,11.989988565444946,29.16216345747928,1739502651.6110065,11.989988565444946,-0.08345792032227176,1739502651.6110084,11.989988565444946,0.02223106289634112,1739502651.6110098,11.989988565444946,-0.03379696976097072,1739502651.6110113,11.989988565444946,-0.007303469088007369,1739502651.6110127,11.989988565444946,2.4333116684390266,1739502651.6110148,11.989988565444946,0.0,1739502651.6110165,11.989988565444946,0.03216436596764005,1739502651.611018,11.989988565444946,0.027900313104463427,1739502651.6110196,11.989988565444946,2.4011473024713865 +1739502651.6318567,12.00998854637146,23.20215141180437,1739502651.63186,12.00998854637146,-0.21597715491761527,1739502651.631864,12.00998854637146,22.36636384828833,1739502651.631868,12.00998854637146,29.16216345747928,1739502651.6318698,12.00998854637146,-0.08345792032227176,1739502651.631872,12.00998854637146,0.02223106289634112,1739502651.6318738,12.00998854637146,-0.03379696976097072,1739502651.6318755,12.00998854637146,-0.007303469088007369,1739502651.6318774,12.00998854637146,2.4333116684390266,1739502651.6318793,12.00998854637146,0.0,1739502651.631881,12.00998854637146,0.03216436596764005,1739502651.631883,12.00998854637146,0.027900313104463427,1739502651.6318848,12.00998854637146,2.4011473024713865 +1739502651.650931,12.029988527297974,23.20215141180437,1739502651.650933,12.029988527297974,-0.21597715491761527,1739502651.650936,12.029988527297974,22.36636384828833,1739502651.6509385,12.029988527297974,29.16216345747928,1739502651.65094,12.029988527297974,-0.08345792032227176,1739502651.6509416,12.029988527297974,0.02223106289634112,1739502651.650943,12.029988527297974,-0.03379696976097072,1739502651.6509445,12.029988527297974,-0.007303469088007369,1739502651.6509454,12.029988527297974,2.4333116684390266,1739502651.6509473,12.029988527297974,0.0,1739502651.6509485,12.029988527297974,0.03216436596764005,1739502651.6509502,12.029988527297974,0.027900313104463427,1739502651.6509514,12.029988527297974,2.4011473024713865 +1739502651.6708374,12.049988508224487,23.20215141180437,1739502651.6708405,12.049988508224487,-0.21597715491761527,1739502651.6708434,12.049988508224487,22.36636384828833,1739502651.6708462,12.049988508224487,29.16216345747928,1739502651.6708474,12.049988508224487,-0.08345792032227176,1739502651.6708493,12.049988508224487,0.02223106289634112,1739502651.6708508,12.049988508224487,-0.03379696976097072,1739502651.6708524,12.049988508224487,-0.007303469088007369,1739502651.6708536,12.049988508224487,2.4333116684390266,1739502651.6708555,12.049988508224487,0.0,1739502651.6708567,12.049988508224487,0.03216436596764005,1739502651.6708581,12.049988508224487,0.027900313104463427,1739502651.6708598,12.049988508224487,2.4011473024713865 +1739502651.691167,12.069988489151001,23.466324817989975,1739502651.6911695,12.069988489151001,-0.20850378090392585,1739502651.6911724,12.069988489151001,22.637801150215118,1739502651.6911752,12.069988489151001,29.440142754540528,1739502651.6911767,12.069988489151001,-0.08143214371216229,1739502651.6911783,12.069988489151001,0.021268220461435998,1739502651.6911795,12.069988489151001,-0.04464504967373992,1739502651.6911807,12.069988489151001,-0.009603568084252587,1739502651.6911821,12.069988489151001,2.412285629718621,1739502651.6911836,12.069988489151001,0.0,1739502651.691185,12.069988489151001,-0.0031823725389381,1739502651.6911864,12.069988489151001,0.028740053138324565,1739502651.6911876,12.069988489151001,2.4044221392320213 +1739502651.7111645,12.089988470077515,23.466324817989975,1739502651.7111676,12.089988470077515,-0.20850378090392585,1739502651.711171,12.089988470077515,22.637801150215118,1739502651.7111738,12.089988470077515,29.440142754540528,1739502651.7111752,12.089988470077515,-0.08143214371216229,1739502651.711177,12.089988470077515,0.021268220461435998,1739502651.7111793,12.089988470077515,-0.04464504967373992,1739502651.7111804,12.089988470077515,-0.009603568084252587,1739502651.711182,12.089988470077515,2.412285629718621,1739502651.7111838,12.089988470077515,0.0,1739502651.7111852,12.089988470077515,0.007863490486599733,1739502651.7111871,12.089988470077515,0.028740053138324565,1739502651.7111888,12.089988470077515,2.4044221392320213 +1739502651.7309096,12.109988451004028,23.466324817989975,1739502651.7309124,12.109988451004028,-0.20850378090392585,1739502651.7309158,12.109988451004028,22.637801150215118,1739502651.7309186,12.109988451004028,29.440142754540528,1739502651.7309198,12.109988451004028,-0.08143214371216229,1739502651.730922,12.109988451004028,0.021268220461435998,1739502651.7309232,12.109988451004028,-0.04464504967373992,1739502651.7309248,12.109988451004028,-0.009603568084252587,1739502651.730926,12.109988451004028,2.412285629718621,1739502651.7309277,12.109988451004028,0.0,1739502651.730929,12.109988451004028,0.007863490486599733,1739502651.7309303,12.109988451004028,0.028740053138324565,1739502651.730932,12.109988451004028,2.4044221392320213 +1739502651.7511704,12.129988431930542,23.466324817989975,1739502651.7511723,12.129988431930542,-0.20850378090392585,1739502651.7511752,12.129988431930542,22.637801150215118,1739502651.751178,12.129988431930542,29.440142754540528,1739502651.7511795,12.129988431930542,-0.08143214371216229,1739502651.7511811,12.129988431930542,0.021268220461435998,1739502651.7511826,12.129988431930542,-0.04464504967373992,1739502651.7511842,12.129988431930542,-0.009603568084252587,1739502651.7511854,12.129988431930542,2.412285629718621,1739502651.7511868,12.129988431930542,0.0,1739502651.7511883,12.129988431930542,0.007863490486599733,1739502651.7511897,12.129988431930542,0.028740053138324565,1739502651.7511911,12.129988431930542,2.4044221392320213 +1739502651.7708952,12.149988412857056,23.466324817989975,1739502651.7708976,12.149988412857056,-0.20850378090392585,1739502651.7709005,12.149988412857056,22.637801150215118,1739502651.7709033,12.149988412857056,29.440142754540528,1739502651.7709045,12.149988412857056,-0.08143214371216229,1739502651.7709064,12.149988412857056,0.021268220461435998,1739502651.7709076,12.149988412857056,-0.04464504967373992,1739502651.770909,12.149988412857056,-0.009603568084252587,1739502651.7709105,12.149988412857056,2.412285629718621,1739502651.7709122,12.149988412857056,0.0,1739502651.7709136,12.149988412857056,0.007863490486599733,1739502651.770915,12.149988412857056,0.028740053138324565,1739502651.7709165,12.149988412857056,2.4044221392320213 +1739502651.7922258,12.16998839378357,23.73074736810815,1739502651.7922294,12.16998839378357,-0.20080114935879134,1739502651.7922342,12.16998839378357,22.927932912064186,1739502651.7922397,12.16998839378357,29.732022567241053,1739502651.7922425,12.16998839378357,-0.07899147860632456,1739502651.7922463,12.16998839378357,0.02029451126909797,1739502651.79225,12.16998839378357,-0.05573420844304537,1739502651.7922535,12.16998839378357,-0.011879955622349277,1739502651.7922568,12.16998839378357,2.3909800989375047,1739502651.7922604,12.16998839378357,0.0,1739502651.792264,12.16998839378357,-0.024405113084563695,1739502651.7922673,12.16998839378357,0.029579793172185703,1739502651.792271,12.16998839378357,2.40530126679453 +1739502651.8108995,12.189988374710083,23.73074736810815,1739502651.8109024,12.189988374710083,-0.20080114935879134,1739502651.810905,12.189988374710083,22.927932912064186,1739502651.8109078,12.189988374710083,29.732022567241053,1739502651.8109093,12.189988374710083,-0.07899147860632456,1739502651.810911,12.189988374710083,0.02029451126909797,1739502651.8109124,12.189988374710083,-0.05573420844304537,1739502651.8109138,12.189988374710083,-0.011879955622349277,1739502651.810915,12.189988374710083,2.3909800989375047,1739502651.8109167,12.189988374710083,0.0,1739502651.8109179,12.189988374710083,-0.014321167857025419,1739502651.8109198,12.189988374710083,0.029579793172185703,1739502651.8109212,12.189988374710083,2.40530126679453 +1739502651.830837,12.209988355636597,23.73074736810815,1739502651.8308394,12.209988355636597,-0.20080114935879134,1739502651.830842,12.209988355636597,22.927932912064186,1739502651.8308449,12.209988355636597,29.732022567241053,1739502651.8308463,12.209988355636597,-0.07899147860632456,1739502651.8308477,12.209988355636597,0.02029451126909797,1739502651.830849,12.209988355636597,-0.05573420844304537,1739502651.8308506,12.209988355636597,-0.011879955622349277,1739502651.8308516,12.209988355636597,2.3909800989375047,1739502651.8308532,12.209988355636597,0.0,1739502651.8308547,12.209988355636597,-0.014321167857025419,1739502651.830856,12.209988355636597,0.029579793172185703,1739502651.8308575,12.209988355636597,2.40530126679453 +1739502651.8509202,12.22998833656311,23.73074736810815,1739502651.8509226,12.22998833656311,-0.20080114935879134,1739502651.8509257,12.22998833656311,22.927932912064186,1739502651.850928,12.22998833656311,29.732022567241053,1739502651.8509297,12.22998833656311,-0.07899147860632456,1739502651.8509316,12.22998833656311,0.02029451126909797,1739502651.850933,12.22998833656311,-0.05573420844304537,1739502651.8509345,12.22998833656311,-0.011879955622349277,1739502651.8509357,12.22998833656311,2.3909800989375047,1739502651.8509376,12.22998833656311,0.0,1739502651.850939,12.22998833656311,-0.014321167857025419,1739502651.850941,12.22998833656311,0.029579793172185703,1739502651.8509424,12.22998833656311,2.40530126679453 +1739502651.8708146,12.249988317489624,23.73074736810815,1739502651.8708165,12.249988317489624,-0.20080114935879134,1739502651.8708196,12.249988317489624,22.927932912064186,1739502651.8708224,12.249988317489624,29.732022567241053,1739502651.8708236,12.249988317489624,-0.07899147860632456,1739502651.8708253,12.249988317489624,0.02029451126909797,1739502651.8708267,12.249988317489624,-0.05573420844304537,1739502651.870828,12.249988317489624,-0.011879955622349277,1739502651.8708293,12.249988317489624,2.3909800989375047,1739502651.8708313,12.249988317489624,0.0,1739502651.8708327,12.249988317489624,-0.014321167857025419,1739502651.870834,12.249988317489624,0.029579793172185703,1739502651.8708355,12.249988317489624,2.40530126679453 +1739502651.8910573,12.269988298416138,23.73074736810815,1739502651.8910623,12.269988298416138,-0.20080114935879134,1739502651.8910663,12.269988298416138,22.927932912064186,1739502651.8910694,12.269988298416138,29.732022567241053,1739502651.8910718,12.269988298416138,-0.07899147860632456,1739502651.8910744,12.269988298416138,0.02029451126909797,1739502651.8910763,12.269988298416138,-0.05573420844304537,1739502651.8910787,12.269988298416138,-0.011879955622349277,1739502651.8910806,12.269988298416138,2.3909800989375047,1739502651.8910828,12.269988298416138,0.0,1739502651.8910842,12.269988298416138,-0.014321167857025419,1739502651.891087,12.269988298416138,0.029579793172185703,1739502651.8910887,12.269988298416138,2.40530126679453 +1739502651.9109921,12.289988279342651,23.995114181233742,1739502651.9109948,12.289988279342651,-0.1928779669273437,1739502651.910998,12.289988279342651,23.219885541265203,1739502651.9110012,12.289988279342651,30.020431700412974,1739502651.9110024,12.289988279342651,-0.07687181448405152,1739502651.9110043,12.289988279342651,0.019250740138009405,1739502651.9110057,12.289988279342651,-0.06730659667815676,1739502651.9110072,12.289988279342651,-0.014232944670858852,1739502651.9110086,12.289988279342651,2.3689467676400353,1739502651.9110103,12.289988279342651,0.0,1739502651.9110117,12.289988279342651,-0.043798848466585105,1739502651.9110131,12.289988279342651,0.03041953320604684,1739502651.9110148,12.289988279342651,2.4035338348764186 +1739502651.93145,12.309988260269165,23.995114181233742,1739502651.9314535,12.309988260269165,-0.1928779669273437,1739502651.931458,12.309988260269165,23.219885541265203,1739502651.9314618,12.309988260269165,30.020431700412974,1739502651.9314637,12.309988260269165,-0.07687181448405152,1739502651.931466,12.309988260269165,0.019250740138009405,1739502651.9314678,12.309988260269165,-0.06730659667815676,1739502651.9314702,12.309988260269165,-0.014232944670858852,1739502651.9314718,12.309988260269165,2.3689467676400353,1739502651.931474,12.309988260269165,0.0,1739502651.9314756,12.309988260269165,-0.03458706723638327,1739502651.9314778,12.309988260269165,0.03041953320604684,1739502651.9314797,12.309988260269165,2.4035338348764186 +1739502651.9517484,12.329988241195679,23.995114181233742,1739502651.9517512,12.329988241195679,-0.1928779669273437,1739502651.951755,12.329988241195679,23.219885541265203,1739502651.9517586,12.329988241195679,30.020431700412974,1739502651.9517603,12.329988241195679,-0.07687181448405152,1739502651.9517624,12.329988241195679,0.019250740138009405,1739502651.951764,12.329988241195679,-0.06730659667815676,1739502651.9517663,12.329988241195679,-0.014232944670858852,1739502651.951768,12.329988241195679,2.3689467676400353,1739502651.95177,12.329988241195679,0.0,1739502651.9517717,12.329988241195679,-0.03458706723638327,1739502651.951774,12.329988241195679,0.03041953320604684,1739502651.9517758,12.329988241195679,2.4035338348764186 +1739502651.971372,12.349988222122192,23.995114181233742,1739502651.9713755,12.349988222122192,-0.1928779669273437,1739502651.97138,12.349988222122192,23.219885541265203,1739502651.971384,12.349988222122192,30.020431700412974,1739502651.9713862,12.349988222122192,-0.07687181448405152,1739502651.9713886,12.349988222122192,0.019250740138009405,1739502651.971391,12.349988222122192,-0.06730659667815676,1739502651.9713933,12.349988222122192,-0.014232944670858852,1739502651.971395,12.349988222122192,2.3689467676400353,1739502651.9713974,12.349988222122192,0.0,1739502651.9713993,12.349988222122192,-0.03458706723638327,1739502651.9714015,12.349988222122192,0.03041953320604684,1739502651.9714034,12.349988222122192,2.4035338348764186 +1739502651.991733,12.369988203048706,23.995114181233742,1739502651.9917357,12.369988203048706,-0.1928779669273437,1739502651.9917397,12.369988203048706,23.219885541265203,1739502651.9917436,12.369988203048706,30.020431700412974,1739502651.991745,12.369988203048706,-0.07687181448405152,1739502651.9917474,12.369988203048706,0.019250740138009405,1739502651.991749,12.369988203048706,-0.06730659667815676,1739502651.991751,12.369988203048706,-0.014232944670858852,1739502651.9917526,12.369988203048706,2.3689467676400353,1739502651.9917548,12.369988203048706,0.0,1739502651.9917564,12.369988203048706,-0.03458706723638327,1739502651.9917583,12.369988203048706,0.03041953320604684,1739502651.9917605,12.369988203048706,2.4035338348764186 +1739502652.011367,12.38998818397522,24.259192655593292,1739502652.011371,12.38998818397522,-0.18474148063680662,1739502652.0113752,12.38998818397522,23.4690224512405,1739502652.011379,12.38998818397522,30.262032051805036,1739502652.0113807,12.38998818397522,-0.07553754578315097,1739502652.0113833,12.38998818397522,0.018190040246546343,1739502652.0113857,12.38998818397522,-0.07846325387234612,1739502652.0113873,12.38998818397522,-0.016717290319434783,1739502652.0113893,12.38998818397522,2.347897222800345,1739502652.0113914,12.38998818397522,0.0,1739502652.0113935,12.38998818397522,-0.05972635551785761,1739502652.011397,12.38998818397522,0.03125927323990798,1739502652.0113986,12.38998818397522,2.3997675455794254 +1739502652.0313206,12.409988164901733,24.259192655593292,1739502652.0313241,12.409988164901733,-0.18474148063680662,1739502652.0313294,12.409988164901733,23.4690224512405,1739502652.031333,12.409988164901733,30.262032051805036,1739502652.0313349,12.409988164901733,-0.07553754578315097,1739502652.0313373,12.409988164901733,0.018190040246546343,1739502652.031339,12.409988164901733,-0.07846325387234612,1739502652.0313408,12.409988164901733,-0.016717290319434783,1739502652.0313427,12.409988164901733,2.347897222800345,1739502652.0313454,12.409988164901733,0.0,1739502652.0313473,12.409988164901733,-0.051870322779080436,1739502652.0313497,12.409988164901733,0.03125927323990798,1739502652.0313518,12.409988164901733,2.3997675455794254 +1739502652.0517817,12.429988145828247,24.259192655593292,1739502652.0517848,12.429988145828247,-0.18474148063680662,1739502652.0517888,12.429988145828247,23.4690224512405,1739502652.0517926,12.429988145828247,30.262032051805036,1739502652.0517945,12.429988145828247,-0.07553754578315097,1739502652.0517964,12.429988145828247,0.018190040246546343,1739502652.0517983,12.429988145828247,-0.07846325387234612,1739502652.0518,12.429988145828247,-0.016717290319434783,1739502652.051802,12.429988145828247,2.347897222800345,1739502652.0518038,12.429988145828247,0.0,1739502652.0518057,12.429988145828247,-0.051870322779080436,1739502652.0518074,12.429988145828247,0.03125927323990798,1739502652.0518093,12.429988145828247,2.3997675455794254 +1739502652.071322,12.44998812675476,24.259192655593292,1739502652.071327,12.44998812675476,-0.18474148063680662,1739502652.0713315,12.44998812675476,23.4690224512405,1739502652.0713353,12.44998812675476,30.262032051805036,1739502652.0713375,12.44998812675476,-0.07553754578315097,1739502652.0713398,12.44998812675476,0.018190040246546343,1739502652.0713415,12.44998812675476,-0.07846325387234612,1739502652.0713437,12.44998812675476,-0.016717290319434783,1739502652.0713453,12.44998812675476,2.347897222800345,1739502652.0713477,12.44998812675476,0.0,1739502652.0713496,12.44998812675476,-0.051870322779080436,1739502652.0713518,12.44998812675476,0.03125927323990798,1739502652.071354,12.44998812675476,2.3997675455794254 +1739502652.091394,12.469988107681274,24.259192655593292,1739502652.0913973,12.469988107681274,-0.18474148063680662,1739502652.091401,12.469988107681274,23.4690224512405,1739502652.0914052,12.469988107681274,30.262032051805036,1739502652.0914068,12.469988107681274,-0.07553754578315097,1739502652.091409,12.469988107681274,0.018190040246546343,1739502652.0914106,12.469988107681274,-0.07846325387234612,1739502652.0914125,12.469988107681274,-0.016717290319434783,1739502652.0914142,12.469988107681274,2.347897222800345,1739502652.0914164,12.469988107681274,0.0,1739502652.0914178,12.469988107681274,-0.051870322779080436,1739502652.09142,12.469988107681274,0.03125927323990798,1739502652.0914218,12.469988107681274,2.3997675455794254 +1739502652.1186428,12.489988088607788,24.259192655593292,1739502652.1186507,12.489988088607788,-0.18474148063680662,1739502652.1186612,12.489988088607788,23.4690224512405,1739502652.1186714,12.489988088607788,30.262032051805036,1739502652.118676,12.489988088607788,-0.07553754578315097,1739502652.1186821,12.489988088607788,0.018190040246546343,1739502652.1186872,12.489988088607788,-0.07846325387234612,1739502652.1186922,12.489988088607788,-0.016717290319434783,1739502652.1186967,12.489988088607788,2.347897222800345,1739502652.1187027,12.489988088607788,0.0,1739502652.1187074,12.489988088607788,-0.051870322779080436,1739502652.118713,12.489988088607788,0.03125927323990798,1739502652.1187181,12.489988088607788,2.3997675455794254 +1739502652.1374974,12.509988069534302,24.522735786790708,1739502652.137506,12.509988069534302,-0.17639997978524047,1739502652.1375167,12.509988069534302,23.86725905378269,1739502652.1375275,12.509988069534302,30.648597108576272,1739502652.1375327,12.509988069534302,-0.07416703665650919,1739502652.1375391,12.509988069534302,0.016687196825817416,1739502652.1375444,12.509988069534302,-0.09442005877365015,1739502652.1375494,12.509988069534302,-0.019318091617260544,1739502652.137554,12.509988069534302,2.3181157636661216,1739502652.1375594,12.509988069534302,0.0,1739502652.1375642,12.509988069534302,-0.08670367597166961,1739502652.137569,12.509988069534302,0.032099013273769156,1739502652.1375742,12.509988069534302,2.393934009628063 +1739502652.1591818,12.519988059997559,24.522735786790708,1739502652.1591878,12.519988059997559,-0.17639997978524047,1739502652.1591954,12.519988059997559,23.86725905378269,1739502652.1592026,12.519988059997559,30.648597108576272,1739502652.1592062,12.519988059997559,-0.07416703665650919,1739502652.1592104,12.519988059997559,0.016687196825817416,1739502652.159214,12.519988059997559,-0.09442005877365015,1739502652.1592171,12.519988059997559,-0.019318091617260544,1739502652.1592205,12.519988059997559,2.3181157636661216,1739502652.1592247,12.519988059997559,0.0,1739502652.159228,12.519988059997559,-0.07581824596194142,1739502652.159232,12.519988059997559,0.032099013273769156,1739502652.1592355,12.519988059997559,2.393934009628063 +1739502652.1789067,12.549988031387329,24.522735786790708,1739502652.178914,12.549988031387329,-0.17639997978524047,1739502652.1789238,12.549988031387329,23.86725905378269,1739502652.1789343,12.549988031387329,30.648597108576272,1739502652.1789398,12.549988031387329,-0.07416703665650919,1739502652.1789477,12.549988031387329,0.016687196825817416,1739502652.1789541,12.549988031387329,-0.09442005877365015,1739502652.1789608,12.549988031387329,-0.019318091617260544,1739502652.1789675,12.549988031387329,2.3181157636661216,1739502652.1789744,12.549988031387329,0.0,1739502652.1789813,12.549988031387329,-0.07581824596194142,1739502652.178988,12.549988031387329,0.032099013273769156,1739502652.178995,12.549988031387329,2.393934009628063 +1739502652.1977797,12.569988012313843,24.522735786790708,1739502652.1977844,12.569988012313843,-0.17639997978524047,1739502652.1977906,12.569988012313843,23.86725905378269,1739502652.1977975,12.569988012313843,30.648597108576272,1739502652.1978018,12.569988012313843,-0.07416703665650919,1739502652.1978068,12.569988012313843,0.016687196825817416,1739502652.1978114,12.569988012313843,-0.09442005877365015,1739502652.1978161,12.569988012313843,-0.019318091617260544,1739502652.1978204,12.569988012313843,2.3181157636661216,1739502652.1978252,12.569988012313843,0.0,1739502652.19783,12.569988012313843,-0.07581824596194142,1739502652.1978345,12.569988012313843,0.032099013273769156,1739502652.1978393,12.569988012313843,2.393934009628063 +1739502652.2158928,12.589987993240356,24.522735786790708,1739502652.2158961,12.589987993240356,-0.17639997978524047,1739502652.2159004,12.589987993240356,23.86725905378269,1739502652.2159054,12.589987993240356,30.648597108576272,1739502652.215908,12.589987993240356,-0.07416703665650919,1739502652.2159116,12.589987993240356,0.016687196825817416,1739502652.215915,12.589987993240356,-0.09442005877365015,1739502652.2159183,12.589987993240356,-0.019318091617260544,1739502652.2159214,12.589987993240356,2.3181157636661216,1739502652.2159247,12.589987993240356,0.0,1739502652.215928,12.589987993240356,-0.07581824596194142,1739502652.2159314,12.589987993240356,0.032099013273769156,1739502652.215935,12.589987993240356,2.393934009628063 +1739502652.2358372,12.60998797416687,24.78551244520974,1739502652.2358391,12.60998797416687,-0.16786186908413914,1739502652.2358418,12.60998797416687,23.873828470243165,1739502652.2358441,12.60998797416687,30.638405578619167,1739502652.235845,12.60998797416687,-0.07422124692223846,1739502652.2358468,12.60998797416687,0.0159976667188906,1739502652.235848,12.60998797416687,-0.09916231534897227,1739502652.235849,12.60998797416687,-0.02222529798159087,1739502652.2358503,12.60998797416687,2.309337945083424,1739502652.2358515,12.60998797416687,0.0,1739502652.2358527,12.60998797416687,-0.07639609818695269,1739502652.2358541,12.60998797416687,0.03293875330763033,1739502652.2358553,12.60998797416687,2.385553464331664 +1739502652.255528,12.629987955093384,24.78551244520974,1739502652.255531,12.629987955093384,-0.16786186908413914,1739502652.2555351,12.629987955093384,23.873828470243165,1739502652.2555397,12.629987955093384,30.638405578619167,1739502652.2555423,12.629987955093384,-0.07422124692223846,1739502652.2555456,12.629987955093384,0.0159976667188906,1739502652.2555487,12.629987955093384,-0.09916231534897227,1739502652.2555518,12.629987955093384,-0.02222529798159087,1739502652.255555,12.629987955093384,2.309337945083424,1739502652.2555578,12.629987955093384,0.0,1739502652.2555609,12.629987955093384,-0.07621551924823988,1739502652.2555642,12.629987955093384,0.03293875330763033,1739502652.2555676,12.629987955093384,2.385553464331664 +1739502652.2752795,12.649987936019897,24.78551244520974,1739502652.2752826,12.649987936019897,-0.16786186908413914,1739502652.2752867,12.649987936019897,23.873828470243165,1739502652.2752917,12.649987936019897,30.638405578619167,1739502652.2752943,12.649987936019897,-0.07422124692223846,1739502652.2752979,12.649987936019897,0.0159976667188906,1739502652.275301,12.649987936019897,-0.09916231534897227,1739502652.2753038,12.649987936019897,-0.02222529798159087,1739502652.275307,12.649987936019897,2.309337945083424,1739502652.27531,12.649987936019897,0.0,1739502652.2753131,12.649987936019897,-0.07621551924823988,1739502652.2753162,12.649987936019897,0.03293875330763033,1739502652.2753193,12.649987936019897,2.385553464331664 +1739502652.2961743,12.669987916946411,24.78551244520974,1739502652.2961779,12.669987916946411,-0.16786186908413914,1739502652.2961822,12.669987916946411,23.873828470243165,1739502652.2961874,12.669987916946411,30.638405578619167,1739502652.29619,12.669987916946411,-0.07422124692223846,1739502652.2961938,12.669987916946411,0.0159976667188906,1739502652.296197,12.669987916946411,-0.09916231534897227,1739502652.2962003,12.669987916946411,-0.02222529798159087,1739502652.2962034,12.669987916946411,2.309337945083424,1739502652.2962065,12.669987916946411,0.0,1739502652.2962098,12.669987916946411,-0.07621551924823988,1739502652.2962132,12.669987916946411,0.03293875330763033,1739502652.2962165,12.669987916946411,2.385553464331664 +1739502652.3161886,12.689987897872925,24.78551244520974,1739502652.316192,12.689987897872925,-0.16786186908413914,1739502652.3161964,12.689987897872925,23.873828470243165,1739502652.3162012,12.689987897872925,30.638405578619167,1739502652.316204,12.689987897872925,-0.07422124692223846,1739502652.3162076,12.689987897872925,0.0159976667188906,1739502652.3162112,12.689987897872925,-0.09916231534897227,1739502652.3162146,12.689987897872925,-0.02222529798159087,1739502652.3162177,12.689987897872925,2.309337945083424,1739502652.316221,12.689987897872925,0.0,1739502652.316224,12.689987897872925,-0.07621551924823988,1739502652.3162274,12.689987897872925,0.03293875330763033,1739502652.3162308,12.689987897872925,2.385553464331664 +1739502652.335724,12.709987878799438,24.78551244520974,1739502652.3357275,12.709987878799438,-0.16786186908413914,1739502652.3357315,12.709987878799438,23.873828470243165,1739502652.3357363,12.709987878799438,30.638405578619167,1739502652.335739,12.709987878799438,-0.07422124692223846,1739502652.3357425,12.709987878799438,0.0159976667188906,1739502652.3357456,12.709987878799438,-0.09916231534897227,1739502652.3357487,12.709987878799438,-0.02222529798159087,1739502652.3357518,12.709987878799438,2.309337945083424,1739502652.3357546,12.709987878799438,0.0,1739502652.3357577,12.709987878799438,-0.07621551924823988,1739502652.335761,12.709987878799438,0.03293875330763033,1739502652.3357642,12.709987878799438,2.385553464331664 +1739502652.3568347,12.729987859725952,25.047361193182127,1739502652.356838,12.729987859725952,-0.15914001208320538,1739502652.3568423,12.729987859725952,24.21492308587432,1739502652.3568473,12.729987859725952,30.9628282583658,1739502652.35685,12.729987859725952,-0.07257906673822588,1739502652.3568535,12.729987859725952,0.014631941471124149,1739502652.3568568,12.729987859725952,-0.11287917235651103,1739502652.3568602,12.729987859725952,-0.024768180518475864,1739502652.3568633,12.729987859725952,2.2841349934029607,1739502652.3568666,12.729987859725952,0.0,1739502652.35687,12.729987859725952,-0.10075417649219721,1739502652.3568733,12.729987859725952,0.033713095542334405,1739502652.3568766,12.729987859725952,2.3772208344786687 +1739502652.3745084,12.749987840652466,25.047361193182127,1739502652.3745103,12.749987840652466,-0.15914001208320538,1739502652.3745131,12.749987840652466,24.21492308587432,1739502652.3745158,12.749987840652466,30.9628282583658,1739502652.3745167,12.749987840652466,-0.07257906673822588,1739502652.3745186,12.749987840652466,0.014631941471124149,1739502652.3745198,12.749987840652466,-0.11287917235651103,1739502652.3745213,12.749987840652466,-0.024768180518475864,1739502652.3745224,12.749987840652466,2.2841349934029607,1739502652.3745239,12.749987840652466,0.0,1739502652.374525,12.749987840652466,-0.09308584107570805,1739502652.3745265,12.749987840652466,0.033713095542334405,1739502652.3745277,12.749987840652466,2.3772208344786687 +1739502652.394679,12.76998782157898,25.047361193182127,1739502652.394681,12.76998782157898,-0.15914001208320538,1739502652.3946838,12.76998782157898,24.21492308587432,1739502652.3946867,12.76998782157898,30.9628282583658,1739502652.394688,12.76998782157898,-0.07257906673822588,1739502652.3946896,12.76998782157898,0.014631941471124149,1739502652.3946908,12.76998782157898,-0.11287917235651103,1739502652.3946924,12.76998782157898,-0.024768180518475864,1739502652.3946934,12.76998782157898,2.2841349934029607,1739502652.3946948,12.76998782157898,0.0,1739502652.3946965,12.76998782157898,-0.09308584107570805,1739502652.3946977,12.76998782157898,0.033713095542334405,1739502652.394699,12.76998782157898,2.3772208344786687 +1739502652.4144633,12.789987802505493,25.047361193182127,1739502652.4144654,12.789987802505493,-0.15914001208320538,1739502652.4144683,12.789987802505493,24.21492308587432,1739502652.414471,12.789987802505493,30.9628282583658,1739502652.414472,12.789987802505493,-0.07257906673822588,1739502652.4144738,12.789987802505493,0.014631941471124149,1739502652.4144752,12.789987802505493,-0.11287917235651103,1739502652.4144766,12.789987802505493,-0.024768180518475864,1739502652.4144778,12.789987802505493,2.2841349934029607,1739502652.4144793,12.789987802505493,0.0,1739502652.4144807,12.789987802505493,-0.09308584107570805,1739502652.4144819,12.789987802505493,0.033713095542334405,1739502652.4144835,12.789987802505493,2.3772208344786687 +1739502652.4344885,12.809987783432007,25.047361193182127,1739502652.4344907,12.809987783432007,-0.15914001208320538,1739502652.4344935,12.809987783432007,24.21492308587432,1739502652.434496,12.809987783432007,30.9628282583658,1739502652.4344974,12.809987783432007,-0.07257906673822588,1739502652.4344988,12.809987783432007,0.014631941471124149,1739502652.4345,12.809987783432007,-0.11287917235651103,1739502652.4345014,12.809987783432007,-0.024768180518475864,1739502652.4345026,12.809987783432007,2.2841349934029607,1739502652.4345043,12.809987783432007,0.0,1739502652.4345055,12.809987783432007,-0.09308584107570805,1739502652.4345067,12.809987783432007,0.033713095542334405,1739502652.4345083,12.809987783432007,2.3772208344786687 +1739502652.4579587,12.82998776435852,25.308198643252975,1739502652.457967,12.82998776435852,-0.15026396700620026,1739502652.4579775,12.82998776435852,24.679379254372506,1739502652.4579873,12.82998776435852,31.406944842509752,1739502652.4579926,12.82998776435852,-0.07330039683636946,1739502652.4579983,12.82998776435852,0.012618902717094338,1739502652.4580035,12.82998776435852,-0.13252772479667574,1739502652.458008,12.82998776435852,-0.027359341695156407,1739502652.4580126,12.82998776435852,2.2485117480119046,1739502652.4580188,12.82998776435852,0.0,1739502652.458024,12.82998776435852,-0.1301136124979259,1739502652.458029,12.82998776435852,0.034349205762641145,1739502652.4580345,12.82998776435852,2.3670541743537266 +1739502652.480795,12.849987745285034,25.308198643252975,1739502652.4808006,12.849987745285034,-0.15026396700620026,1739502652.4808083,12.849987745285034,24.679379254372506,1739502652.4808156,12.849987745285034,31.406944842509752,1739502652.480819,12.849987745285034,-0.07330039683636946,1739502652.4808233,12.849987745285034,0.012618902717094338,1739502652.4808269,12.849987745285034,-0.13252772479667574,1739502652.4808302,12.849987745285034,-0.027359341695156407,1739502652.4808333,12.849987745285034,2.2485117480119046,1739502652.480837,12.849987745285034,0.0,1739502652.4808404,12.849987745285034,-0.118542426341822,1739502652.480844,12.849987745285034,0.034349205762641145,1739502652.4808476,12.849987745285034,2.3670541743537266 +1739502652.4959416,12.869987726211548,25.308198643252975,1739502652.4959466,12.869987726211548,-0.15026396700620026,1739502652.495953,12.869987726211548,24.679379254372506,1739502652.4959602,12.869987726211548,31.406944842509752,1739502652.495964,12.869987726211548,-0.07330039683636946,1739502652.4959693,12.869987726211548,0.012618902717094338,1739502652.4959738,12.869987726211548,-0.13252772479667574,1739502652.4959786,12.869987726211548,-0.027359341695156407,1739502652.495983,12.869987726211548,2.2485117480119046,1739502652.4959877,12.869987726211548,0.0,1739502652.4959924,12.869987726211548,-0.118542426341822,1739502652.4959972,12.869987726211548,0.034349205762641145,1739502652.4960017,12.869987726211548,2.3670541743537266 +1739502652.5149074,12.889987707138062,25.308198643252975,1739502652.51491,12.889987707138062,-0.15026396700620026,1739502652.5149133,12.889987707138062,24.679379254372506,1739502652.5149164,12.889987707138062,31.406944842509752,1739502652.5149179,12.889987707138062,-0.07330039683636946,1739502652.51492,12.889987707138062,0.012618902717094338,1739502652.5149214,12.889987707138062,-0.13252772479667574,1739502652.514923,12.889987707138062,-0.027359341695156407,1739502652.5149243,12.889987707138062,2.2485117480119046,1739502652.5149264,12.889987707138062,0.0,1739502652.5149276,12.889987707138062,-0.118542426341822,1739502652.5149293,12.889987707138062,0.034349205762641145,1739502652.514931,12.889987707138062,2.3670541743537266 +1739502652.5346406,12.909987688064575,25.308198643252975,1739502652.5346432,12.909987688064575,-0.15026396700620026,1739502652.5346465,12.909987688064575,24.679379254372506,1739502652.5346496,12.909987688064575,31.406944842509752,1739502652.534651,12.909987688064575,-0.07330039683636946,1739502652.534653,12.909987688064575,0.012618902717094338,1739502652.5346544,12.909987688064575,-0.13252772479667574,1739502652.5346563,12.909987688064575,-0.027359341695156407,1739502652.5346575,12.909987688064575,2.2485117480119046,1739502652.5346594,12.909987688064575,0.0,1739502652.5346608,12.909987688064575,-0.118542426341822,1739502652.5346627,12.909987688064575,0.034349205762641145,1739502652.534664,12.909987688064575,2.3670541743537266 +1739502652.5546677,12.929987668991089,25.308198643252975,1739502652.5546703,12.929987668991089,-0.15026396700620026,1739502652.554674,12.929987668991089,24.679379254372506,1739502652.5546772,12.929987668991089,31.406944842509752,1739502652.5546787,12.929987668991089,-0.07330039683636946,1739502652.554681,12.929987668991089,0.012618902717094338,1739502652.5546827,12.929987668991089,-0.13252772479667574,1739502652.5546842,12.929987668991089,-0.027359341695156407,1739502652.5546856,12.929987668991089,2.2485117480119046,1739502652.5546877,12.929987668991089,0.0,1739502652.5546892,12.929987668991089,-0.118542426341822,1739502652.5546908,12.929987668991089,0.034349205762641145,1739502652.5546923,12.929987668991089,2.3670541743537266 +1739502652.5747056,12.949987649917603,25.567747256830724,1739502652.5747082,12.949987649917603,-0.14128214098499292,1739502652.5747116,12.949987649917603,24.71130373384257,1739502652.5747147,12.949987649917603,31.41245763361113,1739502652.574716,12.949987649917603,-0.07334918259832855,1739502652.5747182,12.949987649917603,0.011622457769642451,1739502652.5747197,12.949987649917603,-0.13590754134131292,1739502652.5747213,12.949987649917603,-0.030549570335803466,1739502652.5747225,12.949987649917603,2.2424403140785847,1739502652.5747244,12.949987649917603,0.0,1739502652.574726,12.949987649917603,-0.10816525623822101,1739502652.574728,12.949987649917603,0.03487606685398633,1739502652.5747294,12.949987649917603,2.353848438100371 +1739502652.594683,12.969987630844116,25.567747256830724,1739502652.5946858,12.969987630844116,-0.14128214098499292,1739502652.5946891,12.969987630844116,24.71130373384257,1739502652.594692,12.969987630844116,31.41245763361113,1739502652.5946937,12.969987630844116,-0.07334918259832855,1739502652.5946956,12.969987630844116,0.011622457769642451,1739502652.5946972,12.969987630844116,-0.13590754134131292,1739502652.5946987,12.969987630844116,-0.030549570335803466,1739502652.5947003,12.969987630844116,2.2424403140785847,1739502652.594702,12.969987630844116,0.0,1739502652.5947037,12.969987630844116,-0.11140812402178613,1739502652.594705,12.969987630844116,0.03487606685398633,1739502652.5947068,12.969987630844116,2.353848438100371 +1739502652.6146486,12.98998761177063,25.567747256830724,1739502652.6146512,12.98998761177063,-0.14128214098499292,1739502652.6146545,12.98998761177063,24.71130373384257,1739502652.6146576,12.98998761177063,31.41245763361113,1739502652.614659,12.98998761177063,-0.07334918259832855,1739502652.6146612,12.98998761177063,0.011622457769642451,1739502652.6146626,12.98998761177063,-0.13590754134131292,1739502652.614664,12.98998761177063,-0.030549570335803466,1739502652.6146655,12.98998761177063,2.2424403140785847,1739502652.6146672,12.98998761177063,0.0,1739502652.6146688,12.98998761177063,-0.11140812402178613,1739502652.6146703,12.98998761177063,0.03487606685398633,1739502652.6146722,12.98998761177063,2.353848438100371 +1739502652.6347492,13.009987592697144,25.567747256830724,1739502652.6347518,13.009987592697144,-0.14128214098499292,1739502652.6347554,13.009987592697144,24.71130373384257,1739502652.6347585,13.009987592697144,31.41245763361113,1739502652.6347597,13.009987592697144,-0.07334918259832855,1739502652.6347618,13.009987592697144,0.011622457769642451,1739502652.6347635,13.009987592697144,-0.13590754134131292,1739502652.6347651,13.009987592697144,-0.030549570335803466,1739502652.6347666,13.009987592697144,2.2424403140785847,1739502652.6347685,13.009987592697144,0.0,1739502652.63477,13.009987592697144,-0.11140812402178613,1739502652.6347718,13.009987592697144,0.03487606685398633,1739502652.6347733,13.009987592697144,2.353848438100371 +1739502652.6546688,13.029987573623657,25.567747256830724,1739502652.6546714,13.029987573623657,-0.14128214098499292,1739502652.6546748,13.029987573623657,24.71130373384257,1739502652.6546779,13.029987573623657,31.41245763361113,1739502652.6546793,13.029987573623657,-0.07334918259832855,1739502652.6546814,13.029987573623657,0.011622457769642451,1739502652.6546829,13.029987573623657,-0.13590754134131292,1739502652.6546843,13.029987573623657,-0.030549570335803466,1739502652.654686,13.029987573623657,2.2424403140785847,1739502652.6546876,13.029987573623657,0.0,1739502652.6546893,13.029987573623657,-0.11140812402178613,1739502652.6546907,13.029987573623657,0.03487606685398633,1739502652.6546926,13.029987573623657,2.353848438100371 +1739502652.6747193,13.049987554550171,25.825900456715573,1739502652.6747217,13.049987554550171,-0.132225098328826,1739502652.6747253,13.049987554550171,24.959675577428406,1739502652.6747284,13.049987554550171,31.63644642096389,1739502652.67473,13.049987554550171,-0.07445109269376037,1739502652.674732,13.049987554550171,0.009942628835825383,1739502652.6747336,13.049987554550171,-0.147166372047341,1739502652.6747353,13.049987554550171,-0.033471483964961996,1739502652.6747367,13.049987554550171,2.2223331983676315,1739502652.6747386,13.049987554550171,0.0,1739502652.67474,13.049987554550171,-0.12292502782771383,1739502652.6747417,13.049987554550171,0.03527154545501697,1739502652.6747434,13.049987554550171,2.341659191396282 +1739502652.6946728,13.069987535476685,25.825900456715573,1739502652.6946754,13.069987535476685,-0.132225098328826,1739502652.6946788,13.069987535476685,24.959675577428406,1739502652.694682,13.069987535476685,31.63644642096389,1739502652.6946833,13.069987535476685,-0.07445109269376037,1739502652.6946855,13.069987535476685,0.009942628835825383,1739502652.6946871,13.069987535476685,-0.147166372047341,1739502652.6946888,13.069987535476685,-0.033471483964961996,1739502652.6946902,13.069987535476685,2.2223331983676315,1739502652.6946921,13.069987535476685,0.0,1739502652.6946936,13.069987535476685,-0.11932599302865032,1739502652.6946955,13.069987535476685,0.03527154545501697,1739502652.694697,13.069987535476685,2.341659191396282 +1739502652.714617,13.089987516403198,25.825900456715573,1739502652.7146199,13.089987516403198,-0.132225098328826,1739502652.714623,13.089987516403198,24.959675577428406,1739502652.714626,13.089987516403198,31.63644642096389,1739502652.7146277,13.089987516403198,-0.07445109269376037,1739502652.71463,13.089987516403198,0.009942628835825383,1739502652.7146313,13.089987516403198,-0.147166372047341,1739502652.714633,13.089987516403198,-0.033471483964961996,1739502652.7146344,13.089987516403198,2.2223331983676315,1739502652.7146363,13.089987516403198,0.0,1739502652.7146378,13.089987516403198,-0.11932599302865032,1739502652.7146394,13.089987516403198,0.03527154545501697,1739502652.7146409,13.089987516403198,2.341659191396282 +1739502652.73466,13.109987497329712,25.825900456715573,1739502652.7346623,13.109987497329712,-0.132225098328826,1739502652.7346656,13.109987497329712,24.959675577428406,1739502652.7346685,13.109987497329712,31.63644642096389,1739502652.7346704,13.109987497329712,-0.07445109269376037,1739502652.7346723,13.109987497329712,0.009942628835825383,1739502652.734674,13.109987497329712,-0.147166372047341,1739502652.7346754,13.109987497329712,-0.033471483964961996,1739502652.7346773,13.109987497329712,2.2223331983676315,1739502652.734679,13.109987497329712,0.0,1739502652.7346804,13.109987497329712,-0.11932599302865032,1739502652.734682,13.109987497329712,0.03527154545501697,1739502652.7346838,13.109987497329712,2.341659191396282 +1739502652.7547462,13.129987478256226,25.825900456715573,1739502652.7547493,13.129987478256226,-0.132225098328826,1739502652.7547524,13.129987478256226,24.959675577428406,1739502652.7547555,13.129987478256226,31.63644642096389,1739502652.7547572,13.129987478256226,-0.07445109269376037,1739502652.754759,13.129987478256226,0.009942628835825383,1739502652.754761,13.129987478256226,-0.147166372047341,1739502652.7547631,13.129987478256226,-0.033471483964961996,1739502652.7547646,13.129987478256226,2.2223331983676315,1739502652.7547662,13.129987478256226,0.0,1739502652.7547681,13.129987478256226,-0.11932599302865032,1739502652.7547696,13.129987478256226,0.03527154545501697,1739502652.7547717,13.129987478256226,2.341659191396282 +1739502652.774661,13.14998745918274,25.825900456715573,1739502652.7746637,13.14998745918274,-0.132225098328826,1739502652.7746673,13.14998745918274,24.959675577428406,1739502652.7746704,13.14998745918274,31.63644642096389,1739502652.774672,13.14998745918274,-0.07445109269376037,1739502652.7746742,13.14998745918274,0.009942628835825383,1739502652.7746756,13.14998745918274,-0.147166372047341,1739502652.7746773,13.14998745918274,-0.033471483964961996,1739502652.7746787,13.14998745918274,2.2223331983676315,1739502652.7746806,13.14998745918274,0.0,1739502652.774682,13.14998745918274,-0.11932599302865032,1739502652.7746837,13.14998745918274,0.03527154545501697,1739502652.7746854,13.14998745918274,2.341659191396282 +1739502652.7947423,13.169987440109253,26.082660758141525,1739502652.7947454,13.169987440109253,-0.12313078299786362,1739502652.7947488,13.169987440109253,25.737898497038366,1739502652.7947516,13.169987440109253,32.38837715284461,1739502652.7947533,13.169987440109253,-0.08,1739502652.7947552,13.169987440109253,0.006839843039829524,1739502652.794757,13.169987440109253,-0.181064165478598,1739502652.7947586,13.169987440109253,-0.034969133518466616,1739502652.79476,13.169987440109253,2.162877258684191,1739502652.794762,13.169987440109253,0.0,1739502652.7947636,13.169987440109253,-0.1867035703357825,1739502652.7947652,13.169987440109253,0.035557407832536796,1739502652.794767,13.169987440109253,2.3285253223064286 +1739502652.814701,13.189987421035767,26.082660758141525,1739502652.8147037,13.189987421035767,-0.12313078299786362,1739502652.814707,13.189987421035767,25.737898497038366,1739502652.81471,13.189987421035767,32.38837715284461,1739502652.8147116,13.189987421035767,-0.08,1739502652.8147137,13.189987421035767,0.006839843039829524,1739502652.8147154,13.189987421035767,-0.181064165478598,1739502652.8147168,13.189987421035767,-0.034969133518466616,1739502652.8147185,13.189987421035767,2.162877258684191,1739502652.8147202,13.189987421035767,0.0,1739502652.8147218,13.189987421035767,-0.16564806362223772,1739502652.8147233,13.189987421035767,0.035557407832536796,1739502652.8147252,13.189987421035767,2.3285253223064286 +1739502652.8346443,13.20998740196228,26.082660758141525,1739502652.8346467,13.20998740196228,-0.12313078299786362,1739502652.83465,13.20998740196228,25.737898497038366,1739502652.8346534,13.20998740196228,32.38837715284461,1739502652.834655,13.20998740196228,-0.08,1739502652.834657,13.20998740196228,0.006839843039829524,1739502652.8346586,13.20998740196228,-0.181064165478598,1739502652.8346605,13.20998740196228,-0.034969133518466616,1739502652.834662,13.20998740196228,2.162877258684191,1739502652.8346639,13.20998740196228,0.0,1739502652.8346655,13.20998740196228,-0.16564806362223772,1739502652.8346672,13.20998740196228,0.035557407832536796,1739502652.8346689,13.20998740196228,2.3285253223064286 +1739502652.8563607,13.229987382888794,26.082660758141525,1739502652.8563647,13.229987382888794,-0.12313078299786362,1739502652.8563702,13.229987382888794,25.737898497038366,1739502652.8563766,13.229987382888794,32.38837715284461,1739502652.8563802,13.229987382888794,-0.08,1739502652.8563845,13.229987382888794,0.006839843039829524,1739502652.8563883,13.229987382888794,-0.181064165478598,1739502652.8563924,13.229987382888794,-0.034969133518466616,1739502652.8563962,13.229987382888794,2.162877258684191,1739502652.8564005,13.229987382888794,0.0,1739502652.8564045,13.229987382888794,-0.16564806362223772,1739502652.8564084,13.229987382888794,0.035557407832536796,1739502652.8564126,13.229987382888794,2.3285253223064286 +1739502652.8746316,13.249987363815308,26.082660758141525,1739502652.8746343,13.249987363815308,-0.12313078299786362,1739502652.8746376,13.249987363815308,25.737898497038366,1739502652.874641,13.249987363815308,32.38837715284461,1739502652.8746424,13.249987363815308,-0.08,1739502652.8746445,13.249987363815308,0.006839843039829524,1739502652.874646,13.249987363815308,-0.181064165478598,1739502652.874648,13.249987363815308,-0.034969133518466616,1739502652.8746493,13.249987363815308,2.162877258684191,1739502652.8746512,13.249987363815308,0.0,1739502652.8746526,13.249987363815308,-0.16564806362223772,1739502652.8746545,13.249987363815308,0.035557407832536796,1739502652.8746562,13.249987363815308,2.3285253223064286 +1739502652.895066,13.269987344741821,26.337739563265007,1739502652.8950686,13.269987344741821,-0.11403083155021321,1739502652.895072,13.269987344741821,25.87853971737554,1739502652.8950756,13.269987344741821,32.492858405916834,1739502652.8950772,13.269987344741821,-0.08,1739502652.8950791,13.269987344741821,0.005528810356204809,1739502652.8950808,13.269987344741821,-0.1861131864352999,1739502652.8950822,13.269987344741821,-0.03772500546154687,1739502652.8950837,13.269987344741821,2.1541585488330033,1739502652.8950856,13.269987344741821,0.0,1739502652.895087,13.269987344741821,-0.1520316613369029,1739502652.8950887,13.269987344741821,0.0357700968551492,1739502652.89509,13.269987344741821,2.310445338673953 +1739502652.9146526,13.289987325668335,26.337739563265007,1739502652.9146552,13.289987325668335,-0.11403083155021321,1739502652.9146585,13.289987325668335,25.87853971737554,1739502652.914662,13.289987325668335,32.492858405916834,1739502652.9146633,13.289987325668335,-0.08,1739502652.9146655,13.289987325668335,0.005528810356204809,1739502652.914667,13.289987325668335,-0.1861131864352999,1739502652.9146686,13.289987325668335,-0.03772500546154687,1739502652.91467,13.289987325668335,2.1541585488330033,1739502652.914672,13.289987325668335,0.0,1739502652.9146733,13.289987325668335,-0.15628678984094968,1739502652.914675,13.289987325668335,0.0357700968551492,1739502652.9146764,13.289987325668335,2.310445338673953 +1739502652.934668,13.309987306594849,26.337739563265007,1739502652.9346707,13.309987306594849,-0.11403083155021321,1739502652.934674,13.309987306594849,25.87853971737554,1739502652.9346774,13.309987306594849,32.492858405916834,1739502652.9346788,13.309987306594849,-0.08,1739502652.9346805,13.309987306594849,0.005528810356204809,1739502652.9346824,13.309987306594849,-0.1861131864352999,1739502652.9346838,13.309987306594849,-0.03772500546154687,1739502652.9346855,13.309987306594849,2.1541585488330033,1739502652.9346871,13.309987306594849,0.0,1739502652.934689,13.309987306594849,-0.15628678984094968,1739502652.9346905,13.309987306594849,0.0357700968551492,1739502652.9346921,13.309987306594849,2.310445338673953 +1739502652.954798,13.329987287521362,26.337739563265007,1739502652.954801,13.329987287521362,-0.11403083155021321,1739502652.9548047,13.329987287521362,25.87853971737554,1739502652.9548078,13.329987287521362,32.492858405916834,1739502652.9548094,13.329987287521362,-0.08,1739502652.9548116,13.329987287521362,0.005528810356204809,1739502652.9548132,13.329987287521362,-0.1861131864352999,1739502652.9548147,13.329987287521362,-0.03772500546154687,1739502652.9548163,13.329987287521362,2.1541585488330033,1739502652.954818,13.329987287521362,0.0,1739502652.9548197,13.329987287521362,-0.15628678984094968,1739502652.9548213,13.329987287521362,0.0357700968551492,1739502652.954823,13.329987287521362,2.310445338673953 +1739502652.9746723,13.349987268447876,26.337739563265007,1739502652.9746752,13.349987268447876,-0.11403083155021321,1739502652.9746783,13.349987268447876,25.87853971737554,1739502652.9746816,13.349987268447876,32.492858405916834,1739502652.974683,13.349987268447876,-0.08,1739502652.974685,13.349987268447876,0.005528810356204809,1739502652.9746866,13.349987268447876,-0.1861131864352999,1739502652.9746883,13.349987268447876,-0.03772500546154687,1739502652.9746895,13.349987268447876,2.1541585488330033,1739502652.9746916,13.349987268447876,0.0,1739502652.974693,13.349987268447876,-0.15628678984094968,1739502652.9746947,13.349987268447876,0.0357700968551492,1739502652.9746962,13.349987268447876,2.310445338673953 +1739502652.9946864,13.36998724937439,26.337739563265007,1739502652.9946892,13.36998724937439,-0.11403083155021321,1739502652.9946926,13.36998724937439,25.87853971737554,1739502652.994696,13.36998724937439,32.492858405916834,1739502652.9946976,13.36998724937439,-0.08,1739502652.9946995,13.36998724937439,0.005528810356204809,1739502652.9947014,13.36998724937439,-0.1861131864352999,1739502652.9947028,13.36998724937439,-0.03772500546154687,1739502652.9947045,13.36998724937439,2.1541585488330033,1739502652.9947062,13.36998724937439,0.0,1739502652.9947078,13.36998724937439,-0.15628678984094968,1739502652.9947095,13.36998724937439,0.0357700968551492,1739502652.994711,13.36998724937439,2.310445338673953 +1739502653.014709,13.389987230300903,26.59087714125104,1739502653.0147116,13.389987230300903,-0.1049630820664289,1739502653.014715,13.389987230300903,26.133375926867398,1739502653.014718,13.389987230300903,32.71364384147076,1739502653.0147195,13.389987230300903,-0.07956611959667939,1739502653.0147216,13.389987230300903,0.0041479314921879454,1739502653.014723,13.389987230300903,-0.19394433203782818,1739502653.0147245,13.389987230300903,-0.0397292189311968,1739502653.0147262,13.389987230300903,2.1407051117683333,1739502653.0147283,13.389987230300903,0.0,1739502653.0147295,13.389987230300903,-0.1510920058536716,1739502653.0147312,13.389987230300903,0.03582888876619402,1739502653.0147328,13.389987230300903,2.2934204886823943 +1739502653.0346684,13.409987211227417,26.59087714125104,1739502653.0346713,13.409987211227417,-0.1049630820664289,1739502653.0346746,13.409987211227417,26.133375926867398,1739502653.034678,13.409987211227417,32.71364384147076,1739502653.03468,13.409987211227417,-0.07956611959667939,1739502653.0346818,13.409987211227417,0.0041479314921879454,1739502653.0346835,13.409987211227417,-0.19394433203782818,1739502653.0346851,13.409987211227417,-0.0397292189311968,1739502653.0346866,13.409987211227417,2.1407051117683333,1739502653.0346885,13.409987211227417,0.0,1739502653.0346901,13.409987211227417,-0.152715376914061,1739502653.0346916,13.409987211227417,0.03582888876619402,1739502653.0346935,13.409987211227417,2.2934204886823943 +1739502653.0547385,13.42998719215393,26.59087714125104,1739502653.0547416,13.42998719215393,-0.1049630820664289,1739502653.0547447,13.42998719215393,26.133375926867398,1739502653.0547478,13.42998719215393,32.71364384147076,1739502653.0547497,13.42998719215393,-0.07956611959667939,1739502653.0547516,13.42998719215393,0.0041479314921879454,1739502653.0547533,13.42998719215393,-0.19394433203782818,1739502653.054755,13.42998719215393,-0.0397292189311968,1739502653.0547564,13.42998719215393,2.1407051117683333,1739502653.0547585,13.42998719215393,0.0,1739502653.0547602,13.42998719215393,-0.152715376914061,1739502653.0547616,13.42998719215393,0.03582888876619402,1739502653.0547636,13.42998719215393,2.2934204886823943 +1739502653.0746465,13.449987173080444,26.59087714125104,1739502653.074649,13.449987173080444,-0.1049630820664289,1739502653.0746524,13.449987173080444,26.133375926867398,1739502653.0746555,13.449987173080444,32.71364384147076,1739502653.074657,13.449987173080444,-0.07956611959667939,1739502653.074659,13.449987173080444,0.0041479314921879454,1739502653.0746605,13.449987173080444,-0.19394433203782818,1739502653.0746624,13.449987173080444,-0.0397292189311968,1739502653.0746636,13.449987173080444,2.1407051117683333,1739502653.0746655,13.449987173080444,0.0,1739502653.074667,13.449987173080444,-0.152715376914061,1739502653.074669,13.449987173080444,0.03582888876619402,1739502653.0746703,13.449987173080444,2.2934204886823943 +1739502653.0947342,13.469987154006958,26.59087714125104,1739502653.0947368,13.469987154006958,-0.1049630820664289,1739502653.0947402,13.469987154006958,26.133375926867398,1739502653.0947437,13.469987154006958,32.71364384147076,1739502653.0947454,13.469987154006958,-0.07956611959667939,1739502653.0947473,13.469987154006958,0.0041479314921879454,1739502653.0947492,13.469987154006958,-0.19394433203782818,1739502653.0947506,13.469987154006958,-0.0397292189311968,1739502653.0947523,13.469987154006958,2.1407051117683333,1739502653.094754,13.469987154006958,0.0,1739502653.0947556,13.469987154006958,-0.152715376914061,1739502653.0947573,13.469987154006958,0.03582888876619402,1739502653.094759,13.469987154006958,2.2934204886823943 +1739502653.1574044,13.499987125396729,26.84215538640039,1739502653.157406,13.499987125396729,-0.09595803557975824,1739502653.1574087,13.499987125396729,26.702796377567104,1739502653.1574113,13.499987125396729,33.249648784605604,1739502653.1574128,13.499987125396729,-0.07827501066135434,1739502653.1574144,13.499987125396729,0.0027597344120929286,1739502653.1574156,13.499987125396729,-0.21166533050356465,1739502653.157417,13.499987125396729,-0.0395918770507865,1739502653.1574183,13.499987125396729,2.1105708743778044,1739502653.1574197,13.499987125396729,0.0,1739502653.157421,13.499987125396729,-0.17224814507010122,1739502653.1574223,13.499987125396729,0.03579964976111607,1739502653.1574242,13.499987125396729,2.2767150253970527 +1739502653.1632495,13.499987125396729,26.84215538640039,1739502653.1632516,13.499987125396729,-0.09595803557975824,1739502653.1632543,13.499987125396729,26.702796377567104,1739502653.163257,13.499987125396729,33.249648784605604,1739502653.163258,13.499987125396729,-0.07827501066135434,1739502653.16326,13.499987125396729,0.0027597344120929286,1739502653.1632612,13.499987125396729,-0.21166533050356465,1739502653.1632624,13.499987125396729,-0.0395918770507865,1739502653.1632636,13.499987125396729,2.1105708743778044,1739502653.163265,13.499987125396729,0.0,1739502653.1632664,13.499987125396729,-0.1661441510192483,1739502653.1632676,13.499987125396729,0.03579964976111607,1739502653.1632688,13.499987125396729,2.2767150253970527 +1739502653.183915,13.519987106323242,26.84215538640039,1739502653.1839178,13.519987106323242,-0.09595803557975824,1739502653.1839206,13.519987106323242,26.702796377567104,1739502653.1839235,13.519987106323242,33.249648784605604,1739502653.1839247,13.519987106323242,-0.07827501066135434,1739502653.1839266,13.519987106323242,0.0027597344120929286,1739502653.183928,13.519987106323242,-0.21166533050356465,1739502653.1839297,13.519987106323242,-0.0395918770507865,1739502653.1839309,13.519987106323242,2.1105708743778044,1739502653.1839323,13.519987106323242,0.0,1739502653.1839337,13.519987106323242,-0.1661441510192483,1739502653.1839352,13.519987106323242,0.03579964976111607,1739502653.1839368,13.519987106323242,2.2767150253970527 +1739502653.2035115,13.539987087249756,26.84215538640039,1739502653.2035136,13.539987087249756,-0.09595803557975824,1739502653.2035165,13.539987087249756,26.702796377567104,1739502653.2035186,13.539987087249756,33.249648784605604,1739502653.2035203,13.539987087249756,-0.07827501066135434,1739502653.2035217,13.539987087249756,0.0027597344120929286,1739502653.2035232,13.539987087249756,-0.21166533050356465,1739502653.2035244,13.539987087249756,-0.0395918770507865,1739502653.2035263,13.539987087249756,2.1105708743778044,1739502653.2035277,13.539987087249756,0.0,1739502653.203529,13.539987087249756,-0.1661441510192483,1739502653.2035303,13.539987087249756,0.03579964976111607,1739502653.2035315,13.539987087249756,2.2767150253970527 +1739502653.223483,13.55998706817627,26.84215538640039,1739502653.2234852,13.55998706817627,-0.09595803557975824,1739502653.223488,13.55998706817627,26.702796377567104,1739502653.2234907,13.55998706817627,33.249648784605604,1739502653.2234921,13.55998706817627,-0.07827501066135434,1739502653.2234938,13.55998706817627,0.0027597344120929286,1739502653.2234955,13.55998706817627,-0.21166533050356465,1739502653.223497,13.55998706817627,-0.0395918770507865,1739502653.2234979,13.55998706817627,2.1105708743778044,1739502653.2234995,13.55998706817627,0.0,1739502653.2235007,13.55998706817627,-0.1661441510192483,1739502653.2235024,13.55998706817627,0.03579964976111607,1739502653.2235036,13.55998706817627,2.2767150253970527 +1739502653.2437978,13.579987049102783,26.84215538640039,1739502653.2438006,13.579987049102783,-0.09595803557975824,1739502653.2438037,13.579987049102783,26.702796377567104,1739502653.2438068,13.579987049102783,33.249648784605604,1739502653.243808,13.579987049102783,-0.07827501066135434,1739502653.2438097,13.579987049102783,0.0027597344120929286,1739502653.2438111,13.579987049102783,-0.21166533050356465,1739502653.2438123,13.579987049102783,-0.0395918770507865,1739502653.2438135,13.579987049102783,2.1105708743778044,1739502653.2438157,13.579987049102783,0.0,1739502653.2438169,13.579987049102783,-0.1661441510192483,1739502653.2438183,13.579987049102783,0.03579964976111607,1739502653.2438195,13.579987049102783,2.2767150253970527 +1739502653.2638428,13.599987030029297,27.091538107593223,1739502653.2638457,13.599987030029297,-0.08703138271189115,1739502653.263849,13.599987030029297,26.932610926479597,1739502653.2638521,13.599987030029297,33.44337083815359,1739502653.2638535,13.599987030029297,-0.0769816802274261,1739502653.2638552,13.599987030029297,0.0015821723469523776,1739502653.263857,13.599987030029297,-0.2170227766308363,1739502653.2638583,13.599987030029297,-0.041308544625035484,1739502653.2638597,13.599987030029297,2.101544415895574,1739502653.2638614,13.599987030029297,0.0,1739502653.2638628,13.599987030029297,-0.15303344695573226,1739502653.2638643,13.599987030029297,0.03575573467855233,1739502653.263866,13.599987030029297,2.2586749605574217 +1739502653.2837448,13.61998701095581,27.091538107593223,1739502653.2837474,13.61998701095581,-0.08703138271189115,1739502653.28375,13.61998701095581,26.932610926479597,1739502653.283753,13.61998701095581,33.44337083815359,1739502653.2837546,13.61998701095581,-0.0769816802274261,1739502653.283756,13.61998701095581,0.0015821723469523776,1739502653.2837572,13.61998701095581,-0.2170227766308363,1739502653.2837586,13.61998701095581,-0.041308544625035484,1739502653.2837598,13.61998701095581,2.101544415895574,1739502653.2837615,13.61998701095581,0.0,1739502653.2837625,13.61998701095581,-0.15713054466184762,1739502653.283764,13.61998701095581,0.03575573467855233,1739502653.2837653,13.61998701095581,2.2586749605574217 +1739502653.303691,13.639986991882324,27.091538107593223,1739502653.3036938,13.639986991882324,-0.08703138271189115,1739502653.303697,13.639986991882324,26.932610926479597,1739502653.3037002,13.639986991882324,33.44337083815359,1739502653.3037014,13.639986991882324,-0.0769816802274261,1739502653.3037033,13.639986991882324,0.0015821723469523776,1739502653.3037047,13.639986991882324,-0.2170227766308363,1739502653.303707,13.639986991882324,-0.041308544625035484,1739502653.303708,13.639986991882324,2.101544415895574,1739502653.3037097,13.639986991882324,0.0,1739502653.303711,13.639986991882324,-0.15713054466184762,1739502653.3037126,13.639986991882324,0.03575573467855233,1739502653.3037138,13.639986991882324,2.2586749605574217 +1739502653.3238661,13.659986972808838,27.091538107593223,1739502653.3238685,13.659986972808838,-0.08703138271189115,1739502653.3238711,13.659986972808838,26.932610926479597,1739502653.3238738,13.659986972808838,33.44337083815359,1739502653.3238752,13.659986972808838,-0.0769816802274261,1739502653.3238769,13.659986972808838,0.0015821723469523776,1739502653.323878,13.659986972808838,-0.2170227766308363,1739502653.323898,13.659986972808838,-0.041308544625035484,1739502653.323899,13.659986972808838,2.101544415895574,1739502653.3239007,13.659986972808838,0.0,1739502653.323902,13.659986972808838,-0.15713054466184762,1739502653.3239036,13.659986972808838,0.03575573467855233,1739502653.3239048,13.659986972808838,2.2586749605574217 +1739502653.3436747,13.679986953735352,27.091538107593223,1739502653.343677,13.679986953735352,-0.08703138271189115,1739502653.3436797,13.679986953735352,26.932610926479597,1739502653.3436825,13.679986953735352,33.44337083815359,1739502653.343684,13.679986953735352,-0.0769816802274261,1739502653.3436854,13.679986953735352,0.0015821723469523776,1739502653.3436868,13.679986953735352,-0.2170227766308363,1739502653.3436882,13.679986953735352,-0.041308544625035484,1739502653.3436894,13.679986953735352,2.101544415895574,1739502653.3436913,13.679986953735352,0.0,1739502653.3436925,13.679986953735352,-0.15713054466184762,1739502653.3436937,13.679986953735352,0.03575573467855233,1739502653.3436952,13.679986953735352,2.2586749605574217 +1739502653.3652112,13.699986934661865,27.091538107593223,1739502653.3652134,13.699986934661865,-0.08703138271189115,1739502653.3652163,13.699986934661865,26.932610926479597,1739502653.3652189,13.699986934661865,33.44337083815359,1739502653.36522,13.699986934661865,-0.0769816802274261,1739502653.3652217,13.699986934661865,0.0015821723469523776,1739502653.365223,13.699986934661865,-0.2170227766308363,1739502653.3652241,13.699986934661865,-0.041308544625035484,1739502653.3652256,13.699986934661865,2.101544415895574,1739502653.365227,13.699986934661865,0.0,1739502653.3652282,13.699986934661865,-0.15713054466184762,1739502653.3652296,13.699986934661865,0.03575573467855233,1739502653.3652308,13.699986934661865,2.2586749605574217 +1739502653.3845348,13.719986915588379,27.338980532388167,1739502653.3845384,13.719986915588379,-0.07819249580107446,1739502653.3845432,13.719986915588379,26.938805825986382,1739502653.3845484,13.719986915588379,33.41532941330041,1739502653.3845513,13.719986915588379,-0.0775482352599908,1739502653.384555,13.719986915588379,0.00010602757532459335,1739502653.3845751,13.719986915588379,-0.21586148894962323,1739502653.3845785,13.719986915588379,-0.04489712746772427,1739502653.384582,13.719986915588379,2.1034977212082033,1739502653.3845856,13.719986915588379,0.0,1739502653.384589,13.719986915588379,-0.12938575419842546,1739502653.3845925,13.719986915588379,0.035638371293744635,1739502653.3845959,13.719986915588379,2.241553728111109 +1739502653.4042873,13.739986896514893,27.338980532388167,1739502653.4042897,13.739986896514893,-0.07819249580107446,1739502653.4042928,13.739986896514893,26.938805825986382,1739502653.4042957,13.739986896514893,33.41532941330041,1739502653.4042969,13.739986896514893,-0.0775482352599908,1739502653.4042988,13.739986896514893,0.00010602757532459335,1739502653.4043,13.739986896514893,-0.21586148894962323,1739502653.404302,13.739986896514893,-0.04489712746772427,1739502653.404303,13.739986896514893,2.1034977212082033,1739502653.4043047,13.739986896514893,0.0,1739502653.404306,13.739986896514893,-0.13805600690290554,1739502653.4043074,13.739986896514893,0.035638371293744635,1739502653.4043088,13.739986896514893,2.241553728111109 +1739502653.425098,13.759986877441406,27.338980532388167,1739502653.4251003,13.759986877441406,-0.07819249580107446,1739502653.4251034,13.759986877441406,26.938805825986382,1739502653.4251058,13.759986877441406,33.41532941330041,1739502653.4251075,13.759986877441406,-0.0775482352599908,1739502653.425109,13.759986877441406,0.00010602757532459335,1739502653.4251106,13.759986877441406,-0.21586148894962323,1739502653.4251118,13.759986877441406,-0.04489712746772427,1739502653.4251132,13.759986877441406,2.1034977212082033,1739502653.4251149,13.759986877441406,0.0,1739502653.4251163,13.759986877441406,-0.13805600690290554,1739502653.425118,13.759986877441406,0.035638371293744635,1739502653.4251192,13.759986877441406,2.241553728111109 +1739502653.4440963,13.77998685836792,27.338980532388167,1739502653.4440985,13.77998685836792,-0.07819249580107446,1739502653.4441016,13.77998685836792,26.938805825986382,1739502653.4441047,13.77998685836792,33.41532941330041,1739502653.444106,13.77998685836792,-0.0775482352599908,1739502653.4441075,13.77998685836792,0.00010602757532459335,1739502653.4441092,13.77998685836792,-0.21586148894962323,1739502653.4441106,13.77998685836792,-0.04489712746772427,1739502653.4441118,13.77998685836792,2.1034977212082033,1739502653.4441135,13.77998685836792,0.0,1739502653.444115,13.77998685836792,-0.13805600690290554,1739502653.444116,13.77998685836792,0.035638371293744635,1739502653.444118,13.77998685836792,2.241553728111109 +1739502653.46544,13.799986839294434,27.338980532388167,1739502653.4654436,13.799986839294434,-0.07819249580107446,1739502653.4654481,13.799986839294434,26.938805825986382,1739502653.4654534,13.799986839294434,33.41532941330041,1739502653.465456,13.799986839294434,-0.0775482352599908,1739502653.46546,13.799986839294434,0.00010602757532459335,1739502653.4654634,13.799986839294434,-0.21586148894962323,1739502653.4654667,13.799986839294434,-0.04489712746772427,1739502653.4654698,13.799986839294434,2.1034977212082033,1739502653.4654732,13.799986839294434,0.0,1739502653.4654768,13.799986839294434,-0.13805600690290554,1739502653.46548,13.799986839294434,0.035638371293744635,1739502653.4654834,13.799986839294434,2.241553728111109 +1739502653.4851837,13.819986820220947,27.58463638556982,1739502653.4851878,13.819986820220947,-0.06945845389741212,1739502653.4851925,13.819986820220947,26.944955956357823,1739502653.4851978,13.819986820220947,33.39125405853483,1739502653.4852006,13.819986820220947,-0.078,1739502653.4852042,13.819986820220947,-0.0014710009204667563,1739502653.4852078,13.819986820220947,-0.21398101191474916,1739502653.4852111,13.819986820220947,-0.04873610828009341,1739502653.4852145,13.819986820220947,2.1066645660086274,1739502653.485218,13.819986820220947,0.0,1739502653.4852219,13.819986820220947,-0.1114638580857869,1739502653.4852252,13.819986820220947,0.035388536495359654,1739502653.4852293,13.819986820220947,2.2264384760482585 +1739502653.5051298,13.839986801147461,27.58463638556982,1739502653.5051322,13.839986801147461,-0.06945845389741212,1739502653.505135,13.839986801147461,26.944955956357823,1739502653.5051377,13.839986801147461,33.39125405853483,1739502653.5051389,13.839986801147461,-0.078,1739502653.5051405,13.839986801147461,-0.0014710009204667563,1739502653.5051417,13.839986801147461,-0.21398101191474916,1739502653.5051434,13.839986801147461,-0.04873610828009341,1739502653.5051446,13.839986801147461,2.1066645660086274,1739502653.505146,13.839986801147461,0.0,1739502653.5051477,13.839986801147461,-0.11977391003963112,1739502653.5051494,13.839986801147461,0.035388536495359654,1739502653.505151,13.839986801147461,2.2264384760482585 +1739502653.5363617,13.859986782073975,27.58463638556982,1739502653.5363712,13.859986782073975,-0.06945845389741212,1739502653.5363815,13.859986782073975,26.944955956357823,1739502653.536392,13.859986782073975,33.39125405853483,1739502653.5363965,13.859986782073975,-0.078,1739502653.536403,13.859986782073975,-0.0014710009204667563,1739502653.536408,13.859986782073975,-0.21398101191474916,1739502653.5364134,13.859986782073975,-0.04873610828009341,1739502653.536418,13.859986782073975,2.1066645660086274,1739502653.5364237,13.859986782073975,0.0,1739502653.5364287,13.859986782073975,-0.11977391003963112,1739502653.5364342,13.859986782073975,0.035388536495359654,1739502653.5364392,13.859986782073975,2.2264384760482585 +1739502653.5676618,13.889986753463745,27.58463638556982,1739502653.5676715,13.889986753463745,-0.06945845389741212,1739502653.567682,13.889986753463745,26.944955956357823,1739502653.5676913,13.889986753463745,33.39125405853483,1739502653.5676966,13.889986753463745,-0.078,1739502653.5677025,13.889986753463745,-0.0014710009204667563,1739502653.567708,13.889986753463745,-0.21398101191474916,1739502653.567712,13.889986753463745,-0.04873610828009341,1739502653.567717,13.889986753463745,2.1066645660086274,1739502653.5677223,13.889986753463745,0.0,1739502653.567726,13.889986753463745,-0.11977391003963112,1739502653.5677443,13.889986753463745,0.035388536495359654,1739502653.567749,13.889986753463745,2.2264384760482585 +1739502653.5860994,13.919986724853516,27.58463638556982,1739502653.5861034,13.919986724853516,-0.06945845389741212,1739502653.5861096,13.919986724853516,26.944955956357823,1739502653.5861151,13.919986724853516,33.39125405853483,1739502653.5861177,13.919986724853516,-0.078,1739502653.5861206,13.919986724853516,-0.0014710009204667563,1739502653.5861235,13.919986724853516,-0.21398101191474916,1739502653.586126,13.919986724853516,-0.04873610828009341,1739502653.5861287,13.919986724853516,2.1066645660086274,1739502653.5861316,13.919986724853516,0.0,1739502653.5861342,13.919986724853516,-0.11977391003963112,1739502653.586137,13.919986724853516,0.035388536495359654,1739502653.58614,13.919986724853516,2.2264384760482585 +1739502653.606137,13.93998670578003,27.828752100396937,1739502653.6061423,13.93998670578003,-0.06086101963447188,1739502653.606148,13.93998670578003,26.951067446662766,1739502653.6061535,13.93998670578003,33.37146880274068,1739502653.606156,13.93998670578003,-0.078,1739502653.6061594,13.93998670578003,-0.003092152578172945,1739502653.6061625,13.93998670578003,-0.21087199992571623,1739502653.606165,13.93998670578003,-0.0527091399412929,1739502653.6061676,13.93998670578003,2.11191080386473,1739502653.6061707,13.93998670578003,0.0,1739502653.6061733,13.93998670578003,-0.0933090135624392,1739502653.606176,13.93998670578003,0.03496173063127122,1739502653.6061785,13.93998670578003,2.2134901029987133 +1739502653.6285744,13.959986686706543,27.828752100396937,1739502653.6285799,13.959986686706543,-0.06086101963447188,1739502653.6285858,13.959986686706543,26.951067446662766,1739502653.628591,13.959986686706543,33.37146880274068,1739502653.6285937,13.959986686706543,-0.078,1739502653.6285973,13.959986686706543,-0.003092152578172945,1739502653.6286001,13.959986686706543,-0.21087199992571623,1739502653.6286027,13.959986686706543,-0.0527091399412929,1739502653.628605,13.959986686706543,2.11191080386473,1739502653.628608,13.959986686706543,0.0,1739502653.6286106,13.959986686706543,-0.10157929913398345,1739502653.6286137,13.959986686706543,0.03496173063127122,1739502653.628616,13.959986686706543,2.2134901029987133 +1739502653.6513562,13.979986667633057,27.828752100396937,1739502653.6513636,13.979986667633057,-0.06086101963447188,1739502653.651373,13.979986667633057,26.951067446662766,1739502653.6513834,13.979986667633057,33.37146880274068,1739502653.6513891,13.979986667633057,-0.078,1739502653.6513968,13.979986667633057,-0.003092152578172945,1739502653.6514034,13.979986667633057,-0.21087199992571623,1739502653.65141,13.979986667633057,-0.0527091399412929,1739502653.651417,13.979986667633057,2.11191080386473,1739502653.6514242,13.979986667633057,0.0,1739502653.651431,13.979986667633057,-0.10157929913398345,1739502653.6514378,13.979986667633057,0.03496173063127122,1739502653.6514447,13.979986667633057,2.2134901029987133 +1739502653.6722684,14.009986639022827,27.828752100396937,1739502653.6722739,14.009986639022827,-0.06086101963447188,1739502653.672281,14.009986639022827,26.951067446662766,1739502653.6722898,14.009986639022827,33.37146880274068,1739502653.6722944,14.009986639022827,-0.078,1739502653.6723008,14.009986639022827,-0.003092152578172945,1739502653.6723065,14.009986639022827,-0.21087199992571623,1739502653.6723118,14.009986639022827,-0.0527091399412929,1739502653.6723173,14.009986639022827,2.11191080386473,1739502653.6723287,14.009986639022827,0.0,1739502653.6723342,14.009986639022827,-0.10157929913398345,1739502653.6723397,14.009986639022827,0.03496173063127122,1739502653.6723454,14.009986639022827,2.2134901029987133 +1739502653.7028935,14.02998661994934,27.828752100396937,1739502653.7028995,14.02998661994934,-0.06086101963447188,1739502653.702906,14.02998661994934,26.951067446662766,1739502653.7029126,14.02998661994934,33.37146880274068,1739502653.7029157,14.02998661994934,-0.078,1739502653.7029202,14.02998661994934,-0.003092152578172945,1739502653.7029235,14.02998661994934,-0.21087199992571623,1739502653.7029274,14.02998661994934,-0.0527091399412929,1739502653.7029312,14.02998661994934,2.11191080386473,1739502653.7029347,14.02998661994934,0.0,1739502653.7029388,14.02998661994934,-0.10157929913398345,1739502653.7029426,14.02998661994934,0.03496173063127122,1739502653.702946,14.02998661994934,2.2134901029987133 +1739502653.7287996,14.059986591339111,28.071529645677103,1739502653.7288046,14.059986591339111,-0.05242963851159299,1739502653.7288098,14.059986591339111,27.39349089888209,1739502653.7288153,14.059986591339111,33.791622474544724,1739502653.7288182,14.059986591339111,-0.075,1739502653.7288227,14.059986591339111,-0.00394578287964203,1739502653.728826,14.059986591339111,-0.2192155208178151,1739502653.7288296,14.059986591339111,-0.05144901026064902,1739502653.728833,14.059986591339111,2.097861128002033,1739502653.7288375,14.059986591339111,0.0,1739502653.7288413,14.059986591339111,-0.1058329546633094,1739502653.7288444,14.059986591339111,0.034387075665919024,1739502653.7288473,14.059986591339111,2.202364814440892 +1739502653.743098,14.069986581802368,28.071529645677103,1739502653.743103,14.069986581802368,-0.05242963851159299,1739502653.74311,14.069986581802368,27.39349089888209,1739502653.743115,14.069986581802368,33.791622474544724,1739502653.7431176,14.069986581802368,-0.075,1739502653.7431211,14.069986581802368,-0.00394578287964203,1739502653.7431245,14.069986581802368,-0.2192155208178151,1739502653.7431276,14.069986581802368,-0.05144901026064902,1739502653.7431307,14.069986581802368,2.097861128002033,1739502653.7431338,14.069986581802368,0.0,1739502653.7431374,14.069986581802368,-0.10450368643885888,1739502653.74314,14.069986581802368,0.034387075665919024,1739502653.743143,14.069986581802368,2.202364814440892 +1739502653.7625158,14.089986562728882,28.071529645677103,1739502653.7625194,14.089986562728882,-0.05242963851159299,1739502653.7625246,14.089986562728882,27.39349089888209,1739502653.7625277,14.089986562728882,33.791622474544724,1739502653.7625291,14.089986562728882,-0.075,1739502653.7625318,14.089986562728882,-0.00394578287964203,1739502653.7625334,14.089986562728882,-0.2192155208178151,1739502653.7625353,14.089986562728882,-0.05144901026064902,1739502653.7625372,14.089986562728882,2.097861128002033,1739502653.7625403,14.089986562728882,0.0,1739502653.762542,14.089986562728882,-0.10450368643885888,1739502653.7625442,14.089986562728882,0.034387075665919024,1739502653.762546,14.089986562728882,2.202364814440892 +1739502653.7850034,14.109986543655396,28.071529645677103,1739502653.7850103,14.109986543655396,-0.05242963851159299,1739502653.7850187,14.109986543655396,27.39349089888209,1739502653.7850277,14.109986543655396,33.791622474544724,1739502653.7850335,14.109986543655396,-0.075,1739502653.78504,14.109986543655396,-0.00394578287964203,1739502653.7850454,14.109986543655396,-0.2192155208178151,1739502653.7850509,14.109986543655396,-0.05144901026064902,1739502653.7850564,14.109986543655396,2.097861128002033,1739502653.7850618,14.109986543655396,0.0,1739502653.7850676,14.109986543655396,-0.10450368643885888,1739502653.785073,14.109986543655396,0.034387075665919024,1739502653.7850788,14.109986543655396,2.202364814440892 +1739502653.8021147,14.12998652458191,28.071529645677103,1739502653.8021183,14.12998652458191,-0.05242963851159299,1739502653.8021214,14.12998652458191,27.39349089888209,1739502653.8021245,14.12998652458191,33.791622474544724,1739502653.8021262,14.12998652458191,-0.075,1739502653.8021278,14.12998652458191,-0.00394578287964203,1739502653.8021297,14.12998652458191,-0.2192155208178151,1739502653.802131,14.12998652458191,-0.05144901026064902,1739502653.8021324,14.12998652458191,2.097861128002033,1739502653.8021343,14.12998652458191,0.0,1739502653.8021357,14.12998652458191,-0.10450368643885888,1739502653.8021376,14.12998652458191,0.034387075665919024,1739502653.802139,14.12998652458191,2.202364814440892 +1739502653.821706,14.149986505508423,28.313082490564447,1739502653.8217084,14.149986505508423,-0.04418723745595354,1739502653.8217113,14.149986505508423,27.855598683712042,1739502653.821714,14.149986505508423,34.23096492622931,1739502653.821715,14.149986505508423,-0.07184326507248501,1739502653.8217173,14.149986505508423,-0.004673263888998503,1739502653.8217185,14.149986505508423,-0.22748136556305648,1739502653.82172,14.149986505508423,-0.04987981952846195,1739502653.821721,14.149986505508423,2.0840344186541366,1739502653.8217225,14.149986505508423,0.0,1739502653.821724,14.149986505508423,-0.10806834920564193,1739502653.8217254,14.149986505508423,0.033775444886139885,1739502653.8217268,14.149986505508423,2.190988810014791 +1739502653.8415868,14.169986486434937,28.313082490564447,1739502653.8415897,14.169986486434937,-0.04418723745595354,1739502653.8415926,14.169986486434937,27.855598683712042,1739502653.8415952,14.169986486434937,34.23096492622931,1739502653.8415966,14.169986486434937,-0.07184326507248501,1739502653.8415985,14.169986486434937,-0.004673263888998503,1739502653.8415997,14.169986486434937,-0.22748136556305648,1739502653.8416014,14.169986486434937,-0.04987981952846195,1739502653.8416026,14.169986486434937,2.0840344186541366,1739502653.8416045,14.169986486434937,0.0,1739502653.8416057,14.169986486434937,-0.10695439136065454,1739502653.8416069,14.169986486434937,0.033775444886139885,1739502653.8416085,14.169986486434937,2.190988810014791 +1739502653.861584,14.18998646736145,28.313082490564447,1739502653.861586,14.18998646736145,-0.04418723745595354,1739502653.8615892,14.18998646736145,27.855598683712042,1739502653.8615918,14.18998646736145,34.23096492622931,1739502653.861593,14.18998646736145,-0.07184326507248501,1739502653.861595,14.18998646736145,-0.004673263888998503,1739502653.861596,14.18998646736145,-0.22748136556305648,1739502653.8615975,14.18998646736145,-0.04987981952846195,1739502653.8615987,14.18998646736145,2.0840344186541366,1739502653.8616002,14.18998646736145,0.0,1739502653.8616016,14.18998646736145,-0.10695439136065454,1739502653.8616028,14.18998646736145,0.033775444886139885,1739502653.8616042,14.18998646736145,2.190988810014791 +1739502653.8815098,14.209986448287964,28.313082490564447,1739502653.881512,14.209986448287964,-0.04418723745595354,1739502653.8815308,14.209986448287964,27.855598683712042,1739502653.8815334,14.209986448287964,34.23096492622931,1739502653.8815346,14.209986448287964,-0.07184326507248501,1739502653.8815362,14.209986448287964,-0.004673263888998503,1739502653.8815374,14.209986448287964,-0.22748136556305648,1739502653.8815627,14.209986448287964,-0.04987981952846195,1739502653.8815682,14.209986448287964,2.0840344186541366,1739502653.881572,14.209986448287964,0.0,1739502653.8815744,14.209986448287964,-0.10695439136065454,1739502653.8815768,14.209986448287964,0.033775444886139885,1739502653.881579,14.209986448287964,2.190988810014791 +1739502653.9014149,14.229986429214478,28.313082490564447,1739502653.901417,14.229986429214478,-0.04418723745595354,1739502653.9014199,14.229986429214478,27.855598683712042,1739502653.9014223,14.229986429214478,34.23096492622931,1739502653.9014237,14.229986429214478,-0.07184326507248501,1739502653.9014251,14.229986429214478,-0.004673263888998503,1739502653.9014268,14.229986429214478,-0.22748136556305648,1739502653.901428,14.229986429214478,-0.04987981952846195,1739502653.9014292,14.229986429214478,2.0840344186541366,1739502653.9014308,14.229986429214478,0.0,1739502653.901432,14.229986429214478,-0.10695439136065454,1739502653.9014332,14.229986429214478,0.033775444886139885,1739502653.901435,14.229986429214478,2.190988810014791 +1739502653.9217932,14.249986410140991,28.313082490564447,1739502653.9217958,14.249986410140991,-0.04418723745595354,1739502653.921799,14.249986410140991,27.855598683712042,1739502653.9218016,14.249986410140991,34.23096492622931,1739502653.9218028,14.249986410140991,-0.07184326507248501,1739502653.9218042,14.249986410140991,-0.004673263888998503,1739502653.9218059,14.249986410140991,-0.22748136556305648,1739502653.9218073,14.249986410140991,-0.04987981952846195,1739502653.9218085,14.249986410140991,2.0840344186541366,1739502653.9218102,14.249986410140991,0.0,1739502653.9218113,14.249986410140991,-0.10695439136065454,1739502653.921813,14.249986410140991,0.033775444886139885,1739502653.9218144,14.249986410140991,2.190988810014791 +1739502653.9417229,14.269986391067505,28.553367675768996,1739502653.9417262,14.269986391067505,-0.03613522394303459,1739502653.941729,14.269986391067505,27.885169865519224,1739502653.9417317,14.269986391067505,34.23707175149453,1739502653.941733,14.269986391067505,-0.07179279544219395,1739502653.9417343,14.269986391067505,-0.006273567945023129,1739502653.941736,14.269986391067505,-0.22409671977865242,1739502653.9417372,14.269986391067505,-0.05326857331365473,1739502653.9417386,14.269986391067505,2.0896850399901292,1739502653.94174,14.269986391067505,0.0,1739502653.9417412,14.269986391067505,-0.0816704633415855,1739502653.9417427,14.269986391067505,0.033163814106360746,1739502653.941744,14.269986391067505,2.1792567360181256 +1739502653.9613986,14.289986371994019,28.553367675768996,1739502653.9614007,14.289986371994019,-0.03613522394303459,1739502653.9614038,14.289986371994019,27.885169865519224,1739502653.9614067,14.289986371994019,34.23707175149453,1739502653.9614081,14.289986371994019,-0.07179279544219395,1739502653.9614098,14.289986371994019,-0.006273567945023129,1739502653.961411,14.289986371994019,-0.22409671977865242,1739502653.9614127,14.289986371994019,-0.05326857331365473,1739502653.9614139,14.289986371994019,2.0896850399901292,1739502653.9614158,14.289986371994019,0.0,1739502653.961417,14.289986371994019,-0.08957169602799642,1739502653.9614182,14.289986371994019,0.033163814106360746,1739502653.9614198,14.289986371994019,2.1792567360181256 +1739502653.9813795,14.309986352920532,28.553367675768996,1739502653.9813817,14.309986352920532,-0.03613522394303459,1739502653.9813845,14.309986352920532,27.885169865519224,1739502653.981387,14.309986352920532,34.23707175149453,1739502653.9813883,14.309986352920532,-0.07179279544219395,1739502653.9813898,14.309986352920532,-0.006273567945023129,1739502653.9813914,14.309986352920532,-0.22409671977865242,1739502653.9813926,14.309986352920532,-0.05326857331365473,1739502653.9813938,14.309986352920532,2.0896850399901292,1739502653.9813955,14.309986352920532,0.0,1739502653.9813967,14.309986352920532,-0.08957169602799642,1739502653.981398,14.309986352920532,0.033163814106360746,1739502653.9813993,14.309986352920532,2.1792567360181256 +1739502654.0014405,14.329986333847046,28.553367675768996,1739502654.001443,14.329986333847046,-0.03613522394303459,1739502654.0014467,14.329986333847046,27.885169865519224,1739502654.0014496,14.329986333847046,34.23707175149453,1739502654.0014508,14.329986333847046,-0.07179279544219395,1739502654.0014524,14.329986333847046,-0.006273567945023129,1739502654.0014539,14.329986333847046,-0.22409671977865242,1739502654.0014553,14.329986333847046,-0.05326857331365473,1739502654.0014565,14.329986333847046,2.0896850399901292,1739502654.0014582,14.329986333847046,0.0,1739502654.0014594,14.329986333847046,-0.08957169602799642,1739502654.001461,14.329986333847046,0.033163814106360746,1739502654.0014622,14.329986333847046,2.1792567360181256 +1739502654.021422,14.34998631477356,28.553367675768996,1739502654.021424,14.34998631477356,-0.03613522394303459,1739502654.021427,14.34998631477356,27.885169865519224,1739502654.0214295,14.34998631477356,34.23707175149453,1739502654.0214307,14.34998631477356,-0.07179279544219395,1739502654.0214326,14.34998631477356,-0.006273567945023129,1739502654.021434,14.34998631477356,-0.22409671977865242,1739502654.0214355,14.34998631477356,-0.05326857331365473,1739502654.0214367,14.34998631477356,2.0896850399901292,1739502654.0214381,14.34998631477356,0.0,1739502654.0214396,14.34998631477356,-0.08957169602799642,1739502654.021441,14.34998631477356,0.033163814106360746,1739502654.0214427,14.34998631477356,2.1792567360181256 +1739502654.0414834,14.369986295700073,28.79246247079454,1739502654.0414858,14.369986295700073,-0.02826951048121007,1739502654.0414886,14.369986295700073,28.345220084024955,1739502654.0414915,14.369986295700073,34.67749083656294,1739502654.0414927,14.369986295700073,-0.06965094217764445,1739502654.0414946,14.369986295700073,-0.007031529352639643,1739502654.0414958,14.369986295700073,-0.23289620008389866,1739502654.0414972,14.369986295700073,-0.05163713488038437,1739502654.0414987,14.369986295700073,2.0750261827732657,1739502654.0415003,14.369986295700073,0.0,1739502654.0415018,14.369986295700073,-0.0966224191538419,1739502654.041503,14.369986295700073,0.03255218332658161,1739502654.0415046,14.369986295700073,2.1694452495056504 +1739502654.0614238,14.389986276626587,28.79246247079454,1739502654.0614262,14.389986276626587,-0.02826951048121007,1739502654.061429,14.389986276626587,28.345220084024955,1739502654.0614316,14.389986276626587,34.67749083656294,1739502654.0614328,14.389986276626587,-0.06965094217764445,1739502654.0614345,14.389986276626587,-0.007031529352639643,1739502654.061436,14.389986276626587,-0.23289620008389866,1739502654.0614374,14.389986276626587,-0.05163713488038437,1739502654.0614388,14.389986276626587,2.0750261827732657,1739502654.0614402,14.389986276626587,0.0,1739502654.061442,14.389986276626587,-0.09441906673238476,1739502654.061443,14.389986276626587,0.03255218332658161,1739502654.0614445,14.389986276626587,2.1694452495056504 +1739502654.081442,14.4099862575531,28.79246247079454,1739502654.0814438,14.4099862575531,-0.02826951048121007,1739502654.081447,14.4099862575531,28.345220084024955,1739502654.0814497,14.4099862575531,34.67749083656294,1739502654.081451,14.4099862575531,-0.06965094217764445,1739502654.0814528,14.4099862575531,-0.007031529352639643,1739502654.081454,14.4099862575531,-0.23289620008389866,1739502654.0814557,14.4099862575531,-0.05163713488038437,1739502654.0814567,14.4099862575531,2.0750261827732657,1739502654.081458,14.4099862575531,0.0,1739502654.0814595,14.4099862575531,-0.09441906673238476,1739502654.081461,14.4099862575531,0.03255218332658161,1739502654.0814624,14.4099862575531,2.1694452495056504 +1739502654.1015122,14.429986238479614,28.79246247079454,1739502654.1015146,14.429986238479614,-0.02826951048121007,1739502654.1015177,14.429986238479614,28.345220084024955,1739502654.1015203,14.429986238479614,34.67749083656294,1739502654.101522,14.429986238479614,-0.06965094217764445,1739502654.1015236,14.429986238479614,-0.007031529352639643,1739502654.101525,14.429986238479614,-0.23289620008389866,1739502654.1015265,14.429986238479614,-0.05163713488038437,1739502654.1015277,14.429986238479614,2.0750261827732657,1739502654.1015294,14.429986238479614,0.0,1739502654.1015308,14.429986238479614,-0.09441906673238476,1739502654.1015325,14.429986238479614,0.03255218332658161,1739502654.1015337,14.429986238479614,2.1694452495056504 +1739502654.1214676,14.449986219406128,28.79246247079454,1739502654.12147,14.449986219406128,-0.02826951048121007,1739502654.121473,14.449986219406128,28.345220084024955,1739502654.1214764,14.449986219406128,34.67749083656294,1739502654.1214774,14.449986219406128,-0.06965094217764445,1739502654.1214793,14.449986219406128,-0.007031529352639643,1739502654.1214807,14.449986219406128,-0.23289620008389866,1739502654.1214821,14.449986219406128,-0.05163713488038437,1739502654.1214836,14.449986219406128,2.0750261827732657,1739502654.121485,14.449986219406128,0.0,1739502654.1214864,14.449986219406128,-0.09441906673238476,1739502654.1214879,14.449986219406128,0.03255218332658161,1739502654.1214895,14.449986219406128,2.1694452495056504 +1739502654.1414342,14.469986200332642,28.79246247079454,1739502654.1414366,14.469986200332642,-0.02826951048121007,1739502654.1414397,14.469986200332642,28.345220084024955,1739502654.1414423,14.469986200332642,34.67749083656294,1739502654.1414437,14.469986200332642,-0.06965094217764445,1739502654.1414456,14.469986200332642,-0.007031529352639643,1739502654.1414468,14.469986200332642,-0.23289620008389866,1739502654.1414483,14.469986200332642,-0.05163713488038437,1739502654.1414497,14.469986200332642,2.0750261827732657,1739502654.1414514,14.469986200332642,0.0,1739502654.1414526,14.469986200332642,-0.09441906673238476,1739502654.141454,14.469986200332642,0.03255218332658161,1739502654.1414554,14.469986200332642,2.1694452495056504 +1739502654.1614392,14.489986181259155,29.030455416387014,1739502654.1614416,14.489986181259155,-0.020585760127834973,1739502654.1614444,14.489986181259155,28.37450858383354,1739502654.1614473,14.489986181259155,34.68601635432959,1739502654.1614485,14.489986181259155,-0.06961253894446134,1739502654.1614509,14.489986181259155,-0.008668556722790014,1739502654.1614523,14.489986181259155,-0.22961280021238464,1739502654.1614535,14.489986181259155,-0.05512193196405232,1739502654.161455,14.489986181259155,2.0804838600915843,1739502654.1614566,14.489986181259155,0.0,1739502654.161458,14.489986181259155,-0.07138033245885644,1739502654.1614592,14.489986181259155,0.03194055254680247,1739502654.1614606,14.489986181259155,2.15906380173135 +1739502654.1815028,14.509986162185669,29.030455416387014,1739502654.181505,14.509986162185669,-0.020585760127834973,1739502654.1815083,14.509986162185669,28.37450858383354,1739502654.1815112,14.509986162185669,34.68601635432959,1739502654.181513,14.509986162185669,-0.06961253894446134,1739502654.181515,14.509986162185669,-0.008668556722790014,1739502654.1815166,14.509986162185669,-0.22961280021238464,1739502654.1815178,14.509986162185669,-0.05512193196405232,1739502654.181519,14.509986162185669,2.0804838600915843,1739502654.1815207,14.509986162185669,0.0,1739502654.181522,14.509986162185669,-0.07857994163976567,1739502654.1815236,14.509986162185669,0.03194055254680247,1739502654.1815248,14.509986162185669,2.15906380173135 +1739502654.2016454,14.529986143112183,29.030455416387014,1739502654.2016482,14.529986143112183,-0.020585760127834973,1739502654.201651,14.529986143112183,28.37450858383354,1739502654.201654,14.529986143112183,34.68601635432959,1739502654.2016554,14.529986143112183,-0.06961253894446134,1739502654.201657,14.529986143112183,-0.008668556722790014,1739502654.2016582,14.529986143112183,-0.22961280021238464,1739502654.20166,14.529986143112183,-0.05512193196405232,1739502654.201661,14.529986143112183,2.0804838600915843,1739502654.2016628,14.529986143112183,0.0,1739502654.201664,14.529986143112183,-0.07857994163976567,1739502654.2016652,14.529986143112183,0.03194055254680247,1739502654.2016668,14.529986143112183,2.15906380173135 +1739502654.2215836,14.549986124038696,29.030455416387014,1739502654.2215867,14.549986124038696,-0.020585760127834973,1739502654.221591,14.549986124038696,28.37450858383354,1739502654.221594,14.549986124038696,34.68601635432959,1739502654.2215953,14.549986124038696,-0.06961253894446134,1739502654.2215974,14.549986124038696,-0.008668556722790014,1739502654.2215989,14.549986124038696,-0.22961280021238464,1739502654.2216005,14.549986124038696,-0.05512193196405232,1739502654.221602,14.549986124038696,2.0804838600915843,1739502654.2216043,14.549986124038696,0.0,1739502654.2216058,14.549986124038696,-0.07857994163976567,1739502654.2216074,14.549986124038696,0.03194055254680247,1739502654.2216089,14.549986124038696,2.15906380173135 +1739502654.2425003,14.56998610496521,29.030455416387014,1739502654.242506,14.56998610496521,-0.020585760127834973,1739502654.2425113,14.56998610496521,28.37450858383354,1739502654.2425156,14.56998610496521,34.68601635432959,1739502654.2425177,14.56998610496521,-0.06961253894446134,1739502654.2425215,14.56998610496521,-0.008668556722790014,1739502654.2425241,14.56998610496521,-0.22961280021238464,1739502654.242527,14.56998610496521,-0.05512193196405232,1739502654.2425294,14.56998610496521,2.0804838600915843,1739502654.242532,14.56998610496521,0.0,1739502654.2425349,14.56998610496521,-0.07857994163976567,1739502654.2425375,14.56998610496521,0.03194055254680247,1739502654.2425404,14.56998610496521,2.15906380173135 +1739502654.262639,14.589986085891724,29.267400193838746,1739502654.2626452,14.589986085891724,-0.013086674884858596,1739502654.2626517,14.589986085891724,28.403667789630582,1739502654.262656,14.589986085891724,34.69795918104717,1739502654.2626595,14.589986085891724,-0.06955874242771548,1739502654.2626626,14.589986085891724,-0.010398567111768188,1739502654.2626655,14.589986085891724,-0.2261884009505365,1739502654.262668,14.589986085891724,-0.058889752703781814,1739502654.2626703,14.589986085891724,2.086191200122358,1739502654.2626731,14.589986085891724,0.0,1739502654.2626762,14.589986085891724,-0.057757435086314535,1739502654.2626793,14.589986085891724,0.031262265984093325,1739502654.2626822,14.589986085891724,2.1504556727729724 +1739502654.282396,14.609986066818237,29.267400193838746,1739502654.2824004,14.609986066818237,-0.013086674884858596,1739502654.2824056,14.609986066818237,28.403667789630582,1739502654.2824104,14.609986066818237,34.69795918104717,1739502654.2824128,14.609986066818237,-0.06955874242771548,1739502654.2824156,14.609986066818237,-0.010398567111768188,1739502654.2824183,14.609986066818237,-0.2261884009505365,1739502654.2824202,14.609986066818237,-0.058889752703781814,1739502654.2824223,14.609986066818237,2.086191200122358,1739502654.282425,14.609986066818237,0.0,1739502654.2824273,14.609986066818237,-0.0642644726506143,1739502654.2824302,14.609986066818237,0.031262265984093325,1739502654.2824323,14.609986066818237,2.1504556727729724 +1739502654.3033993,14.629986047744751,29.267400193838746,1739502654.303405,14.629986047744751,-0.013086674884858596,1739502654.3034122,14.629986047744751,28.403667789630582,1739502654.3034165,14.629986047744751,34.69795918104717,1739502654.3034189,14.629986047744751,-0.06955874242771548,1739502654.303422,14.629986047744751,-0.010398567111768188,1739502654.3034246,14.629986047744751,-0.2261884009505365,1739502654.3034277,14.629986047744751,-0.058889752703781814,1739502654.3034294,14.629986047744751,2.086191200122358,1739502654.3034322,14.629986047744751,0.0,1739502654.303435,14.629986047744751,-0.0642644726506143,1739502654.3034382,14.629986047744751,0.031262265984093325,1739502654.3034406,14.629986047744751,2.1504556727729724 +1739502654.3227842,14.649986028671265,29.267400193838746,1739502654.3227882,14.649986028671265,-0.013086674884858596,1739502654.3227935,14.649986028671265,28.403667789630582,1739502654.322798,14.649986028671265,34.69795918104717,1739502654.3228004,14.649986028671265,-0.06955874242771548,1739502654.3228035,14.649986028671265,-0.010398567111768188,1739502654.3228061,14.649986028671265,-0.2261884009505365,1739502654.3228097,14.649986028671265,-0.058889752703781814,1739502654.322812,14.649986028671265,2.086191200122358,1739502654.322815,14.649986028671265,0.0,1739502654.3228176,14.649986028671265,-0.0642644726506143,1739502654.3228204,14.649986028671265,0.031262265984093325,1739502654.3228228,14.649986028671265,2.1504556727729724 +1739502654.343174,14.669986009597778,29.267400193838746,1739502654.3431776,14.669986009597778,-0.013086674884858596,1739502654.3431818,14.669986009597778,28.403667789630582,1739502654.3431857,14.669986009597778,34.69795918104717,1739502654.343187,14.669986009597778,-0.06955874242771548,1739502654.3431895,14.669986009597778,-0.010398567111768188,1739502654.3431914,14.669986009597778,-0.2261884009505365,1739502654.3431926,14.669986009597778,-0.058889752703781814,1739502654.343194,14.669986009597778,2.086191200122358,1739502654.3431962,14.669986009597778,0.0,1739502654.343198,14.669986009597778,-0.0642644726506143,1739502654.3431995,14.669986009597778,0.031262265984093325,1739502654.343201,14.669986009597778,2.1504556727729724 +1739502654.363482,14.689985990524292,29.267400193838746,1739502654.363487,14.689985990524292,-0.013086674884858596,1739502654.363492,14.689985990524292,28.403667789630582,1739502654.3634963,14.689985990524292,34.69795918104717,1739502654.3634984,14.689985990524292,-0.06955874242771548,1739502654.3635008,14.689985990524292,-0.010398567111768188,1739502654.3635027,14.689985990524292,-0.2261884009505365,1739502654.3635046,14.689985990524292,-0.058889752703781814,1739502654.3635063,14.689985990524292,2.086191200122358,1739502654.363509,14.689985990524292,0.0,1739502654.3635113,14.689985990524292,-0.0642644726506143,1739502654.3635137,14.689985990524292,0.031262265984093325,1739502654.3635159,14.689985990524292,2.1504556727729724 +1739502654.3831673,14.709985971450806,29.50349744868285,1739502654.3831933,14.709985971450806,-0.0057906523041566516,1739502654.3832,14.709985971450806,28.78491784773263,1739502654.3832054,14.709985971450806,35.0653908937789,1739502654.3832085,14.709985971450806,-0.0680280455311055,1739502654.3832123,14.709985971450806,-0.011189498027027445,1739502654.383216,14.709985971450806,-0.2314204496019397,1739502654.38322,14.709985971450806,-0.057439436913127445,1739502654.3832238,14.709985971450806,2.077477406157633,1739502654.3832288,14.709985971450806,0.0,1739502654.3832324,14.709985971450806,-0.06689205950833868,1739502654.383236,14.709985971450806,0.030428123429082722,1739502654.3832395,14.709985971450806,2.1435483442345635 +1739502654.4020534,14.72998595237732,29.50349744868285,1739502654.4020572,14.72998595237732,-0.0057906523041566516,1739502654.4020607,14.72998595237732,28.78491784773263,1739502654.4020636,14.72998595237732,35.0653908937789,1739502654.402065,14.72998595237732,-0.0680280455311055,1739502654.4020667,14.72998595237732,-0.011189498027027445,1739502654.4020684,14.72998595237732,-0.2314204496019397,1739502654.40207,14.72998595237732,-0.057439436913127445,1739502654.4020712,14.72998595237732,2.077477406157633,1739502654.4020734,14.72998595237732,0.0,1739502654.402096,14.72998595237732,-0.06607093807693065,1739502654.4020975,14.72998595237732,0.030428123429082722,1739502654.4020991,14.72998595237732,2.1435483442345635 +1739502654.4221191,14.749985933303833,29.50349744868285,1739502654.4221256,14.749985933303833,-0.0057906523041566516,1739502654.4221318,14.749985933303833,28.78491784773263,1739502654.4221375,14.749985933303833,35.0653908937789,1739502654.4221406,14.749985933303833,-0.0680280455311055,1739502654.4221444,14.749985933303833,-0.011189498027027445,1739502654.422148,14.749985933303833,-0.2314204496019397,1739502654.422152,14.749985933303833,-0.057439436913127445,1739502654.4221554,14.749985933303833,2.077477406157633,1739502654.422159,14.749985933303833,0.0,1739502654.4221807,14.749985933303833,-0.06607093807693065,1739502654.4221842,14.749985933303833,0.030428123429082722,1739502654.4221876,14.749985933303833,2.1435483442345635 +1739502654.4420307,14.769985914230347,29.50349744868285,1739502654.4420342,14.769985914230347,-0.0057906523041566516,1739502654.44204,14.769985914230347,28.78491784773263,1739502654.442044,14.769985914230347,35.0653908937789,1739502654.4420457,14.769985914230347,-0.0680280455311055,1739502654.4420483,14.769985914230347,-0.011189498027027445,1739502654.4420502,14.769985914230347,-0.2314204496019397,1739502654.4420526,14.769985914230347,-0.057439436913127445,1739502654.442055,14.769985914230347,2.077477406157633,1739502654.4420571,14.769985914230347,0.0,1739502654.4420593,14.769985914230347,-0.06607093807693065,1739502654.4420617,14.769985914230347,0.030428123429082722,1739502654.4420636,14.769985914230347,2.1435483442345635 +1739502654.4625726,14.78998589515686,29.50349744868285,1739502654.4625766,14.78998589515686,-0.0057906523041566516,1739502654.462582,14.78998589515686,28.78491784773263,1739502654.4625874,14.78998589515686,35.0653908937789,1739502654.4625905,14.78998589515686,-0.0680280455311055,1739502654.4625943,14.78998589515686,-0.011189498027027445,1739502654.4625976,14.78998589515686,-0.2314204496019397,1739502654.4626012,14.78998589515686,-0.057439436913127445,1739502654.4626045,14.78998589515686,2.077477406157633,1739502654.462608,14.78998589515686,0.0,1739502654.4626114,14.78998589515686,-0.06607093807693065,1739502654.4626148,14.78998589515686,0.030428123429082722,1739502654.462618,14.78998589515686,2.1435483442345635 +1739502654.489136,14.809985876083374,29.738820215381054,1739502654.489149,14.809985876083374,0.001280355096076491,1739502654.4891644,14.809985876083374,28.796455734308243,1739502654.4891803,14.809985876083374,35.062476415575624,1739502654.4891891,14.809985876083374,-0.06804261792212189,1739502654.489199,14.809985876083374,-0.013020948869882244,1739502654.489207,14.809985876083374,-0.22669934039865414,1739502654.4892147,14.809985876083374,-0.06141255544464366,1739502654.4892218,14.809985876083374,2.0853386404724046,1739502654.48923,14.809985876083374,0.0,1739502654.4892373,14.809985876083374,-0.044125571653652385,1739502654.4892447,14.809985876083374,0.02957171053815513,1739502654.489255,14.809985876083374,2.1363221436297417 +1739502654.5110624,14.829985857009888,29.738820215381054,1739502654.511071,14.829985857009888,0.001280355096076491,1739502654.511082,14.829985857009888,28.796455734308243,1739502654.5110922,14.829985857009888,35.062476415575624,1739502654.5110977,14.829985857009888,-0.06804261792212189,1739502654.5111036,14.829985857009888,-0.013020948869882244,1739502654.5111089,14.829985857009888,-0.22669934039865414,1739502654.511114,14.829985857009888,-0.06141255544464366,1739502654.5111187,14.829985857009888,2.0853386404724046,1739502654.5111244,14.829985857009888,0.0,1739502654.5111294,14.829985857009888,-0.05098350315733713,1739502654.5111346,14.829985857009888,0.02957171053815513,1739502654.5111403,14.829985857009888,2.1363221436297417 +1739502654.5307837,14.849985837936401,29.738820215381054,1739502654.5307937,14.849985837936401,0.001280355096076491,1739502654.5308046,14.849985837936401,28.796455734308243,1739502654.530815,14.849985837936401,35.062476415575624,1739502654.5308201,14.849985837936401,-0.06804261792212189,1739502654.5308263,14.849985837936401,-0.013020948869882244,1739502654.5308316,14.849985837936401,-0.22669934039865414,1739502654.5308366,14.849985837936401,-0.06141255544464366,1739502654.5308414,14.849985837936401,2.0853386404724046,1739502654.5308473,14.849985837936401,0.0,1739502654.5308523,14.849985837936401,-0.05098350315733713,1739502654.5308576,14.849985837936401,0.02957171053815513,1739502654.5308628,14.849985837936401,2.1363221436297417 +1739502654.5583127,14.869985818862915,29.738820215381054,1739502654.5583222,14.869985818862915,0.001280355096076491,1739502654.5583348,14.869985818862915,28.796455734308243,1739502654.558348,14.869985818862915,35.062476415575624,1739502654.5583558,14.869985818862915,-0.06804261792212189,1739502654.5583656,14.869985818862915,-0.013020948869882244,1739502654.5583744,14.869985818862915,-0.22669934039865414,1739502654.5583835,14.869985818862915,-0.06141255544464366,1739502654.558392,14.869985818862915,2.0853386404724046,1739502654.5584013,14.869985818862915,0.0,1739502654.5584102,14.869985818862915,-0.05098350315733713,1739502654.5584192,14.869985818862915,0.02957171053815513,1739502654.558428,14.869985818862915,2.1363221436297417 +1739502654.5747223,14.899985790252686,29.738820215381054,1739502654.574729,14.899985790252686,0.001280355096076491,1739502654.5747366,14.899985790252686,28.796455734308243,1739502654.5747442,14.899985790252686,35.062476415575624,1739502654.5747476,14.899985790252686,-0.06804261792212189,1739502654.5747523,14.899985790252686,-0.013020948869882244,1739502654.5747561,14.899985790252686,-0.22669934039865414,1739502654.5747595,14.899985790252686,-0.06141255544464366,1739502654.574763,14.899985790252686,2.0853386404724046,1739502654.5747669,14.899985790252686,0.0,1739502654.5747702,14.899985790252686,-0.05098350315733713,1739502654.574774,14.899985790252686,0.02957171053815513,1739502654.5747776,14.899985790252686,2.1363221436297417 +1739502654.5942626,14.9199857711792,29.97344925528266,1739502654.5942686,14.9199857711792,0.00812224933692729,1739502654.594276,14.9199857711792,29.66160922492848,1739502654.5942829,14.9199857711792,35.91672585493815,1739502654.594286,14.9199857711792,-0.06488169447398015,1739502654.5942905,14.9199857711792,-0.012282832749030439,1739502654.5942938,14.9199857711792,-0.24317179177571716,1739502654.5942972,14.9199857711792,-0.05285816254363884,1739502654.5943005,14.9199857711792,2.0580384047822022,1739502654.5943043,14.9199857711792,0.0,1739502654.5943077,14.9199857711792,-0.082771040596157,1739502654.5943112,14.9199857711792,0.028640945272488866,1739502654.5943148,14.9199857711792,2.1308758334157445 +1739502654.6135578,14.939985752105713,29.97344925528266,1739502654.6135614,14.939985752105713,0.00812224933692729,1739502654.613566,14.939985752105713,29.66160922492848,1739502654.6135705,14.939985752105713,35.91672585493815,1739502654.6135726,14.939985752105713,-0.06488169447398015,1739502654.6135752,14.939985752105713,-0.012282832749030439,1739502654.6135774,14.939985752105713,-0.24317179177571716,1739502654.6135795,14.939985752105713,-0.05285816254363884,1739502654.6135817,14.939985752105713,2.0580384047822022,1739502654.613584,14.939985752105713,0.0,1739502654.6135862,14.939985752105713,-0.07283742863354226,1739502654.6135886,14.939985752105713,0.028640945272488866,1739502654.613591,14.939985752105713,2.1308758334157445 +1739502654.6324208,14.959985733032227,29.97344925528266,1739502654.6324239,14.959985733032227,0.00812224933692729,1739502654.6324282,14.959985733032227,29.66160922492848,1739502654.632431,14.959985733032227,35.91672585493815,1739502654.6324325,14.959985733032227,-0.06488169447398015,1739502654.6324341,14.959985733032227,-0.012282832749030439,1739502654.6324358,14.959985733032227,-0.24317179177571716,1739502654.6324372,14.959985733032227,-0.05285816254363884,1739502654.6324384,14.959985733032227,2.0580384047822022,1739502654.6324406,14.959985733032227,0.0,1739502654.632442,14.959985733032227,-0.07283742863354226,1739502654.6324437,14.959985733032227,0.028640945272488866,1739502654.632445,14.959985733032227,2.1308758334157445 +1739502654.6523669,14.97998571395874,29.97344925528266,1739502654.6523695,14.97998571395874,0.00812224933692729,1739502654.6523728,14.97998571395874,29.66160922492848,1739502654.6523752,14.97998571395874,35.91672585493815,1739502654.652377,14.97998571395874,-0.06488169447398015,1739502654.6523786,14.97998571395874,-0.012282832749030439,1739502654.6523802,14.97998571395874,-0.24317179177571716,1739502654.6523814,14.97998571395874,-0.05285816254363884,1739502654.6523826,14.97998571395874,2.0580384047822022,1739502654.6523843,14.97998571395874,0.0,1739502654.6523855,14.97998571395874,-0.07283742863354226,1739502654.6523871,14.97998571395874,0.028640945272488866,1739502654.6523883,14.97998571395874,2.1308758334157445 +1739502654.6722476,14.999985694885254,29.97344925528266,1739502654.6722498,14.999985694885254,0.00812224933692729,1739502654.6722524,14.999985694885254,29.66160922492848,1739502654.672255,14.999985694885254,35.91672585493815,1739502654.6722562,14.999985694885254,-0.06488169447398015,1739502654.672258,14.999985694885254,-0.012282832749030439,1739502654.672259,14.999985694885254,-0.24317179177571716,1739502654.6722603,14.999985694885254,-0.05285816254363884,1739502654.6722617,14.999985694885254,2.0580384047822022,1739502654.6722631,14.999985694885254,0.0,1739502654.6722643,14.999985694885254,-0.07283742863354226,1739502654.672266,14.999985694885254,0.028640945272488866,1739502654.6722672,14.999985694885254,2.1308758334157445 +1739502654.6924746,15.019985675811768,29.97344925528266,1739502654.6924777,15.019985675811768,0.00812224933692729,1739502654.6924818,15.019985675811768,29.66160922492848,1739502654.6924846,15.019985675811768,35.91672585493815,1739502654.6924858,15.019985675811768,-0.06488169447398015,1739502654.6924877,15.019985675811768,-0.012282832749030439,1739502654.6924891,15.019985675811768,-0.24317179177571716,1739502654.6924908,15.019985675811768,-0.05285816254363884,1739502654.6924922,15.019985675811768,2.0580384047822022,1739502654.6924944,15.019985675811768,0.0,1739502654.6924958,15.019985675811768,-0.07283742863354226,1739502654.6924975,15.019985675811768,0.028640945272488866,1739502654.692499,15.019985675811768,2.1308758334157445 +1739502654.712411,15.039985656738281,30.207334167869917,1739502654.712413,15.039985656738281,0.014723013834773369,1739502654.712416,15.039985656738281,29.68944813029086,1739502654.7124188,15.039985656738281,35.928220489009085,1739502654.71242,15.039985656738281,-0.06482669622483693,1739502654.7124217,15.039985656738281,-0.013904241254743465,1739502654.712423,15.039985656738281,-0.2379831702543439,1739502654.712425,15.039985656738281,-0.0558273135313432,1739502654.712426,15.039985656738281,2.066598865173549,1739502654.7124279,15.039985656738281,0.0,1739502654.712429,15.039985656738281,-0.04849919556189867,1739502654.7124305,15.039985656738281,0.027702744769348735,1739502654.712432,15.039985656738281,2.122703763557024 +1739502654.7322886,15.059985637664795,30.207334167869917,1739502654.7322907,15.059985637664795,0.014723013834773369,1739502654.7322934,15.059985637664795,29.68944813029086,1739502654.7322962,15.059985637664795,35.928220489009085,1739502654.7322974,15.059985637664795,-0.06482669622483693,1739502654.7322998,15.059985637664795,-0.013904241254743465,1739502654.732301,15.059985637664795,-0.2379831702543439,1739502654.7323027,15.059985637664795,-0.0558273135313432,1739502654.7323039,15.059985637664795,2.066598865173549,1739502654.732306,15.059985637664795,0.0,1739502654.7323072,15.059985637664795,-0.056104898383474655,1739502654.7323086,15.059985637664795,0.027702744769348735,1739502654.73231,15.059985637664795,2.122703763557024 +1739502654.752314,15.079985618591309,30.207334167869917,1739502654.7523167,15.079985618591309,0.014723013834773369,1739502654.7523196,15.079985618591309,29.68944813029086,1739502654.752323,15.079985618591309,35.928220489009085,1739502654.7523243,15.079985618591309,-0.06482669622483693,1739502654.7523263,15.079985618591309,-0.013904241254743465,1739502654.7523277,15.079985618591309,-0.2379831702543439,1739502654.752329,15.079985618591309,-0.0558273135313432,1739502654.7523308,15.079985618591309,2.066598865173549,1739502654.7523327,15.079985618591309,0.0,1739502654.752334,15.079985618591309,-0.056104898383474655,1739502654.7523355,15.079985618591309,0.027702744769348735,1739502654.7523372,15.079985618591309,2.122703763557024 +1739502654.7723825,15.099985599517822,30.207334167869917,1739502654.7723856,15.099985599517822,0.014723013834773369,1739502654.7723885,15.099985599517822,29.68944813029086,1739502654.7723913,15.099985599517822,35.928220489009085,1739502654.7723927,15.099985599517822,-0.06482669622483693,1739502654.7723947,15.099985599517822,-0.013904241254743465,1739502654.772396,15.099985599517822,-0.2379831702543439,1739502654.7723975,15.099985599517822,-0.0558273135313432,1739502654.7723992,15.099985599517822,2.066598865173549,1739502654.7724006,15.099985599517822,0.0,1739502654.7724018,15.099985599517822,-0.056104898383474655,1739502654.7724037,15.099985599517822,0.027702744769348735,1739502654.7724051,15.099985599517822,2.122703763557024 +1739502654.7923234,15.119985580444336,30.207334167869917,1739502654.7923253,15.119985580444336,0.014723013834773369,1739502654.7923281,15.119985580444336,29.68944813029086,1739502654.7923307,15.119985580444336,35.928220489009085,1739502654.7923322,15.119985580444336,-0.06482669622483693,1739502654.792334,15.119985580444336,-0.013904241254743465,1739502654.7923355,15.119985580444336,-0.2379831702543439,1739502654.792337,15.119985580444336,-0.0558273135313432,1739502654.7923381,15.119985580444336,2.066598865173549,1739502654.7923398,15.119985580444336,0.0,1739502654.792341,15.119985580444336,-0.056104898383474655,1739502654.7923424,15.119985580444336,0.027702744769348735,1739502654.7923443,15.119985580444336,2.122703763557024 +1739502654.8123305,15.13998556137085,30.44043408423429,1739502654.8123333,15.13998556137085,0.021082743776418944,1739502654.8123364,15.13998556137085,29.717193380068164,1739502654.8123393,15.13998556137085,35.94366462166115,1739502654.8123405,15.13998556137085,-0.06475280085329596,1739502654.8123422,15.13998556137085,-0.015596036635458712,1739502654.8123438,15.13998556137085,-0.2330786755207802,1739502654.8123453,15.13998556137085,-0.05908354605973651,1739502654.8123467,15.13998556137085,2.0747232918344722,1739502654.8123484,15.13998556137085,0.0,1739502654.81235,15.13998556137085,-0.03534140589371316,1739502654.8123515,15.13998556137085,0.026764544266208605,1739502654.8123531,15.13998556137085,2.1165532933854907 +1739502654.8322425,15.159985542297363,30.44043408423429,1739502654.8322456,15.159985542297363,0.021082743776418944,1739502654.8322492,15.159985542297363,29.717193380068164,1739502654.8322518,15.159985542297363,35.94366462166115,1739502654.8322532,15.159985542297363,-0.06475280085329596,1739502654.832255,15.159985542297363,-0.015596036635458712,1739502654.8322566,15.159985542297363,-0.2330786755207802,1739502654.832258,15.159985542297363,-0.05908354605973651,1739502654.8322594,15.159985542297363,2.0747232918344722,1739502654.832261,15.159985542297363,0.0,1739502654.8322628,15.159985542297363,-0.04183000155101846,1739502654.8322642,15.159985542297363,0.026764544266208605,1739502654.8322656,15.159985542297363,2.1165532933854907 +1739502654.8521667,15.179985523223877,30.44043408423429,1739502654.8521693,15.179985523223877,0.021082743776418944,1739502654.8521721,15.179985523223877,29.717193380068164,1739502654.8521748,15.179985523223877,35.94366462166115,1739502654.852176,15.179985523223877,-0.06475280085329596,1739502654.8521776,15.179985523223877,-0.015596036635458712,1739502654.852179,15.179985523223877,-0.2330786755207802,1739502654.8521802,15.179985523223877,-0.05908354605973651,1739502654.8521814,15.179985523223877,2.0747232918344722,1739502654.852183,15.179985523223877,0.0,1739502654.8521843,15.179985523223877,-0.04183000155101846,1739502654.8521855,15.179985523223877,0.026764544266208605,1739502654.8521872,15.179985523223877,2.1165532933854907 +1739502654.8722394,15.19998550415039,30.44043408423429,1739502654.8722427,15.19998550415039,0.021082743776418944,1739502654.8722458,15.19998550415039,29.717193380068164,1739502654.8722486,15.19998550415039,35.94366462166115,1739502654.87225,15.19998550415039,-0.06475280085329596,1739502654.8722525,15.19998550415039,-0.015596036635458712,1739502654.872254,15.19998550415039,-0.2330786755207802,1739502654.8722556,15.19998550415039,-0.05908354605973651,1739502654.8722568,15.19998550415039,2.0747232918344722,1739502654.8722587,15.19998550415039,0.0,1739502654.8722599,15.19998550415039,-0.04183000155101846,1739502654.8722613,15.19998550415039,0.026764544266208605,1739502654.8722627,15.19998550415039,2.1165532933854907 +1739502654.8922398,15.219985485076904,30.44043408423429,1739502654.8922424,15.219985485076904,0.021082743776418944,1739502654.8922453,15.219985485076904,29.717193380068164,1739502654.8922482,15.219985485076904,35.94366462166115,1739502654.8922493,15.219985485076904,-0.06475280085329596,1739502654.8922508,15.219985485076904,-0.015596036635458712,1739502654.8922522,15.219985485076904,-0.2330786755207802,1739502654.8922534,15.219985485076904,-0.05908354605973651,1739502654.8922548,15.219985485076904,2.0747232918344722,1739502654.8922563,15.219985485076904,0.0,1739502654.8922575,15.219985485076904,-0.04183000155101846,1739502654.8922591,15.219985485076904,0.026764544266208605,1739502654.8922603,15.219985485076904,2.1165532933854907 +1739502654.9131734,15.239985466003418,30.44043408423429,1739502654.913176,15.239985466003418,0.021082743776418944,1739502654.9131794,15.239985466003418,29.717193380068164,1739502654.9131823,15.239985466003418,35.94366462166115,1739502654.9131837,15.239985466003418,-0.06475280085329596,1739502654.9131854,15.239985466003418,-0.015596036635458712,1739502654.9131868,15.239985466003418,-0.2330786755207802,1739502654.913188,15.239985466003418,-0.05908354605973651,1739502654.9131894,15.239985466003418,2.0747232918344722,1739502654.9131908,15.239985466003418,0.0,1739502654.9131923,15.239985466003418,-0.04183000155101846,1739502654.9131937,15.239985466003418,0.026764544266208605,1739502654.9131954,15.239985466003418,2.1165532933854907 +1739502654.9323938,15.259985446929932,30.672957114563587,1739502654.932397,15.259985446929932,0.02720841099401028,1739502654.9324002,15.259985446929932,29.95543511454539,1739502654.9324028,15.259985446929932,36.17300158565084,1739502654.9324043,15.259985446929932,-0.064,1739502654.932406,15.259985446929932,-0.01658169347385257,1739502654.9324076,15.259985446929932,-0.23320824364179646,1739502654.9324093,15.259985446929932,-0.05918299722000368,1739502654.9324107,15.259985446929932,2.0745082485809236,1739502654.9324124,15.259985446929932,0.0,1739502654.9324136,15.259985446929932,-0.03566790296419207,1739502654.9324152,15.259985446929932,0.025826343763068475,1739502654.932417,15.259985446929932,2.112101808616058 +1739502654.952161,15.279985427856445,30.672957114563587,1739502654.9521646,15.279985427856445,0.02720841099401028,1739502654.952168,15.279985427856445,29.95543511454539,1739502654.952171,15.279985427856445,36.17300158565084,1739502654.9521725,15.279985427856445,-0.064,1739502654.9521744,15.279985427856445,-0.01658169347385257,1739502654.9521759,15.279985427856445,-0.23320824364179646,1739502654.9521775,15.279985427856445,-0.05918299722000368,1739502654.9521787,15.279985427856445,2.0745082485809236,1739502654.9521804,15.279985427856445,0.0,1739502654.9521818,15.279985427856445,-0.03759356003513448,1739502654.9521832,15.279985427856445,0.025826343763068475,1739502654.952185,15.279985427856445,2.112101808616058 +1739502654.9722757,15.299985408782959,30.672957114563587,1739502654.9722786,15.299985408782959,0.02720841099401028,1739502654.972282,15.299985408782959,29.95543511454539,1739502654.9722846,15.299985408782959,36.17300158565084,1739502654.9722862,15.299985408782959,-0.064,1739502654.9722884,15.299985408782959,-0.01658169347385257,1739502654.9722896,15.299985408782959,-0.23320824364179646,1739502654.972291,15.299985408782959,-0.05918299722000368,1739502654.9722924,15.299985408782959,2.0745082485809236,1739502654.972294,15.299985408782959,0.0,1739502654.972296,15.299985408782959,-0.03759356003513448,1739502654.9722974,15.299985408782959,0.025826343763068475,1739502654.972299,15.299985408782959,2.112101808616058 +1739502654.9922953,15.319985389709473,30.672957114563587,1739502654.9922974,15.319985389709473,0.02720841099401028,1739502654.9923003,15.319985389709473,29.95543511454539,1739502654.9923031,15.319985389709473,36.17300158565084,1739502654.9923043,15.319985389709473,-0.064,1739502654.9923062,15.319985389709473,-0.01658169347385257,1739502654.9923077,15.319985389709473,-0.23320824364179646,1739502654.992309,15.319985389709473,-0.05918299722000368,1739502654.9923103,15.319985389709473,2.0745082485809236,1739502654.9923117,15.319985389709473,0.0,1739502654.9923131,15.319985389709473,-0.03759356003513448,1739502654.9923143,15.319985389709473,0.025826343763068475,1739502654.992316,15.319985389709473,2.112101808616058 +1739502655.012218,15.339985370635986,30.672957114563587,1739502655.0122209,15.339985370635986,0.02720841099401028,1739502655.0122244,15.339985370635986,29.95543511454539,1739502655.0122273,15.339985370635986,36.17300158565084,1739502655.012229,15.339985370635986,-0.064,1739502655.0122306,15.339985370635986,-0.01658169347385257,1739502655.0122323,15.339985370635986,-0.23320824364179646,1739502655.0122335,15.339985370635986,-0.05918299722000368,1739502655.0122347,15.339985370635986,2.0745082485809236,1739502655.0122366,15.339985370635986,0.0,1739502655.0122378,15.339985370635986,-0.03759356003513448,1739502655.0122395,15.339985370635986,0.025826343763068475,1739502655.0122406,15.339985370635986,2.112101808616058 +1739502655.03218,15.3599853515625,30.905006689060208,1739502655.0321822,15.3599853515625,0.03310374722712428,1739502655.032185,15.3599853515625,30.296695447289068,1739502655.0321877,15.3599853515625,36.50602621915368,1739502655.0321891,15.3599853515625,-0.063,1739502655.0321908,15.3599853515625,-0.01715657608534001,1739502655.0321922,15.3599853515625,-0.2354585703217487,1739502655.0321934,15.3599853515625,-0.05761828190715506,1739502655.0321949,15.3599853515625,2.0707769512362026,1739502655.0321963,15.3599853515625,0.0,1739502655.0321977,15.3599853515625,-0.03703403608218735,1739502655.032199,15.3599853515625,0.024888143259928344,1739502655.0322003,15.3599853515625,2.1079858386683274 +1739502655.0522888,15.379985332489014,30.905006689060208,1739502655.0522916,15.379985332489014,0.03310374722712428,1739502655.0522954,15.379985332489014,30.296695447289068,1739502655.0522983,15.379985332489014,36.50602621915368,1739502655.0522997,15.379985332489014,-0.063,1739502655.0523014,15.379985332489014,-0.01715657608534001,1739502655.052303,15.379985332489014,-0.2354585703217487,1739502655.0523047,15.379985332489014,-0.05761828190715506,1739502655.052306,15.379985332489014,2.0707769512362026,1739502655.0523074,15.379985332489014,0.0,1739502655.052309,15.379985332489014,-0.037208887432124804,1739502655.0523102,15.379985332489014,0.024888143259928344,1739502655.052312,15.379985332489014,2.1079858386683274 +1739502655.0721447,15.399985313415527,30.905006689060208,1739502655.0721467,15.399985313415527,0.03310374722712428,1739502655.0721495,15.399985313415527,30.296695447289068,1739502655.0721524,15.399985313415527,36.50602621915368,1739502655.0721536,15.399985313415527,-0.063,1739502655.0721552,15.399985313415527,-0.01715657608534001,1739502655.0721567,15.399985313415527,-0.2354585703217487,1739502655.072158,15.399985313415527,-0.05761828190715506,1739502655.0721593,15.399985313415527,2.0707769512362026,1739502655.0721607,15.399985313415527,0.0,1739502655.0721624,15.399985313415527,-0.037208887432124804,1739502655.0721638,15.399985313415527,0.024888143259928344,1739502655.072165,15.399985313415527,2.1079858386683274 +1739502655.0923474,15.419985294342041,30.905006689060208,1739502655.0923502,15.419985294342041,0.03310374722712428,1739502655.0923536,15.419985294342041,30.296695447289068,1739502655.092357,15.419985294342041,36.50602621915368,1739502655.092358,15.419985294342041,-0.063,1739502655.09236,15.419985294342041,-0.01715657608534001,1739502655.0923615,15.419985294342041,-0.2354585703217487,1739502655.0923626,15.419985294342041,-0.05761828190715506,1739502655.092364,15.419985294342041,2.0707769512362026,1739502655.0923655,15.419985294342041,0.0,1739502655.0923672,15.419985294342041,-0.037208887432124804,1739502655.0923688,15.419985294342041,0.024888143259928344,1739502655.0923703,15.419985294342041,2.1079858386683274 +1739502655.1121662,15.439985275268555,30.905006689060208,1739502655.112168,15.439985275268555,0.03310374722712428,1739502655.112171,15.439985275268555,30.296695447289068,1739502655.1121738,15.439985275268555,36.50602621915368,1739502655.1121755,15.439985275268555,-0.063,1739502655.1121771,15.439985275268555,-0.01715657608534001,1739502655.112179,15.439985275268555,-0.2354585703217487,1739502655.1121802,15.439985275268555,-0.05761828190715506,1739502655.1121814,15.439985275268555,2.0707769512362026,1739502655.112183,15.439985275268555,0.0,1739502655.1121843,15.439985275268555,-0.037208887432124804,1739502655.112186,15.439985275268555,0.024888143259928344,1739502655.1121871,15.439985275268555,2.1079858386683274 +1739502655.1321394,15.459985256195068,30.905006689060208,1739502655.1321416,15.459985256195068,0.03310374722712428,1739502655.1321442,15.459985256195068,30.296695447289068,1739502655.1321468,15.459985256195068,36.50602621915368,1739502655.1321483,15.459985256195068,-0.063,1739502655.13215,15.459985256195068,-0.01715657608534001,1739502655.1321514,15.459985256195068,-0.2354585703217487,1739502655.1321526,15.459985256195068,-0.05761828190715506,1739502655.1321537,15.459985256195068,2.0707769512362026,1739502655.1321554,15.459985256195068,0.0,1739502655.1321566,15.459985256195068,-0.037208887432124804,1739502655.132158,15.459985256195068,0.024888143259928344,1739502655.1321595,15.459985256195068,2.1079858386683274 +1739502655.1524582,15.479985237121582,31.13661205810854,1739502655.1524615,15.479985237121582,0.03877037066310596,1739502655.1524653,15.479985237121582,30.324262152829252,1739502655.1524682,15.479985237121582,36.52545150864181,1739502655.1524699,15.479985237121582,-0.063,1739502655.1524715,15.479985237121582,-0.018883151948827292,1739502655.1524734,15.479985237121582,-0.2307912426880233,1739502655.152475,15.479985237121582,-0.061006388811240944,1739502655.1524763,15.479985237121582,2.078523399912115,1739502655.1524785,15.479985237121582,0.0,1739502655.1524796,15.479985237121582,-0.020020290743063475,1739502655.1524816,15.479985237121582,0.023949942756788214,1739502655.1524837,15.479985237121582,2.1039151306423007 +1739502655.1722443,15.499985218048096,31.13661205810854,1739502655.1722467,15.499985218048096,0.03877037066310596,1739502655.1722496,15.499985218048096,30.324262152829252,1739502655.1722524,15.499985218048096,36.52545150864181,1739502655.1722538,15.499985218048096,-0.063,1739502655.172256,15.499985218048096,-0.018883151948827292,1739502655.172258,15.499985218048096,-0.2307912426880233,1739502655.172259,15.499985218048096,-0.061006388811240944,1739502655.1722605,15.499985218048096,2.078523399912115,1739502655.1722624,15.499985218048096,0.0,1739502655.1722639,15.499985218048096,-0.025391730730185635,1739502655.1722655,15.499985218048096,0.023949942756788214,1739502655.172267,15.499985218048096,2.1039151306423007 +1739502655.1927004,15.51998519897461,31.13661205810854,1739502655.1927059,15.51998519897461,0.03877037066310596,1739502655.1927106,15.51998519897461,30.324262152829252,1739502655.1927137,15.51998519897461,36.52545150864181,1739502655.1927161,15.51998519897461,-0.063,1739502655.1927183,15.51998519897461,-0.018883151948827292,1739502655.1927204,15.51998519897461,-0.2307912426880233,1739502655.1927223,15.51998519897461,-0.061006388811240944,1739502655.1927242,15.51998519897461,2.078523399912115,1739502655.1927264,15.51998519897461,0.0,1739502655.192728,15.51998519897461,-0.025391730730185635,1739502655.1927302,15.51998519897461,0.023949942756788214,1739502655.192732,15.51998519897461,2.1039151306423007 +1739502655.2123978,15.539985179901123,31.13661205810854,1739502655.2124007,15.539985179901123,0.03877037066310596,1739502655.212404,15.539985179901123,30.324262152829252,1739502655.212407,15.539985179901123,36.52545150864181,1739502655.2124083,15.539985179901123,-0.063,1739502655.2124102,15.539985179901123,-0.018883151948827292,1739502655.2124119,15.539985179901123,-0.2307912426880233,1739502655.2124138,15.539985179901123,-0.061006388811240944,1739502655.2124152,15.539985179901123,2.078523399912115,1739502655.2124166,15.539985179901123,0.0,1739502655.2124183,15.539985179901123,-0.025391730730185635,1739502655.21242,15.539985179901123,0.023949942756788214,1739502655.212422,15.539985179901123,2.1039151306423007 +1739502655.2323914,15.559985160827637,31.13661205810854,1739502655.2323942,15.559985160827637,0.03877037066310596,1739502655.2323973,15.559985160827637,30.324262152829252,1739502655.2324002,15.559985160827637,36.52545150864181,1739502655.2324018,15.559985160827637,-0.063,1739502655.2324038,15.559985160827637,-0.018883151948827292,1739502655.2324052,15.559985160827637,-0.2307912426880233,1739502655.2324069,15.559985160827637,-0.061006388811240944,1739502655.232408,15.559985160827637,2.078523399912115,1739502655.2324102,15.559985160827637,0.0,1739502655.2324114,15.559985160827637,-0.025391730730185635,1739502655.2324128,15.559985160827637,0.023949942756788214,1739502655.2324145,15.559985160827637,2.1039151306423007 +1739502655.252472,15.57998514175415,31.367837159519063,1739502655.2524748,15.57998514175415,0.04421061830649986,1739502655.2524784,15.57998514175415,30.767125566987865,1739502655.2524817,15.57998514175415,36.96273542380738,1739502655.2524834,15.57998514175415,-0.06155010797179716,1739502655.2524853,15.57998514175415,-0.018900814093220804,1739502655.2524874,15.57998514175415,-0.2344697194187723,1739502655.2524889,15.57998514175415,-0.057498333382937875,1739502655.2524903,15.57998514175415,2.0724157510886974,1739502655.252492,15.57998514175415,0.0,1739502655.2524936,15.57998514175415,-0.03022169303438858,1739502655.252495,15.57998514175415,0.023011742253648083,1739502655.2524967,15.57998514175415,2.101128079913406 +1739502655.2723618,15.599985122680664,31.367837159519063,1739502655.2723646,15.599985122680664,0.04421061830649986,1739502655.272368,15.599985122680664,30.767125566987865,1739502655.272371,15.599985122680664,36.96273542380738,1739502655.2723725,15.599985122680664,-0.06155010797179716,1739502655.2723746,15.599985122680664,-0.018900814093220804,1739502655.272376,15.599985122680664,-0.2344697194187723,1739502655.2723775,15.599985122680664,-0.057498333382937875,1739502655.2723792,15.599985122680664,2.0724157510886974,1739502655.2723806,15.599985122680664,0.0,1739502655.2723823,15.599985122680664,-0.028712328824708866,1739502655.2723837,15.599985122680664,0.023011742253648083,1739502655.2723854,15.599985122680664,2.101128079913406 +1739502655.2923594,15.619985103607178,31.367837159519063,1739502655.2923641,15.619985103607178,0.04421061830649986,1739502655.2923675,15.619985103607178,30.767125566987865,1739502655.2923708,15.619985103607178,36.96273542380738,1739502655.2923722,15.619985103607178,-0.06155010797179716,1739502655.2923741,15.619985103607178,-0.018900814093220804,1739502655.2923756,15.619985103607178,-0.2344697194187723,1739502655.292377,15.619985103607178,-0.057498333382937875,1739502655.2923787,15.619985103607178,2.0724157510886974,1739502655.29238,15.619985103607178,0.0,1739502655.2923818,15.619985103607178,-0.028712328824708866,1739502655.2923834,15.619985103607178,0.023011742253648083,1739502655.292385,15.619985103607178,2.101128079913406 +1739502655.3123944,15.639985084533691,31.367837159519063,1739502655.3123972,15.639985084533691,0.04421061830649986,1739502655.3124006,15.639985084533691,30.767125566987865,1739502655.3124037,15.639985084533691,36.96273542380738,1739502655.3124053,15.639985084533691,-0.06155010797179716,1739502655.3124073,15.639985084533691,-0.018900814093220804,1739502655.312409,15.639985084533691,-0.2344697194187723,1739502655.3124104,15.639985084533691,-0.057498333382937875,1739502655.3124118,15.639985084533691,2.0724157510886974,1739502655.3124137,15.639985084533691,0.0,1739502655.312415,15.639985084533691,-0.028712328824708866,1739502655.3124166,15.639985084533691,0.023011742253648083,1739502655.3124177,15.639985084533691,2.101128079913406 +1739502655.3322687,15.659985065460205,31.367837159519063,1739502655.332272,15.659985065460205,0.04421061830649986,1739502655.3322752,15.659985065460205,30.767125566987865,1739502655.3322785,15.659985065460205,36.96273542380738,1739502655.3322802,15.659985065460205,-0.06155010797179716,1739502655.3322818,15.659985065460205,-0.018900814093220804,1739502655.3322835,15.659985065460205,-0.2344697194187723,1739502655.332285,15.659985065460205,-0.057498333382937875,1739502655.3322864,15.659985065460205,2.0724157510886974,1739502655.3322883,15.659985065460205,0.0,1739502655.3322895,15.659985065460205,-0.028712328824708866,1739502655.3322911,15.659985065460205,0.023011742253648083,1739502655.3322926,15.659985065460205,2.101128079913406 +1739502655.3523915,15.679985046386719,31.367837159519063,1739502655.3523946,15.679985046386719,0.04421061830649986,1739502655.3523984,15.679985046386719,30.767125566987865,1739502655.3524015,15.679985046386719,36.96273542380738,1739502655.352403,15.679985046386719,-0.06155010797179716,1739502655.352405,15.679985046386719,-0.018900814093220804,1739502655.3524067,15.679985046386719,-0.2344697194187723,1739502655.3524084,15.679985046386719,-0.057498333382937875,1739502655.3524098,15.679985046386719,2.0724157510886974,1739502655.3524117,15.679985046386719,0.0,1739502655.3524134,15.679985046386719,-0.028712328824708866,1739502655.352415,15.679985046386719,0.023011742253648083,1739502655.3524165,15.679985046386719,2.101128079913406 +1739502655.3724737,15.699985027313232,31.598741995766048,1739502655.3724766,15.699985027313232,0.04942658433025482,1739502655.37248,15.699985027313232,30.794146648794786,1739502655.372483,15.699985027313232,36.98340835472053,1739502655.3724844,15.699985027313232,-0.06139697515021831,1739502655.3724864,15.699985027313232,-0.02057841807090563,1739502655.3724883,15.699985027313232,-0.22964556745414724,1739502655.3724897,15.699985027313232,-0.06079366294550088,1739502655.3724911,15.699985027313232,2.080429323432292,1739502655.3724928,15.699985027313232,0.0,1739502655.3724942,15.699985027313232,-0.012439794207731218,1739502655.3724964,15.699985027313232,0.022073541750507953,1739502655.372498,15.699985027313232,2.0979542880419264 +1739502655.3925576,15.719985008239746,31.598741995766048,1739502655.3925612,15.719985008239746,0.04942658433025482,1739502655.392565,15.719985008239746,30.794146648794786,1739502655.3925683,15.719985008239746,36.98340835472053,1739502655.3925695,15.719985008239746,-0.06139697515021831,1739502655.3925717,15.719985008239746,-0.02057841807090563,1739502655.392573,15.719985008239746,-0.22964556745414724,1739502655.3925748,15.719985008239746,-0.06079366294550088,1739502655.3925762,15.719985008239746,2.080429323432292,1739502655.392578,15.719985008239746,0.0,1739502655.3925793,15.719985008239746,-0.017524964609634264,1739502655.3925812,15.719985008239746,0.022073541750507953,1739502655.3925827,15.719985008239746,2.0979542880419264 +1739502655.4123952,15.73998498916626,31.598741995766048,1739502655.412398,15.73998498916626,0.04942658433025482,1739502655.4124014,15.73998498916626,30.794146648794786,1739502655.4124045,15.73998498916626,36.98340835472053,1739502655.4124057,15.73998498916626,-0.06139697515021831,1739502655.4124076,15.73998498916626,-0.02057841807090563,1739502655.412409,15.73998498916626,-0.22964556745414724,1739502655.4124103,15.73998498916626,-0.06079366294550088,1739502655.4124117,15.73998498916626,2.080429323432292,1739502655.4124134,15.73998498916626,0.0,1739502655.412415,15.73998498916626,-0.017524964609634264,1739502655.4124165,15.73998498916626,0.022073541750507953,1739502655.4124181,15.73998498916626,2.0979542880419264 +1739502655.4326339,15.759984970092773,31.598741995766048,1739502655.4326406,15.759984970092773,0.04942658433025482,1739502655.4326448,15.759984970092773,30.794146648794786,1739502655.4326494,15.759984970092773,36.98340835472053,1739502655.432653,15.759984970092773,-0.06139697515021831,1739502655.4326558,15.759984970092773,-0.02057841807090563,1739502655.432659,15.759984970092773,-0.22964556745414724,1739502655.4326615,15.759984970092773,-0.06079366294550088,1739502655.4326646,15.759984970092773,2.080429323432292,1739502655.432668,15.759984970092773,0.0,1739502655.4326696,15.759984970092773,-0.017524964609634264,1739502655.432692,15.759984970092773,0.022073541750507953,1739502655.4326952,15.759984970092773,2.0979542880419264 +1739502655.4524255,15.779984951019287,31.598741995766048,1739502655.4524288,15.779984951019287,0.04942658433025482,1739502655.4524322,15.779984951019287,30.794146648794786,1739502655.4524353,15.779984951019287,36.98340835472053,1739502655.4524364,15.779984951019287,-0.06139697515021831,1739502655.4524386,15.779984951019287,-0.02057841807090563,1739502655.4524403,15.779984951019287,-0.22964556745414724,1739502655.452442,15.779984951019287,-0.06079366294550088,1739502655.4524431,15.779984951019287,2.080429323432292,1739502655.452445,15.779984951019287,0.0,1739502655.4524462,15.779984951019287,-0.017524964609634264,1739502655.4524477,15.779984951019287,0.022073541750507953,1739502655.4524493,15.779984951019287,2.0979542880419264 +1739502655.4727397,15.7999849319458,31.82936455629971,1739502655.4727435,15.7999849319458,0.054419686825117886,1739502655.472747,15.7999849319458,31.026844390349652,1739502655.472751,15.7999849319458,37.212252598167495,1739502655.4727526,15.7999849319458,-0.06094110496625001,1739502655.4727547,15.7999849319458,-0.021427741847285423,1739502655.4727566,15.7999849319458,-0.22909573244988157,1739502655.4727583,15.7999849319458,-0.06068604867486609,1739502655.47276,15.7999849319458,2.081344639019293,1739502655.4727619,15.7999849319458,0.0,1739502655.4727635,15.7999849319458,-0.013392208948666879,1739502655.4727654,15.7999849319458,0.021135341247367823,1739502655.4727669,15.7999849319458,2.096028334958777 +1739502655.4930515,15.819984912872314,31.82936455629971,1739502655.4930549,15.819984912872314,0.054419686825117886,1739502655.4930592,15.819984912872314,31.026844390349652,1739502655.493063,15.819984912872314,37.212252598167495,1739502655.4930646,15.819984912872314,-0.06094110496625001,1739502655.493067,15.819984912872314,-0.021427741847285423,1739502655.4930692,15.819984912872314,-0.22909573244988157,1739502655.4930708,15.819984912872314,-0.06068604867486609,1739502655.4930727,15.819984912872314,2.081344639019293,1739502655.4930747,15.819984912872314,0.0,1739502655.4930766,15.819984912872314,-0.014683695939484043,1739502655.4930785,15.819984912872314,0.021135341247367823,1739502655.4930804,15.819984912872314,2.096028334958777 +1739502655.522764,15.839984893798828,31.82936455629971,1739502655.522773,15.839984893798828,0.054419686825117886,1739502655.5227833,15.839984893798828,31.026844390349652,1739502655.5227935,15.839984893798828,37.212252598167495,1739502655.5227983,15.839984893798828,-0.06094110496625001,1739502655.5228047,15.839984893798828,-0.021427741847285423,1739502655.5228097,15.839984893798828,-0.22909573244988157,1739502655.5228148,15.839984893798828,-0.06068604867486609,1739502655.5228193,15.839984893798828,2.081344639019293,1739502655.5228252,15.839984893798828,0.0,1739502655.52283,15.839984893798828,-0.014683695939484043,1739502655.5228355,15.839984893798828,0.021135341247367823,1739502655.5228403,15.839984893798828,2.096028334958777 +1739502655.5358462,15.859984874725342,31.82936455629971,1739502655.535854,15.859984874725342,0.054419686825117886,1739502655.5358648,15.859984874725342,31.026844390349652,1739502655.5358753,15.859984874725342,37.212252598167495,1739502655.5358799,15.859984874725342,-0.06094110496625001,1739502655.535886,15.859984874725342,-0.021427741847285423,1739502655.5358913,15.859984874725342,-0.22909573244988157,1739502655.535896,15.859984874725342,-0.06068604867486609,1739502655.5359004,15.859984874725342,2.081344639019293,1739502655.535906,15.859984874725342,0.0,1739502655.5359108,15.859984874725342,-0.014683695939484043,1739502655.5359163,15.859984874725342,0.021135341247367823,1739502655.535921,15.859984874725342,2.096028334958777 +1739502655.561356,15.879984855651855,31.82936455629971,1739502655.561366,15.879984855651855,0.054419686825117886,1739502655.5613794,15.879984855651855,31.026844390349652,1739502655.5613904,15.879984855651855,37.212252598167495,1739502655.5613956,15.879984855651855,-0.06094110496625001,1739502655.561403,15.879984855651855,-0.021427741847285423,1739502655.561431,15.879984855651855,-0.22909573244988157,1739502655.5614386,15.879984855651855,-0.06068604867486609,1739502655.5614448,15.879984855651855,2.081344639019293,1739502655.5614507,15.879984855651855,0.0,1739502655.5614574,15.879984855651855,-0.014683695939484043,1739502655.561462,15.879984855651855,0.021135341247367823,1739502655.5614698,15.879984855651855,2.096028334958777 +1739502655.5810828,15.89998483657837,31.82936455629971,1739502655.5810883,15.89998483657837,0.054419686825117886,1739502655.5810945,15.89998483657837,31.026844390349652,1739502655.5810997,15.89998483657837,37.212252598167495,1739502655.5811026,15.89998483657837,-0.06094110496625001,1739502655.581106,15.89998483657837,-0.021427741847285423,1739502655.5811088,15.89998483657837,-0.22909573244988157,1739502655.581112,15.89998483657837,-0.06068604867486609,1739502655.5811143,15.89998483657837,2.081344639019293,1739502655.5811174,15.89998483657837,0.0,1739502655.58112,15.89998483657837,-0.014683695939484043,1739502655.5811229,15.89998483657837,0.021135341247367823,1739502655.5811257,15.89998483657837,2.096028334958777 +1739502655.6016822,15.919984817504883,32.059800149762985,1739502655.6016865,15.919984817504883,0.05919244723601924,1739502655.6016922,15.919984817504883,31.172579395841357,1739502655.6016972,15.919984817504883,37.35482198811375,1739502655.6017,15.919984817504883,-0.06035197525572831,1739502655.6017032,15.919984817504883,-0.02257292252147225,1739502655.601706,15.919984817504883,-0.2264570713661043,1739502655.6017087,15.919984817504883,-0.06199097523670717,1739502655.6017108,15.919984817504883,2.0857428500220947,1739502655.601714,15.919984817504883,0.0,1739502655.6017168,15.919984817504883,-0.005984914913514595,1739502655.6017194,15.919984817504883,0.020197140744227692,1739502655.601722,15.919984817504883,2.0944461357885276 +1739502655.6187727,15.939984798431396,32.059800149762985,1739502655.6187758,15.939984798431396,0.05919244723601924,1739502655.6187797,15.939984798431396,31.172579395841357,1739502655.6187832,15.939984798431396,37.35482198811375,1739502655.6187851,15.939984798431396,-0.06035197525572831,1739502655.618787,15.939984798431396,-0.02257292252147225,1739502655.618789,15.939984798431396,-0.2264570713661043,1739502655.6187906,15.939984798431396,-0.06199097523670717,1739502655.6187925,15.939984798431396,2.0857428500220947,1739502655.6187944,15.939984798431396,0.0,1739502655.6187963,15.939984798431396,-0.008703285766432867,1739502655.618798,15.939984798431396,0.020197140744227692,1739502655.6188,15.939984798431396,2.0944461357885276 +1739502655.6375632,15.95998477935791,32.059800149762985,1739502655.6375659,15.95998477935791,0.05919244723601924,1739502655.6375692,15.95998477935791,31.172579395841357,1739502655.6375723,15.95998477935791,37.35482198811375,1739502655.637574,15.95998477935791,-0.06035197525572831,1739502655.6375759,15.95998477935791,-0.02257292252147225,1739502655.6375775,15.95998477935791,-0.2264570713661043,1739502655.637579,15.95998477935791,-0.06199097523670717,1739502655.6375804,15.95998477935791,2.0857428500220947,1739502655.6375823,15.95998477935791,0.0,1739502655.6375837,15.95998477935791,-0.008703285766432867,1739502655.6375854,15.95998477935791,0.020197140744227692,1739502655.6375868,15.95998477935791,2.0944461357885276 +1739502655.6578631,15.979984760284424,32.059800149762985,1739502655.6578658,15.979984760284424,0.05919244723601924,1739502655.6578686,15.979984760284424,31.172579395841357,1739502655.6578712,15.979984760284424,37.35482198811375,1739502655.6578727,15.979984760284424,-0.06035197525572831,1739502655.6578743,15.979984760284424,-0.02257292252147225,1739502655.6578758,15.979984760284424,-0.2264570713661043,1739502655.657877,15.979984760284424,-0.06199097523670717,1739502655.6578782,15.979984760284424,2.0857428500220947,1739502655.6578798,15.979984760284424,0.0,1739502655.6578813,15.979984760284424,-0.008703285766432867,1739502655.6578827,15.979984760284424,0.020197140744227692,1739502655.6578841,15.979984760284424,2.0944461357885276 +1739502655.6772997,15.999984741210938,32.059800149762985,1739502655.6773016,15.999984741210938,0.05919244723601924,1739502655.6773045,15.999984741210938,31.172579395841357,1739502655.6773071,15.999984741210938,37.35482198811375,1739502655.677308,15.999984741210938,-0.06035197525572831,1739502655.6773098,15.999984741210938,-0.02257292252147225,1739502655.677311,15.999984741210938,-0.2264570713661043,1739502655.6773124,15.999984741210938,-0.06199097523670717,1739502655.6773133,15.999984741210938,2.0857428500220947,1739502655.6773148,15.999984741210938,0.0,1739502655.677316,15.999984741210938,-0.008703285766432867,1739502655.6773171,15.999984741210938,0.020197140744227692,1739502655.6773183,15.999984741210938,2.0944461357885276 +1739502655.6975687,16.01998472213745,32.290089571891365,1739502655.6975713,16.01998472213745,0.06374166713262852,1739502655.6975741,16.01998472213745,31.564913917569047,1739502655.6975768,16.01998472213745,37.74512271789703,1739502655.697578,16.01998472213745,-0.059,1739502655.6975799,16.01998472213745,-0.022496831151484938,1739502655.697581,16.01998472213745,-0.22744615488662046,1739502655.6975822,16.01998472213745,-0.05866375430368597,1739502655.6975837,16.01998472213745,2.0840931236902276,1739502655.697585,16.01998472213745,0.0,1739502655.6975865,16.01998472213745,-0.009627009117479195,1739502655.697588,16.01998472213745,0.01919943307295354,1739502655.6975892,16.01998472213745,2.093431469071242 +1739502655.7173057,16.039984703063965,32.290089571891365,1739502655.7173078,16.039984703063965,0.06374166713262852,1739502655.7173107,16.039984703063965,31.564913917569047,1739502655.7173135,16.039984703063965,37.74512271789703,1739502655.7173147,16.039984703063965,-0.059,1739502655.7173164,16.039984703063965,-0.022496831151484938,1739502655.7173176,16.039984703063965,-0.22744615488662046,1739502655.717319,16.039984703063965,-0.05866375430368597,1739502655.7173202,16.039984703063965,2.0840931236902276,1739502655.7173216,16.039984703063965,0.0,1739502655.717323,16.039984703063965,-0.009338345381014523,1739502655.7173243,16.039984703063965,0.01919943307295354,1739502655.717326,16.039984703063965,2.093431469071242 +1739502655.7372997,16.05998468399048,32.290089571891365,1739502655.737302,16.05998468399048,0.06374166713262852,1739502655.7373052,16.05998468399048,31.564913917569047,1739502655.7373075,16.05998468399048,37.74512271789703,1739502655.7373095,16.05998468399048,-0.059,1739502655.737311,16.05998468399048,-0.022496831151484938,1739502655.7373126,16.05998468399048,-0.22744615488662046,1739502655.7373166,16.05998468399048,-0.05866375430368597,1739502655.7373211,16.05998468399048,2.0840931236902276,1739502655.7373254,16.05998468399048,0.0,1739502655.7373295,16.05998468399048,-0.009338345381014523,1739502655.7373319,16.05998468399048,0.01919943307295354,1739502655.7373338,16.05998468399048,2.093431469071242 +1739502655.7572732,16.079984664916992,32.290089571891365,1739502655.757275,16.079984664916992,0.06374166713262852,1739502655.7572782,16.079984664916992,31.564913917569047,1739502655.7572808,16.079984664916992,37.74512271789703,1739502655.757282,16.079984664916992,-0.059,1739502655.757284,16.079984664916992,-0.022496831151484938,1739502655.7572854,16.079984664916992,-0.22744615488662046,1739502655.7572865,16.079984664916992,-0.05866375430368597,1739502655.757288,16.079984664916992,2.0840931236902276,1739502655.7572894,16.079984664916992,0.0,1739502655.7572908,16.079984664916992,-0.009338345381014523,1739502655.757292,16.079984664916992,0.01919943307295354,1739502655.7572935,16.079984664916992,2.093431469071242 +1739502655.7772782,16.099984645843506,32.290089571891365,1739502655.7772808,16.099984645843506,0.06374166713262852,1739502655.777284,16.099984645843506,31.564913917569047,1739502655.7772863,16.099984645843506,37.74512271789703,1739502655.777288,16.099984645843506,-0.059,1739502655.7772894,16.099984645843506,-0.022496831151484938,1739502655.7772908,16.099984645843506,-0.22744615488662046,1739502655.7772923,16.099984645843506,-0.05866375430368597,1739502655.7772937,16.099984645843506,2.0840931236902276,1739502655.7772949,16.099984645843506,0.0,1739502655.777296,16.099984645843506,-0.009338345381014523,1739502655.7772977,16.099984645843506,0.01919943307295354,1739502655.777299,16.099984645843506,2.093431469071242 +1739502655.7972755,16.11998462677002,32.290089571891365,1739502655.7972777,16.11998462677002,0.06374166713262852,1739502655.7972806,16.11998462677002,31.564913917569047,1739502655.7972834,16.11998462677002,37.74512271789703,1739502655.7972846,16.11998462677002,-0.059,1739502655.797286,16.11998462677002,-0.022496831151484938,1739502655.7972875,16.11998462677002,-0.22744615488662046,1739502655.7972887,16.11998462677002,-0.05866375430368597,1739502655.79729,16.11998462677002,2.0840931236902276,1739502655.7972918,16.11998462677002,0.0,1739502655.797293,16.11998462677002,-0.009338345381014523,1739502655.7972944,16.11998462677002,0.01919943307295354,1739502655.7972956,16.11998462677002,2.093431469071242 +1739502655.8174152,16.139984607696533,32.52027485063812,1739502655.8174186,16.139984607696533,0.06805488355333367,1739502655.8174224,16.139984607696533,32.28012203552065,1739502655.8174293,16.139984607696533,38.45826806203078,1739502655.8174324,16.139984607696533,-0.057333831587551315,1739502655.817436,16.139984607696533,-0.02111320756321241,1739502655.817439,16.139984607696533,-0.2333112642874401,1739502655.817441,16.139984607696533,-0.05079049296523609,1739502655.8174436,16.139984607696533,2.0743372818829307,1739502655.8174467,16.139984607696533,0.0,1739502655.8174486,16.139984607696533,-0.022033048606218728,1739502655.8174524,16.139984607696533,0.018179410213629132,1739502655.8174555,16.139984607696533,2.0924032331302413 +1739502655.8372629,16.159984588623047,32.52027485063812,1739502655.8372655,16.159984588623047,0.06805488355333367,1739502655.8372679,16.159984588623047,32.28012203552065,1739502655.8372707,16.159984588623047,38.45826806203078,1739502655.8372722,16.159984588623047,-0.057333831587551315,1739502655.8372738,16.159984588623047,-0.02111320756321241,1739502655.837275,16.159984588623047,-0.2333112642874401,1739502655.8372765,16.159984588623047,-0.05079049296523609,1739502655.8372777,16.159984588623047,2.0743372818829307,1739502655.8372793,16.159984588623047,0.0,1739502655.8372805,16.159984588623047,-0.018065951247310696,1739502655.8372817,16.159984588623047,0.018179410213629132,1739502655.8372831,16.159984588623047,2.0924032331302413 +1739502655.8574264,16.17998456954956,32.52027485063812,1739502655.857429,16.17998456954956,0.06805488355333367,1739502655.8574321,16.17998456954956,32.28012203552065,1739502655.8574345,16.17998456954956,38.45826806203078,1739502655.8574362,16.17998456954956,-0.057333831587551315,1739502655.8574376,16.17998456954956,-0.02111320756321241,1739502655.8574393,16.17998456954956,-0.2333112642874401,1739502655.8574407,16.17998456954956,-0.05079049296523609,1739502655.8574421,16.17998456954956,2.0743372818829307,1739502655.8574438,16.17998456954956,0.0,1739502655.8574455,16.17998456954956,-0.018065951247310696,1739502655.857447,16.17998456954956,0.018179410213629132,1739502655.8574483,16.17998456954956,2.0924032331302413 +1739502655.877433,16.199984550476074,32.52027485063812,1739502655.8774357,16.199984550476074,0.06805488355333367,1739502655.877439,16.199984550476074,32.28012203552065,1739502655.8774424,16.199984550476074,38.45826806203078,1739502655.8774438,16.199984550476074,-0.057333831587551315,1739502655.877446,16.199984550476074,-0.02111320756321241,1739502655.8774478,16.199984550476074,-0.2333112642874401,1739502655.8774495,16.199984550476074,-0.05079049296523609,1739502655.8774512,16.199984550476074,2.0743372818829307,1739502655.877453,16.199984550476074,0.0,1739502655.8774548,16.199984550476074,-0.018065951247310696,1739502655.8774567,16.199984550476074,0.018179410213629132,1739502655.877458,16.199984550476074,2.0924032331302413 +1739502655.8973584,16.219984531402588,32.52027485063812,1739502655.8973608,16.219984531402588,0.06805488355333367,1739502655.897364,16.219984531402588,32.28012203552065,1739502655.8973668,16.219984531402588,38.45826806203078,1739502655.8973684,16.219984531402588,-0.057333831587551315,1739502655.89737,16.219984531402588,-0.02111320756321241,1739502655.8973715,16.219984531402588,-0.2333112642874401,1739502655.8973732,16.219984531402588,-0.05079049296523609,1739502655.8973744,16.219984531402588,2.0743372818829307,1739502655.8973763,16.219984531402588,0.0,1739502655.8973777,16.219984531402588,-0.018065951247310696,1739502655.8973794,16.219984531402588,0.018179410213629132,1739502655.8973808,16.219984531402588,2.0924032331302413 +1739502655.9177237,16.2399845123291,32.75030606930743,1739502655.9177268,16.2399845123291,0.07213050731426218,1739502655.9177303,16.2399845123291,32.65783394531403,1739502655.9177337,16.2399845123291,38.83202852844316,1739502655.9177353,16.2399845123291,-0.059143309975288244,1739502655.9177377,16.2399845123291,-0.021581622075049465,1739502655.9177396,16.2399845123291,-0.23560800155974052,1739502655.917741,16.2399845123291,-0.04889419610381168,1739502655.9177427,16.2399845123291,2.070529415021612,1739502655.9177446,16.2399845123291,0.0,1739502655.9177465,16.2399845123291,-0.020739990079637585,1739502655.9177482,16.2399845123291,0.017159387354304723,1739502655.9177501,16.2399845123291,2.0904337674182605 +1739502655.9379225,16.259984493255615,32.75030606930743,1739502655.9379256,16.259984493255615,0.07213050731426218,1739502655.9379299,16.259984493255615,32.65783394531403,1739502655.937934,16.259984493255615,38.83202852844316,1739502655.9379358,16.259984493255615,-0.059143309975288244,1739502655.9379385,16.259984493255615,-0.021581622075049465,1739502655.9379406,16.259984493255615,-0.23560800155974052,1739502655.9379423,16.259984493255615,-0.04889419610381168,1739502655.9379442,16.259984493255615,2.070529415021612,1739502655.9379463,16.259984493255615,0.0,1739502655.9379485,16.259984493255615,-0.019904352396648672,1739502655.9379501,16.259984493255615,0.017159387354304723,1739502655.9379523,16.259984493255615,2.0904337674182605 +1739502655.958528,16.27998447418213,32.75030606930743,1739502655.9585316,16.27998447418213,0.07213050731426218,1739502655.958536,16.27998447418213,32.65783394531403,1739502655.9585402,16.27998447418213,38.83202852844316,1739502655.958542,16.27998447418213,-0.059143309975288244,1739502655.9585445,16.27998447418213,-0.021581622075049465,1739502655.9585464,16.27998447418213,-0.23560800155974052,1739502655.9585483,16.27998447418213,-0.04889419610381168,1739502655.95855,16.27998447418213,2.070529415021612,1739502655.9585526,16.27998447418213,0.0,1739502655.9585543,16.27998447418213,-0.019904352396648672,1739502655.9585564,16.27998447418213,0.017159387354304723,1739502655.9585586,16.27998447418213,2.0904337674182605 +1739502655.977759,16.299984455108643,32.75030606930743,1739502655.9777622,16.299984455108643,0.07213050731426218,1739502655.9777665,16.299984455108643,32.65783394531403,1739502655.9777703,16.299984455108643,38.83202852844316,1739502655.9777722,16.299984455108643,-0.059143309975288244,1739502655.9777749,16.299984455108643,-0.021581622075049465,1739502655.977777,16.299984455108643,-0.23560800155974052,1739502655.977779,16.299984455108643,-0.04889419610381168,1739502655.9777808,16.299984455108643,2.070529415021612,1739502655.977783,16.299984455108643,0.0,1739502655.9777849,16.299984455108643,-0.019904352396648672,1739502655.9777868,16.299984455108643,0.017159387354304723,1739502655.977789,16.299984455108643,2.0904337674182605 +1739502655.9985197,16.319984436035156,32.75030606930743,1739502655.998523,16.319984436035156,0.07213050731426218,1739502655.998527,16.319984436035156,32.65783394531403,1739502655.9985309,16.319984436035156,38.83202852844316,1739502655.9985328,16.319984436035156,-0.059143309975288244,1739502655.9985354,16.319984436035156,-0.021581622075049465,1739502655.9985375,16.319984436035156,-0.23560800155974052,1739502655.9985392,16.319984436035156,-0.04889419610381168,1739502655.998541,16.319984436035156,2.070529415021612,1739502655.9985435,16.319984436035156,0.0,1739502655.9985456,16.319984436035156,-0.019904352396648672,1739502655.9985478,16.319984436035156,0.017159387354304723,1739502655.9985497,16.319984436035156,2.0904337674182605 +1739502656.0178056,16.33998441696167,32.75030606930743,1739502656.017809,16.33998441696167,0.07213050731426218,1739502656.0178127,16.33998441696167,32.65783394531403,1739502656.0178168,16.33998441696167,38.83202852844316,1739502656.017819,16.33998441696167,-0.059143309975288244,1739502656.017821,16.33998441696167,-0.021581622075049465,1739502656.0178232,16.33998441696167,-0.23560800155974052,1739502656.0178251,16.33998441696167,-0.04889419610381168,1739502656.017827,16.33998441696167,2.070529415021612,1739502656.0178292,16.33998441696167,0.0,1739502656.017831,16.33998441696167,-0.019904352396648672,1739502656.0178332,16.33998441696167,0.017159387354304723,1739502656.0178354,16.33998441696167,2.0904337674182605 +1739502656.0378318,16.359984397888184,32.98011098646312,1739502656.0378356,16.359984397888184,0.07596764746495133,1739502656.0378394,16.359984397888184,32.70425837571963,1739502656.0378435,16.359984397888184,38.87405561507705,1739502656.0378456,16.359984397888184,-0.059810406588524476,1739502656.037848,16.359984397888184,-0.02303279912304372,1739502656.03785,16.359984397888184,-0.23088076183577075,1739502656.037852,16.359984397888184,-0.05101108815681943,1739502656.037854,16.359984397888184,2.078374551127439,1739502656.0378563,16.359984397888184,0.0,1739502656.0378582,16.359984397888184,-0.005299023026284153,1739502656.0378604,16.359984397888184,0.016139364494980313,1739502656.0378625,16.359984397888184,2.088237742574464 +1739502656.0580459,16.379984378814697,32.98011098646312,1739502656.0580494,16.379984378814697,0.07596764746495133,1739502656.0580537,16.379984378814697,32.70425837571963,1739502656.0580578,16.379984378814697,38.87405561507705,1739502656.0580595,16.379984378814697,-0.059810406588524476,1739502656.058062,16.379984378814697,-0.02303279912304372,1739502656.0580642,16.379984378814697,-0.23088076183577075,1739502656.0580661,16.379984378814697,-0.05101108815681943,1739502656.0580683,16.379984378814697,2.078374551127439,1739502656.0580702,16.379984378814697,0.0,1739502656.0580723,16.379984378814697,-0.009863191447025077,1739502656.0580747,16.379984378814697,0.016139364494980313,1739502656.0580766,16.379984378814697,2.088237742574464 +1739502656.078568,16.39998435974121,32.98011098646312,1739502656.0785718,16.39998435974121,0.07596764746495133,1739502656.0785766,16.39998435974121,32.70425837571963,1739502656.078581,16.39998435974121,38.87405561507705,1739502656.0785832,16.39998435974121,-0.059810406588524476,1739502656.078586,16.39998435974121,-0.02303279912304372,1739502656.0785885,16.39998435974121,-0.23088076183577075,1739502656.0785904,16.39998435974121,-0.05101108815681943,1739502656.0785928,16.39998435974121,2.078374551127439,1739502656.0785954,16.39998435974121,0.0,1739502656.0785975,16.39998435974121,-0.009863191447025077,1739502656.0786,16.39998435974121,0.016139364494980313,1739502656.0786026,16.39998435974121,2.088237742574464 +1739502656.099267,16.419984340667725,32.98011098646312,1739502656.0992706,16.419984340667725,0.07596764746495133,1739502656.0992754,16.419984340667725,32.70425837571963,1739502656.0992799,16.419984340667725,38.87405561507705,1739502656.099282,16.419984340667725,-0.059810406588524476,1739502656.0992846,16.419984340667725,-0.02303279912304372,1739502656.0992868,16.419984340667725,-0.23088076183577075,1739502656.0992892,16.419984340667725,-0.05101108815681943,1739502656.099291,16.419984340667725,2.078374551127439,1739502656.0992937,16.419984340667725,0.0,1739502656.0992959,16.419984340667725,-0.009863191447025077,1739502656.0992982,16.419984340667725,0.016139364494980313,1739502656.0993004,16.419984340667725,2.088237742574464 +1739502656.118825,16.43998432159424,32.98011098646312,1739502656.1188288,16.43998432159424,0.07596764746495133,1739502656.1188343,16.43998432159424,32.70425837571963,1739502656.1188388,16.43998432159424,38.87405561507705,1739502656.118841,16.43998432159424,-0.059810406588524476,1739502656.1188433,16.43998432159424,-0.02303279912304372,1739502656.1188457,16.43998432159424,-0.23088076183577075,1739502656.118848,16.43998432159424,-0.05101108815681943,1739502656.11885,16.43998432159424,2.078374551127439,1739502656.1188526,16.43998432159424,0.0,1739502656.118855,16.43998432159424,-0.009863191447025077,1739502656.1188571,16.43998432159424,0.016139364494980313,1739502656.1188593,16.43998432159424,2.088237742574464 +1739502656.1388085,16.459984302520752,33.209732747748575,1739502656.1388128,16.459984302520752,0.07956743782865949,1739502656.1388175,16.459984302520752,32.75064557128965,1739502656.1388218,16.459984302520752,38.91826342178535,1739502656.1388242,16.459984302520752,-0.06051211780611655,1739502656.138827,16.459984302520752,-0.024533712391812002,1739502656.1388292,16.459984302520752,-0.22636948246609231,1739502656.1388316,16.459984302520752,-0.05331179081302315,1739502656.1388338,16.459984302520752,2.0858890054802264,1739502656.1388361,16.459984302520752,0.0,1739502656.1388385,16.459984302520752,0.002647887758946057,1739502656.138841,16.459984302520752,0.015119341635655915,1739502656.138843,16.459984302520752,2.087150832536555 +1739502656.1600454,16.479984283447266,33.209732747748575,1739502656.1600497,16.479984283447266,0.07956743782865949,1739502656.1600554,16.479984283447266,32.75064557128965,1739502656.1600602,16.479984283447266,38.91826342178535,1739502656.1600626,16.479984283447266,-0.06051211780611655,1739502656.1600652,16.479984283447266,-0.024533712391812002,1739502656.1600676,16.479984283447266,-0.22636948246609231,1739502656.1600697,16.479984283447266,-0.05331179081302315,1739502656.1600718,16.479984283447266,2.0858890054802264,1739502656.1600747,16.479984283447266,0.0,1739502656.160077,16.479984283447266,-0.0012618270563287126,1739502656.1600797,16.479984283447266,0.015119341635655915,1739502656.1600819,16.479984283447266,2.087150832536555 +1739502656.178332,16.49998426437378,33.209732747748575,1739502656.1783361,16.49998426437378,0.07956743782865949,1739502656.1783412,16.49998426437378,32.75064557128965,1739502656.1783457,16.49998426437378,38.91826342178535,1739502656.178348,16.49998426437378,-0.06051211780611655,1739502656.1783512,16.49998426437378,-0.024533712391812002,1739502656.1783533,16.49998426437378,-0.22636948246609231,1739502656.1783555,16.49998426437378,-0.05331179081302315,1739502656.1783578,16.49998426437378,2.0858890054802264,1739502656.1783602,16.49998426437378,0.0,1739502656.1783626,16.49998426437378,-0.0012618270563287126,1739502656.1783652,16.49998426437378,0.015119341635655915,1739502656.1783674,16.49998426437378,2.087150832536555 +1739502656.199012,16.519984245300293,33.209732747748575,1739502656.1990159,16.519984245300293,0.07956743782865949,1739502656.1990206,16.519984245300293,32.75064557128965,1739502656.199025,16.519984245300293,38.91826342178535,1739502656.1990275,16.519984245300293,-0.06051211780611655,1739502656.19903,16.519984245300293,-0.024533712391812002,1739502656.1990323,16.519984245300293,-0.22636948246609231,1739502656.1990347,16.519984245300293,-0.05331179081302315,1739502656.1990366,16.519984245300293,2.0858890054802264,1739502656.1990392,16.519984245300293,0.0,1739502656.1990414,16.519984245300293,-0.0012618270563287126,1739502656.1990438,16.519984245300293,0.015119341635655915,1739502656.1990461,16.519984245300293,2.087150832536555 +1739502656.2184005,16.539984226226807,33.209732747748575,1739502656.218405,16.539984226226807,0.07956743782865949,1739502656.21841,16.539984226226807,32.75064557128965,1739502656.2184145,16.539984226226807,38.91826342178535,1739502656.2184172,16.539984226226807,-0.06051211780611655,1739502656.21842,16.539984226226807,-0.024533712391812002,1739502656.2184222,16.539984226226807,-0.22636948246609231,1739502656.2184248,16.539984226226807,-0.05331179081302315,1739502656.218427,16.539984226226807,2.0858890054802264,1739502656.2184293,16.539984226226807,0.0,1739502656.2184317,16.539984226226807,-0.0012618270563287126,1739502656.218434,16.539984226226807,0.015119341635655915,1739502656.2184362,16.539984226226807,2.087150832536555 +1739502656.238926,16.55998420715332,33.209732747748575,1739502656.2389297,16.55998420715332,0.07956743782865949,1739502656.2389343,16.55998420715332,32.75064557128965,1739502656.2389388,16.55998420715332,38.91826342178535,1739502656.238941,16.55998420715332,-0.06051211780611655,1739502656.238944,16.55998420715332,-0.024533712391812002,1739502656.2389462,16.55998420715332,-0.22636948246609231,1739502656.2389486,16.55998420715332,-0.05331179081302315,1739502656.2389507,16.55998420715332,2.0858890054802264,1739502656.238953,16.55998420715332,0.0,1739502656.2389555,16.55998420715332,-0.0012618270563287126,1739502656.238958,16.55998420715332,0.015119341635655915,1739502656.23896,16.55998420715332,2.087150832536555 +1739502656.2592509,16.579984188079834,33.43928591044376,1739502656.2592545,16.579984188079834,0.08293194074320098,1739502656.2592592,16.579984188079834,32.797018674657,1739502656.2592638,16.579984188079834,38.96434108279615,1739502656.2592661,16.579984188079834,-0.06124350925073255,1739502656.2592688,16.579984188079834,-0.026088922893328564,1739502656.2592714,16.579984188079834,-0.2220580530620056,1739502656.2592738,16.579984188079834,-0.05582243208756451,1739502656.2592757,16.579984188079834,2.0930959577953416,1739502656.2592783,16.579984188079834,0.0,1739502656.2592804,16.579984188079834,0.009431661700285414,1739502656.2592826,16.579984188079834,0.014099318776331525,1739502656.259285,16.579984188079834,2.087006013522499 +1739502656.278856,16.599984169006348,33.43928591044376,1739502656.27886,16.599984169006348,0.08293194074320098,1739502656.2788649,16.599984169006348,32.797018674657,1739502656.2788694,16.599984169006348,38.96434108279615,1739502656.2788718,16.599984169006348,-0.06124350925073255,1739502656.2788749,16.599984169006348,-0.026088922893328564,1739502656.2788773,16.599984169006348,-0.2220580530620056,1739502656.2788792,16.599984169006348,-0.05582243208756451,1739502656.2788818,16.599984169006348,2.0930959577953416,1739502656.2788844,16.599984169006348,0.0,1739502656.2788866,16.599984169006348,0.006089944272842818,1739502656.278889,16.599984169006348,0.014099318776331525,1739502656.2788913,16.599984169006348,2.087006013522499 +1739502656.299059,16.61998414993286,33.43928591044376,1739502656.2990625,16.61998414993286,0.08293194074320098,1739502656.2990675,16.61998414993286,32.797018674657,1739502656.299072,16.61998414993286,38.96434108279615,1739502656.299074,16.61998414993286,-0.06124350925073255,1739502656.2990768,16.61998414993286,-0.026088922893328564,1739502656.2990794,16.61998414993286,-0.2220580530620056,1739502656.2990816,16.61998414993286,-0.05582243208756451,1739502656.2990837,16.61998414993286,2.0930959577953416,1739502656.2990863,16.61998414993286,0.0,1739502656.2990887,16.61998414993286,0.006089944272842818,1739502656.2990909,16.61998414993286,0.014099318776331525,1739502656.2990932,16.61998414993286,2.087006013522499 +1739502656.3188906,16.639984130859375,33.43928591044376,1739502656.3188944,16.639984130859375,0.08293194074320098,1739502656.318899,16.639984130859375,32.797018674657,1739502656.3189034,16.639984130859375,38.96434108279615,1739502656.3189058,16.639984130859375,-0.06124350925073255,1739502656.3189087,16.639984130859375,-0.026088922893328564,1739502656.318911,16.639984130859375,-0.2220580530620056,1739502656.318913,16.639984130859375,-0.05582243208756451,1739502656.3189151,16.639984130859375,2.0930959577953416,1739502656.318918,16.639984130859375,0.0,1739502656.31892,16.639984130859375,0.006089944272842818,1739502656.3189223,16.639984130859375,0.014099318776331525,1739502656.3189242,16.639984130859375,2.087006013522499 +1739502656.3391004,16.65998411178589,33.43928591044376,1739502656.3391073,16.65998411178589,0.08293194074320098,1739502656.3391147,16.65998411178589,32.797018674657,1739502656.339122,16.65998411178589,38.96434108279615,1739502656.3391263,16.65998411178589,-0.06124350925073255,1739502656.339131,16.65998411178589,-0.026088922893328564,1739502656.3391352,16.65998411178589,-0.2220580530620056,1739502656.3391392,16.65998411178589,-0.05582243208756451,1739502656.3391438,16.65998411178589,2.0930959577953416,1739502656.3391478,16.65998411178589,0.0,1739502656.3391516,16.65998411178589,0.006089944272842818,1739502656.3391557,16.65998411178589,0.014099318776331525,1739502656.33916,16.65998411178589,2.087006013522499 +1739502656.3593383,16.679984092712402,33.668859729520925,1739502656.359342,16.679984092712402,0.08606252202440601,1739502656.3593466,16.679984092712402,33.41406660026998,1739502656.3593514,16.679984092712402,39.5825042512766,1739502656.3593533,16.679984092712402,-0.06968223941759837,1739502656.3593562,16.679984092712402,-0.02633042399599099,1739502656.3593585,16.679984092712402,-0.23307554158170635,1739502656.3593607,16.679984092712402,-0.05114512997789833,1739502656.3593628,16.679984092712402,2.074728493486106,1739502656.3593655,16.679984092712402,0.0,1739502656.3593676,16.679984092712402,-0.021481226174683246,1739502656.35937,16.679984092712402,0.013079295917007135,1739502656.3593726,16.679984092712402,2.08759372324685 +1739502656.3789525,16.699984073638916,33.668859729520925,1739502656.3789568,16.699984073638916,0.08606252202440601,1739502656.3789628,16.699984073638916,33.41406660026998,1739502656.378967,16.699984073638916,39.5825042512766,1739502656.3789694,16.699984073638916,-0.06968223941759837,1739502656.3789725,16.699984073638916,-0.02633042399599099,1739502656.3789785,16.699984073638916,-0.23307554158170635,1739502656.3789852,16.699984073638916,-0.05114512997789833,1739502656.378992,16.699984073638916,2.074728493486106,1739502656.3789995,16.699984073638916,0.0,1739502656.3790064,16.699984073638916,-0.01286522976074389,1739502656.3790138,16.699984073638916,0.013079295917007135,1739502656.3790212,16.699984073638916,2.08759372324685 +1739502656.3995416,16.71998405456543,33.668859729520925,1739502656.3995457,16.71998405456543,0.08606252202440601,1739502656.3995502,16.71998405456543,33.41406660026998,1739502656.3995547,16.71998405456543,39.5825042512766,1739502656.399557,16.71998405456543,-0.06968223941759837,1739502656.39956,16.71998405456543,-0.02633042399599099,1739502656.3995624,16.71998405456543,-0.23307554158170635,1739502656.3995645,16.71998405456543,-0.05114512997789833,1739502656.3995667,16.71998405456543,2.074728493486106,1739502656.399569,16.71998405456543,0.0,1739502656.3995714,16.71998405456543,-0.01286522976074389,1739502656.3995738,16.71998405456543,0.013079295917007135,1739502656.399576,16.71998405456543,2.08759372324685 +1739502656.418891,16.739984035491943,33.668859729520925,1739502656.4188952,16.739984035491943,0.08606252202440601,1739502656.4189005,16.739984035491943,33.41406660026998,1739502656.418905,16.739984035491943,39.5825042512766,1739502656.4189074,16.739984035491943,-0.06968223941759837,1739502656.4189103,16.739984035491943,-0.02633042399599099,1739502656.4189124,16.739984035491943,-0.23307554158170635,1739502656.4189148,16.739984035491943,-0.05114512997789833,1739502656.418917,16.739984035491943,2.074728493486106,1739502656.4189193,16.739984035491943,0.0,1739502656.4189215,16.739984035491943,-0.01286522976074389,1739502656.418924,16.739984035491943,0.013079295917007135,1739502656.4189262,16.739984035491943,2.08759372324685 +1739502656.438903,16.759984016418457,33.668859729520925,1739502656.438907,16.759984016418457,0.08606252202440601,1739502656.4389117,16.759984016418457,33.41406660026998,1739502656.4389164,16.759984016418457,39.5825042512766,1739502656.4389186,16.759984016418457,-0.06968223941759837,1739502656.4389215,16.759984016418457,-0.02633042399599099,1739502656.438924,16.759984016418457,-0.23307554158170635,1739502656.4389262,16.759984016418457,-0.05114512997789833,1739502656.4389284,16.759984016418457,2.074728493486106,1739502656.4389312,16.759984016418457,0.0,1739502656.4389331,16.759984016418457,-0.01286522976074389,1739502656.4389355,16.759984016418457,0.013079295917007135,1739502656.438938,16.759984016418457,2.08759372324685 +1739502656.4588468,16.77998399734497,33.668859729520925,1739502656.4588506,16.77998399734497,0.08606252202440601,1739502656.4588554,16.77998399734497,33.41406660026998,1739502656.4588597,16.77998399734497,39.5825042512766,1739502656.458862,16.77998399734497,-0.06968223941759837,1739502656.4588647,16.77998399734497,-0.02633042399599099,1739502656.4588668,16.77998399734497,-0.23307554158170635,1739502656.4588692,16.77998399734497,-0.05114512997789833,1739502656.4588714,16.77998399734497,2.074728493486106,1739502656.4588737,16.77998399734497,0.0,1739502656.4588761,16.77998399734497,-0.01286522976074389,1739502656.4588785,16.77998399734497,0.013079295917007135,1739502656.4588807,16.77998399734497,2.08759372324685 +1739502656.478492,16.799983978271484,33.89838302137313,1739502656.4784968,16.799983978271484,0.08895827610055385,1739502656.4785018,16.799983978271484,33.42439804415741,1739502656.4785066,16.799983978271484,39.58950533327764,1739502656.4785087,16.799983978271484,-0.06974157062099699,1739502656.4785113,16.799983978271484,-0.027878285181690332,1739502656.4785137,16.799983978271484,-0.22731744183900612,1739502656.4785156,16.799983978271484,-0.053853497181443916,1739502656.478518,16.799983978271484,2.084307734721304,1739502656.4785209,16.799983978271484,0.0,1739502656.4785228,16.799983978271484,0.0034901154465454788,1739502656.4785254,16.799983978271484,0.012059273057682745,1739502656.4785278,16.799983978271484,2.0859286680031013 +1739502656.49924,16.819983959197998,33.89838302137313,1739502656.499244,16.819983959197998,0.08895827610055385,1739502656.4992487,16.819983959197998,33.42439804415741,1739502656.4992533,16.819983959197998,39.58950533327764,1739502656.4992552,16.819983959197998,-0.06974157062099699,1739502656.4992578,16.819983959197998,-0.027878285181690332,1739502656.4992602,16.819983959197998,-0.22731744183900612,1739502656.4992626,16.819983959197998,-0.053853497181443916,1739502656.4992645,16.819983959197998,2.084307734721304,1739502656.499267,16.819983959197998,0.0,1739502656.4992695,16.819983959197998,-0.0016209332817971323,1739502656.4992716,16.819983959197998,0.012059273057682745,1739502656.499274,16.819983959197998,2.0859286680031013 +1739502656.5187774,16.83998394012451,33.89838302137313,1739502656.5187812,16.83998394012451,0.08895827610055385,1739502656.5187862,16.83998394012451,33.42439804415741,1739502656.5187907,16.83998394012451,39.58950533327764,1739502656.5187929,16.83998394012451,-0.06974157062099699,1739502656.5187957,16.83998394012451,-0.027878285181690332,1739502656.518798,16.83998394012451,-0.22731744183900612,1739502656.5188005,16.83998394012451,-0.053853497181443916,1739502656.5188024,16.83998394012451,2.084307734721304,1739502656.5188053,16.83998394012451,0.0,1739502656.5188074,16.83998394012451,-0.0016209332817971323,1739502656.5188096,16.83998394012451,0.012059273057682745,1739502656.518812,16.83998394012451,2.0859286680031013 +1739502656.538345,16.859983921051025,33.89838302137313,1739502656.5383492,16.859983921051025,0.08895827610055385,1739502656.5383537,16.859983921051025,33.42439804415741,1739502656.5383582,16.859983921051025,39.58950533327764,1739502656.5383606,16.859983921051025,-0.06974157062099699,1739502656.5383635,16.859983921051025,-0.027878285181690332,1739502656.5383656,16.859983921051025,-0.22731744183900612,1739502656.538368,16.859983921051025,-0.053853497181443916,1739502656.5383701,16.859983921051025,2.084307734721304,1739502656.5383725,16.859983921051025,0.0,1739502656.538375,16.859983921051025,-0.0016209332817971323,1739502656.5383775,16.859983921051025,0.012059273057682745,1739502656.5383797,16.859983921051025,2.0859286680031013 +1739502656.5592484,16.87998390197754,33.89838302137313,1739502656.5592523,16.87998390197754,0.08895827610055385,1739502656.5592566,16.87998390197754,33.42439804415741,1739502656.5592608,16.87998390197754,39.58950533327764,1739502656.559263,16.87998390197754,-0.06974157062099699,1739502656.5592659,16.87998390197754,-0.027878285181690332,1739502656.559268,16.87998390197754,-0.22731744183900612,1739502656.5592704,16.87998390197754,-0.053853497181443916,1739502656.5592725,16.87998390197754,2.084307734721304,1739502656.559275,16.87998390197754,0.0,1739502656.5592773,16.87998390197754,-0.0016209332817971323,1739502656.5592797,16.87998390197754,0.012059273057682745,1739502656.559282,16.87998390197754,2.0859286680031013 +1739502656.5778778,16.899983882904053,34.12781202998568,1739502656.5778816,16.899983882904053,0.09161876889367804,1739502656.5778854,16.899983882904053,33.43472501003776,1739502656.577889,16.899983882904053,39.599561578856324,1739502656.577891,16.899983882904053,-0.06982679304115529,1739502656.5778933,16.899983882904053,-0.029496733262749736,1739502656.5778954,16.899983882904053,-0.22183851019333975,1739502656.5778975,16.899983882904053,-0.05684808458015872,1739502656.5778992,16.899983882904053,2.0934636095132957,1739502656.5779014,16.899983882904053,0.0,1739502656.5779033,16.899983882904053,0.011893331676817318,1739502656.5779054,16.899983882904053,0.011039250198358354,1739502656.577907,16.899983882904053,2.085793488404998 +1739502656.597975,16.919983863830566,34.12781202998568,1739502656.5979786,16.919983863830566,0.09161876889367804,1739502656.5979824,16.919983863830566,33.43472501003776,1739502656.5979865,16.919983863830566,39.599561578856324,1739502656.5979884,16.919983863830566,-0.06982679304115529,1739502656.597991,16.919983863830566,-0.029496733262749736,1739502656.597993,16.919983863830566,-0.22183851019333975,1739502656.597995,16.919983863830566,-0.05684808458015872,1739502656.5979967,16.919983863830566,2.0934636095132957,1739502656.597999,16.919983863830566,0.0,1739502656.598001,16.919983863830566,0.007670121108297678,1739502656.598003,16.919983863830566,0.011039250198358354,1739502656.5980053,16.919983863830566,2.085793488404998 +1739502656.6210508,16.93998384475708,34.12781202998568,1739502656.62106,16.93998384475708,0.09161876889367804,1739502656.6210706,16.93998384475708,33.43472501003776,1739502656.6210804,16.93998384475708,39.599561578856324,1739502656.6210852,16.93998384475708,-0.06982679304115529,1739502656.6210916,16.93998384475708,-0.029496733262749736,1739502656.6210968,16.93998384475708,-0.22183851019333975,1739502656.6211019,16.93998384475708,-0.05684808458015872,1739502656.6211066,16.93998384475708,2.0934636095132957,1739502656.6211126,16.93998384475708,0.0,1739502656.6211176,16.93998384475708,0.007670121108297678,1739502656.621123,16.93998384475708,0.011039250198358354,1739502656.6211286,16.93998384475708,2.085793488404998 +1739502656.6408982,16.959983825683594,34.12781202998568,1739502656.6409066,16.959983825683594,0.09161876889367804,1739502656.640917,16.959983825683594,33.43472501003776,1739502656.6409276,16.959983825683594,39.599561578856324,1739502656.6409323,16.959983825683594,-0.06982679304115529,1739502656.6409385,16.959983825683594,-0.029496733262749736,1739502656.6409435,16.959983825683594,-0.22183851019333975,1739502656.6409485,16.959983825683594,-0.05684808458015872,1739502656.640953,16.959983825683594,2.0934636095132957,1739502656.6409593,16.959983825683594,0.0,1739502656.6409643,16.959983825683594,0.007670121108297678,1739502656.6409695,16.959983825683594,0.011039250198358354,1739502656.6409748,16.959983825683594,2.085793488404998 +1739502656.663805,16.979983806610107,34.12781202998568,1739502656.6638107,16.979983806610107,0.09161876889367804,1739502656.6638181,16.979983806610107,33.43472501003776,1739502656.6638255,16.979983806610107,39.599561578856324,1739502656.6638288,16.979983806610107,-0.06982679304115529,1739502656.663833,16.979983806610107,-0.029496733262749736,1739502656.6638362,16.979983806610107,-0.22183851019333975,1739502656.6638398,16.979983806610107,-0.05684808458015872,1739502656.6638432,16.979983806610107,2.0934636095132957,1739502656.6638467,16.979983806610107,0.0,1739502656.6638503,16.979983806610107,0.007670121108297678,1739502656.6638541,16.979983806610107,0.011039250198358354,1739502656.6638575,16.979983806610107,2.085793488404998 +1739502656.6829875,17.009983777999878,34.357286533327894,1739502656.682991,17.009983777999878,0.09404568238761524,1739502656.682996,17.009983777999878,33.44505378960166,1739502656.6830003,17.009983777999878,39.61173709260879,1739502656.6830027,17.009983777999878,-0.06992997536109147,1739502656.6830053,17.009983777999878,-0.031196878963921842,1739502656.6830075,17.009983777999878,-0.21661208137284174,1739502656.6830096,17.009983777999878,-0.060187770656856814,1739502656.6830115,17.009983777999878,2.1022350047988554,1739502656.6830142,17.009983777999878,0.0,1739502656.6830163,17.009983777999878,0.019085120275456408,1739502656.6830184,17.009983777999878,0.010019227339033964,1739502656.6830206,17.009983777999878,2.086717074101968 +1739502656.7035372,17.02998375892639,34.357286533327894,1739502656.7035408,17.02998375892639,0.09404568238761524,1739502656.7035456,17.02998375892639,33.44505378960166,1739502656.7035508,17.02998375892639,39.61173709260879,1739502656.7035537,17.02998375892639,-0.06992997536109147,1739502656.7035577,17.02998375892639,-0.031196878963921842,1739502656.703561,17.02998375892639,-0.21661208137284174,1739502656.7035646,17.02998375892639,-0.060187770656856814,1739502656.703568,17.02998375892639,2.1022350047988554,1739502656.7035716,17.02998375892639,0.0,1739502656.703575,17.02998375892639,0.01551793069688756,1739502656.7035785,17.02998375892639,0.010019227339033964,1739502656.703582,17.02998375892639,2.086717074101968 +1739502656.723572,17.049983739852905,34.357286533327894,1739502656.7235756,17.049983739852905,0.09404568238761524,1739502656.7235801,17.049983739852905,33.44505378960166,1739502656.7235854,17.049983739852905,39.61173709260879,1739502656.7235885,17.049983739852905,-0.06992997536109147,1739502656.7235923,17.049983739852905,-0.031196878963921842,1739502656.7235956,17.049983739852905,-0.21661208137284174,1739502656.723599,17.049983739852905,-0.060187770656856814,1739502656.7236025,17.049983739852905,2.1022350047988554,1739502656.723606,17.049983739852905,0.0,1739502656.7236094,17.049983739852905,0.01551793069688756,1739502656.7236128,17.049983739852905,0.010019227339033964,1739502656.7236164,17.049983739852905,2.086717074101968 +1739502656.743398,17.06998372077942,34.357286533327894,1739502656.7434022,17.06998372077942,0.09404568238761524,1739502656.7434068,17.06998372077942,33.44505378960166,1739502656.7434123,17.06998372077942,39.61173709260879,1739502656.743415,17.06998372077942,-0.06992997536109147,1739502656.743419,17.06998372077942,-0.031196878963921842,1739502656.7434225,17.06998372077942,-0.21661208137284174,1739502656.7434258,17.06998372077942,-0.060187770656856814,1739502656.7434292,17.06998372077942,2.1022350047988554,1739502656.7434328,17.06998372077942,0.0,1739502656.7434363,17.06998372077942,0.01551793069688756,1739502656.7434397,17.06998372077942,0.010019227339033964,1739502656.7434433,17.06998372077942,2.086717074101968 +1739502656.7628827,17.089983701705933,34.357286533327894,1739502656.762887,17.089983701705933,0.09404568238761524,1739502656.762892,17.089983701705933,33.44505378960166,1739502656.7628965,17.089983701705933,39.61173709260879,1739502656.7628987,17.089983701705933,-0.06992997536109147,1739502656.7629018,17.089983701705933,-0.031196878963921842,1739502656.7629044,17.089983701705933,-0.21661208137284174,1739502656.7629068,17.089983701705933,-0.060187770656856814,1739502656.762909,17.089983701705933,2.1022350047988554,1739502656.7629116,17.089983701705933,0.0,1739502656.7629135,17.089983701705933,0.01551793069688756,1739502656.762916,17.089983701705933,0.010019227339033964,1739502656.7629185,17.089983701705933,2.086717074101968 +1739502656.782647,17.109983682632446,34.357286533327894,1739502656.7826505,17.109983682632446,0.09404568238761524,1739502656.7826548,17.109983682632446,33.44505378960166,1739502656.782659,17.109983682632446,39.61173709260879,1739502656.7826614,17.109983682632446,-0.06992997536109147,1739502656.7826643,17.109983682632446,-0.031196878963921842,1739502656.7826664,17.109983682632446,-0.21661208137284174,1739502656.782669,17.109983682632446,-0.060187770656856814,1739502656.7826715,17.109983682632446,2.1022350047988554,1739502656.7826738,17.109983682632446,0.0,1739502656.7826765,17.109983682632446,0.01551793069688756,1739502656.7826788,17.109983682632446,0.010019227339033964,1739502656.782681,17.109983682632446,2.086717074101968 +1739502656.8025024,17.12998366355896,34.586906783510294,1739502656.8025062,17.12998366355896,0.09623988775549197,1739502656.8025103,17.12998366355896,33.72031524778467,1739502656.8025143,17.12998366355896,39.890507345688356,1739502656.8025165,17.12998366355896,-0.07387331118212949,1739502656.8025193,17.12998366355896,-0.03206404686376035,1739502656.802522,17.12998366355896,-0.2178338523411978,1739502656.802524,17.12998366355896,-0.05940754788927674,1739502656.8025265,17.12998366355896,2.100181248892076,1739502656.8025296,17.12998366355896,0.0,1739502656.802532,17.12998366355896,0.00995626529961647,1739502656.8025343,17.12998366355896,0.008999204479709574,1739502656.802537,17.12998366355896,2.0884869620162765 +1739502656.822825,17.149983644485474,34.586906783510294,1739502656.8228288,17.149983644485474,0.09623988775549197,1739502656.8228333,17.149983644485474,33.72031524778467,1739502656.8228388,17.149983644485474,39.890507345688356,1739502656.822842,17.149983644485474,-0.07387331118212949,1739502656.8228457,17.149983644485474,-0.03206404686376035,1739502656.8228493,17.149983644485474,-0.2178338523411978,1739502656.8228528,17.149983644485474,-0.05940754788927674,1739502656.8228562,17.149983644485474,2.100181248892076,1739502656.8228598,17.149983644485474,0.0,1739502656.822863,17.149983644485474,0.011694286875799431,1739502656.8228667,17.149983644485474,0.008999204479709574,1739502656.8228703,17.149983644485474,2.0884869620162765 +1739502656.8417678,17.169983625411987,34.586906783510294,1739502656.8417702,17.169983625411987,0.09623988775549197,1739502656.8417735,17.169983625411987,33.72031524778467,1739502656.8417764,17.169983625411987,39.890507345688356,1739502656.8417778,17.169983625411987,-0.07387331118212949,1739502656.8417795,17.169983625411987,-0.03206404686376035,1739502656.841781,17.169983625411987,-0.2178338523411978,1739502656.8417823,17.169983625411987,-0.05940754788927674,1739502656.8417835,17.169983625411987,2.100181248892076,1739502656.8417847,17.169983625411987,0.0,1739502656.8417864,17.169983625411987,0.011694286875799431,1739502656.8417878,17.169983625411987,0.008999204479709574,1739502656.8417895,17.169983625411987,2.0884869620162765 +1739502656.8617735,17.1899836063385,34.586906783510294,1739502656.8617759,17.1899836063385,0.09623988775549197,1739502656.8617787,17.1899836063385,33.72031524778467,1739502656.8617814,17.1899836063385,39.890507345688356,1739502656.8617826,17.1899836063385,-0.07387331118212949,1739502656.861784,17.1899836063385,-0.03206404686376035,1739502656.8617854,17.1899836063385,-0.2178338523411978,1739502656.8617866,17.1899836063385,-0.05940754788927674,1739502656.8617878,17.1899836063385,2.100181248892076,1739502656.8617895,17.1899836063385,0.0,1739502656.8617907,17.1899836063385,0.011694286875799431,1739502656.861792,17.1899836063385,0.008999204479709574,1739502656.8617935,17.1899836063385,2.0884869620162765 +1739502656.8817132,17.209983587265015,34.586906783510294,1739502656.8817153,17.209983587265015,0.09623988775549197,1739502656.8817177,17.209983587265015,33.72031524778467,1739502656.88172,17.209983587265015,39.890507345688356,1739502656.8817213,17.209983587265015,-0.07387331118212949,1739502656.881723,17.209983587265015,-0.03206404686376035,1739502656.881724,17.209983587265015,-0.2178338523411978,1739502656.8817255,17.209983587265015,-0.05940754788927674,1739502656.8817267,17.209983587265015,2.100181248892076,1739502656.881728,17.209983587265015,0.0,1739502656.8817294,17.209983587265015,0.011694286875799431,1739502656.8817306,17.209983587265015,0.008999204479709574,1739502656.8817317,17.209983587265015,2.0884869620162765 +1739502656.9019551,17.22998356819153,34.8166968120731,1739502656.901958,17.22998356819153,0.09820130973275276,1739502656.9019608,17.22998356819153,33.97605578154143,1739502656.9019637,17.22998356819153,40.14879745349436,1739502656.9019651,17.22998356819153,-0.07657342879198549,1739502656.9019673,17.22998356819153,-0.03276610827582575,1739502656.901969,17.22998356819153,-0.21731452280750171,1739502656.9019701,17.22998356819153,-0.05863158641654347,1739502656.9019713,17.22998356819153,2.1010539790922813,1739502656.901973,17.22998356819153,0.0,1739502656.9019744,17.22998356819153,0.011098588876082872,1739502656.901976,17.22998356819153,0.007979181620385184,1739502656.9019773,17.22998356819153,2.089769234469234 +1739502656.921995,17.249983549118042,34.8166968120731,1739502656.9219975,17.249983549118042,0.09820130973275276,1739502656.9220004,17.249983549118042,33.97605578154143,1739502656.9220033,17.249983549118042,40.14879745349436,1739502656.9220045,17.249983549118042,-0.07657342879198549,1739502656.9220273,17.249983549118042,-0.03276610827582575,1739502656.9220285,17.249983549118042,-0.21731452280750171,1739502656.92203,17.249983549118042,-0.05863158641654347,1739502656.9220312,17.249983549118042,2.1010539790922813,1739502656.9220328,17.249983549118042,0.0,1739502656.9220343,17.249983549118042,0.011284744623047516,1739502656.9220355,17.249983549118042,0.007979181620385184,1739502656.922037,17.249983549118042,2.089769234469234 +1739502656.9421089,17.269983530044556,34.8166968120731,1739502656.9421113,17.269983530044556,0.09820130973275276,1739502656.942114,17.269983530044556,33.97605578154143,1739502656.9421165,17.269983530044556,40.14879745349436,1739502656.942118,17.269983530044556,-0.07657342879198549,1739502656.9421194,17.269983530044556,-0.03276610827582575,1739502656.942121,17.269983530044556,-0.21731452280750171,1739502656.9421222,17.269983530044556,-0.05863158641654347,1739502656.9421234,17.269983530044556,2.1010539790922813,1739502656.9421253,17.269983530044556,0.0,1739502656.9421265,17.269983530044556,0.011284744623047516,1739502656.942128,17.269983530044556,0.007979181620385184,1739502656.9421291,17.269983530044556,2.089769234469234 +1739502656.9680605,17.28998351097107,34.8166968120731,1739502656.9680707,17.28998351097107,0.09820130973275276,1739502656.9680817,17.28998351097107,33.97605578154143,1739502656.9680917,17.28998351097107,40.14879745349436,1739502656.9680965,17.28998351097107,-0.07657342879198549,1739502656.9681027,17.28998351097107,-0.03276610827582575,1739502656.9681077,17.28998351097107,-0.21731452280750171,1739502656.9681132,17.28998351097107,-0.05863158641654347,1739502656.9681177,17.28998351097107,2.1010539790922813,1739502656.9681234,17.28998351097107,0.0,1739502656.9681284,17.28998351097107,0.011284744623047516,1739502656.9681337,17.28998351097107,0.007979181620385184,1739502656.9681392,17.28998351097107,2.089769234469234 +1739502656.9870157,17.309983491897583,34.8166968120731,1739502656.9870257,17.309983491897583,0.09820130973275276,1739502656.987037,17.309983491897583,33.97605578154143,1739502656.9870474,17.309983491897583,40.14879745349436,1739502656.9870524,17.309983491897583,-0.07657342879198549,1739502656.9870589,17.309983491897583,-0.03276610827582575,1739502656.987064,17.309983491897583,-0.21731452280750171,1739502656.9870687,17.309983491897583,-0.05863158641654347,1739502656.9870732,17.309983491897583,2.1010539790922813,1739502656.987079,17.309983491897583,0.0,1739502656.9870837,17.309983491897583,0.011284744623047516,1739502656.9870887,17.309983491897583,0.007979181620385184,1739502656.9870934,17.309983491897583,2.089769234469234 +1739502657.0133696,17.329983472824097,34.8166968120731,1739502657.0133753,17.329983472824097,0.09820130973275276,1739502657.013383,17.329983472824097,33.97605578154143,1739502657.01339,17.329983472824097,40.14879745349436,1739502657.0133936,17.329983472824097,-0.07657342879198549,1739502657.013398,17.329983472824097,-0.03276610827582575,1739502657.0134015,17.329983472824097,-0.21731452280750171,1739502657.0134048,17.329983472824097,-0.05863158641654347,1739502657.0134082,17.329983472824097,2.1010539790922813,1739502657.0134122,17.329983472824097,0.0,1739502657.013416,17.329983472824097,0.011284744623047516,1739502657.0134196,17.329983472824097,0.007979181620385184,1739502657.0134232,17.329983472824097,2.089769234469234 +1739502657.0343435,17.359983444213867,35.046626467485424,1739502657.03435,17.359983444213867,0.099929375170972,1739502657.0343573,17.359983444213867,34.21326100725782,1739502657.0343647,17.359983444213867,40.388455508281666,1739502657.034368,17.359983444213867,-0.07863433155372662,1739502657.0343726,17.359983444213867,-0.0334150047169086,1739502657.0343761,17.359983444213867,-0.2157337191412315,1739502657.0343797,17.359983444213867,-0.05799094368515449,1739502657.0343833,17.359983444213867,2.103712742997966,1739502657.034387,17.359983444213867,0.0,1739502657.0343907,17.359983444213867,0.013360112475016924,1739502657.0343943,17.359983444213867,0.006959158761060786,1739502657.0343978,17.359983444213867,2.091001183401914 +1739502657.0517569,17.37998342514038,35.046626467485424,1739502657.0517602,17.37998342514038,0.099929375170972,1739502657.0517645,17.37998342514038,34.21326100725782,1739502657.0517683,17.37998342514038,40.388455508281666,1739502657.0517704,17.37998342514038,-0.07863433155372662,1739502657.0517726,17.37998342514038,-0.0334150047169086,1739502657.0517745,17.37998342514038,-0.2157337191412315,1739502657.0517764,17.37998342514038,-0.05799094368515449,1739502657.0517783,17.37998342514038,2.103712742997966,1739502657.0517805,17.37998342514038,0.0,1739502657.0517821,17.37998342514038,0.01271155959605208,1739502657.0517843,17.37998342514038,0.006959158761060786,1739502657.0517862,17.37998342514038,2.091001183401914 +1739502657.072795,17.399983406066895,35.046626467485424,1739502657.0727983,17.399983406066895,0.099929375170972,1739502657.0728018,17.399983406066895,34.21326100725782,1739502657.0728047,17.399983406066895,40.388455508281666,1739502657.072806,17.399983406066895,-0.07863433155372662,1739502657.072808,17.399983406066895,-0.0334150047169086,1739502657.0728095,17.399983406066895,-0.2157337191412315,1739502657.0728106,17.399983406066895,-0.05799094368515449,1739502657.072812,17.399983406066895,2.103712742997966,1739502657.0728137,17.399983406066895,0.0,1739502657.0728152,17.399983406066895,0.01271155959605208,1739502657.072817,17.399983406066895,0.006959158761060786,1739502657.0728188,17.399983406066895,2.091001183401914 +1739502657.0922978,17.419983386993408,35.046626467485424,1739502657.0923018,17.419983386993408,0.099929375170972,1739502657.0923066,17.419983386993408,34.21326100725782,1739502657.0923119,17.419983386993408,40.388455508281666,1739502657.0923147,17.419983386993408,-0.07863433155372662,1739502657.0923185,17.419983386993408,-0.0334150047169086,1739502657.0923216,17.419983386993408,-0.2157337191412315,1739502657.0923254,17.419983386993408,-0.05799094368515449,1739502657.0923288,17.419983386993408,2.103712742997966,1739502657.0923321,17.419983386993408,0.0,1739502657.0923355,17.419983386993408,0.01271155959605208,1739502657.0923388,17.419983386993408,0.006959158761060786,1739502657.092342,17.419983386993408,2.091001183401914 +1739502657.1123312,17.439983367919922,35.046626467485424,1739502657.1123345,17.439983367919922,0.099929375170972,1739502657.1123393,17.439983367919922,34.21326100725782,1739502657.112344,17.439983367919922,40.388455508281666,1739502657.1123471,17.439983367919922,-0.07863433155372662,1739502657.1123507,17.439983367919922,-0.0334150047169086,1739502657.1123543,17.439983367919922,-0.2157337191412315,1739502657.1123574,17.439983367919922,-0.05799094368515449,1739502657.1123607,17.439983367919922,2.103712742997966,1739502657.1123643,17.439983367919922,0.0,1739502657.1123676,17.439983367919922,0.01271155959605208,1739502657.112371,17.439983367919922,0.006959158761060786,1739502657.1123743,17.439983367919922,2.091001183401914 +1739502657.1324406,17.459983348846436,35.27669951101676,1739502657.1324441,17.459983348846436,0.10142382553458518,1739502657.1324487,17.459983348846436,34.561156626188804,1739502657.1324537,17.459983348846436,40.739068859950606,1739502657.1324565,17.459983348846436,-0.08212652645630397,1739502657.13246,17.459983348846436,-0.03359005996688026,1739502657.1324635,17.459983348846436,-0.21598867797150864,1739502657.1324668,17.459983348846436,-0.05552523218752678,1739502657.1324697,17.459983348846436,2.103283698642757,1739502657.1324732,17.459983348846436,0.0,1739502657.1324766,17.459983348846436,0.010088628258006186,1739502657.13248,17.459983348846436,0.005939135901736386,1739502657.1324832,17.459983348846436,2.0923754038041964 +1739502657.1525278,17.47998332977295,35.27669951101676,1739502657.1525314,17.47998332977295,0.10142382553458518,1739502657.152536,17.47998332977295,34.561156626188804,1739502657.152541,17.47998332977295,40.739068859950606,1739502657.1525438,17.47998332977295,-0.08212652645630397,1739502657.1525474,17.47998332977295,-0.03359005996688026,1739502657.1525505,17.47998332977295,-0.21598867797150864,1739502657.1525538,17.47998332977295,-0.05552523218752678,1739502657.152557,17.47998332977295,2.103283698642757,1739502657.1525602,17.47998332977295,0.0,1739502657.1525636,17.47998332977295,0.010908294838560817,1739502657.1525667,17.47998332977295,0.005939135901736386,1739502657.15257,17.47998332977295,2.0923754038041964 +1739502657.1719007,17.499983310699463,35.27669951101676,1739502657.1719046,17.499983310699463,0.10142382553458518,1739502657.1719089,17.499983310699463,34.561156626188804,1739502657.1719134,17.499983310699463,40.739068859950606,1739502657.171916,17.499983310699463,-0.08212652645630397,1739502657.1719196,17.499983310699463,-0.03359005996688026,1739502657.171923,17.499983310699463,-0.21598867797150864,1739502657.1719258,17.499983310699463,-0.05552523218752678,1739502657.1719291,17.499983310699463,2.103283698642757,1739502657.1719322,17.499983310699463,0.0,1739502657.1719353,17.499983310699463,0.010908294838560817,1739502657.1719387,17.499983310699463,0.005939135901736386,1739502657.171942,17.499983310699463,2.0923754038041964 +1739502657.192844,17.519983291625977,35.27669951101676,1739502657.192848,17.519983291625977,0.10142382553458518,1739502657.1928525,17.519983291625977,34.561156626188804,1739502657.1928573,17.519983291625977,40.739068859950606,1739502657.1928601,17.519983291625977,-0.08212652645630397,1739502657.1928637,17.519983291625977,-0.03359005996688026,1739502657.1928673,17.519983291625977,-0.21598867797150864,1739502657.1928706,17.519983291625977,-0.05552523218752678,1739502657.1928737,17.519983291625977,2.103283698642757,1739502657.192877,17.519983291625977,0.0,1739502657.1928804,17.519983291625977,0.010908294838560817,1739502657.1928837,17.519983291625977,0.005939135901736386,1739502657.192887,17.519983291625977,2.0923754038041964 +1739502657.212061,17.53998327255249,35.27669951101676,1739502657.212064,17.53998327255249,0.10142382553458518,1739502657.2120686,17.53998327255249,34.561156626188804,1739502657.2120736,17.53998327255249,40.739068859950606,1739502657.2120762,17.53998327255249,-0.08212652645630397,1739502657.2120798,17.53998327255249,-0.03359005996688026,1739502657.212083,17.53998327255249,-0.21598867797150864,1739502657.2120862,17.53998327255249,-0.05552523218752678,1739502657.2120895,17.53998327255249,2.103283698642757,1739502657.2121055,17.53998327255249,0.0,1739502657.2121086,17.53998327255249,0.010908294838560817,1739502657.2121117,17.53998327255249,0.005939135901736386,1739502657.212115,17.53998327255249,2.0923754038041964 +1739502657.23067,17.559983253479004,35.50691745660158,1739502657.2306721,17.559983253479004,0.10268438299602956,1739502657.2306745,17.559983253479004,35.22885385032268,1739502657.230677,17.559983253479004,41.409090303397285,1739502657.230678,17.559983253479004,-0.09066838673137677,1739502657.2306795,17.559983253479004,-0.03274787965548321,1739502657.230681,17.559983253479004,-0.22238376872760407,1739502657.2306821,17.559983253479004,-0.0489706705983596,1739502657.2306833,17.559983253479004,2.0925506255332875,1739502657.2306848,17.559983253479004,0.0,1739502657.230686,17.559983253479004,-0.006441297610305042,1739502657.2306871,17.559983253479004,0.004919113042411986,1739502657.2306883,17.559983253479004,2.093570171948545 +1739502657.2523906,17.579983234405518,35.50691745660158,1739502657.2523942,17.579983234405518,0.10268438299602956,1739502657.2523987,17.579983234405518,35.22885385032268,1739502657.2524037,17.579983234405518,41.409090303397285,1739502657.2524066,17.579983234405518,-0.09066838673137677,1739502657.2524104,17.579983234405518,-0.03274787965548321,1739502657.2524135,17.579983234405518,-0.22238376872760407,1739502657.2524168,17.579983234405518,-0.0489706705983596,1739502657.25242,17.579983234405518,2.0925506255332875,1739502657.2524235,17.579983234405518,0.0,1739502657.2524269,17.579983234405518,-0.0010195464152573663,1739502657.2524304,17.579983234405518,0.004919113042411986,1739502657.2524343,17.579983234405518,2.093570171948545 +1739502657.271014,17.59998321533203,35.50691745660158,1739502657.2710164,17.59998321533203,0.10268438299602956,1739502657.2710195,17.59998321533203,35.22885385032268,1739502657.2710223,17.59998321533203,41.409090303397285,1739502657.2710235,17.59998321533203,-0.09066838673137677,1739502657.2710252,17.59998321533203,-0.03274787965548321,1739502657.2710266,17.59998321533203,-0.22238376872760407,1739502657.271028,17.59998321533203,-0.0489706705983596,1739502657.2710295,17.59998321533203,2.0925506255332875,1739502657.2710311,17.59998321533203,0.0,1739502657.2710323,17.59998321533203,-0.0010195464152573663,1739502657.271034,17.59998321533203,0.004919113042411986,1739502657.2710354,17.59998321533203,2.093570171948545 +1739502657.292761,17.619983196258545,35.50691745660158,1739502657.2927644,17.619983196258545,0.10268438299602956,1739502657.292769,17.619983196258545,35.22885385032268,1739502657.2927742,17.619983196258545,41.409090303397285,1739502657.292777,17.619983196258545,-0.09066838673137677,1739502657.2927809,17.619983196258545,-0.03274787965548321,1739502657.2927842,17.619983196258545,-0.22238376872760407,1739502657.2927876,17.619983196258545,-0.0489706705983596,1739502657.2927904,17.619983196258545,2.0925506255332875,1739502657.2927942,17.619983196258545,0.0,1739502657.2927973,17.619983196258545,-0.0010195464152573663,1739502657.2928007,17.619983196258545,0.004919113042411986,1739502657.2928042,17.619983196258545,2.093570171948545 +1739502657.3110392,17.63998317718506,35.50691745660158,1739502657.311042,17.63998317718506,0.10268438299602956,1739502657.3110454,17.63998317718506,35.22885385032268,1739502657.311048,17.63998317718506,41.409090303397285,1739502657.3110495,17.63998317718506,-0.09066838673137677,1739502657.311051,17.63998317718506,-0.03274787965548321,1739502657.3110526,17.63998317718506,-0.22238376872760407,1739502657.311054,17.63998317718506,-0.0489706705983596,1739502657.3110554,17.63998317718506,2.0925506255332875,1739502657.3110569,17.63998317718506,0.0,1739502657.3110583,17.63998317718506,-0.0010195464152573663,1739502657.3110597,17.63998317718506,0.004919113042411986,1739502657.311062,17.63998317718506,2.093570171948545 +1739502657.3328006,17.659983158111572,35.50691745660158,1739502657.3328044,17.659983158111572,0.10268438299602956,1739502657.3328087,17.659983158111572,35.22885385032268,1739502657.3328137,17.659983158111572,41.409090303397285,1739502657.3328166,17.659983158111572,-0.09066838673137677,1739502657.332821,17.659983158111572,-0.03274787965548321,1739502657.332824,17.659983158111572,-0.22238376872760407,1739502657.3328276,17.659983158111572,-0.0489706705983596,1739502657.332831,17.659983158111572,2.0925506255332875,1739502657.3328345,17.659983158111572,0.0,1739502657.3328378,17.659983158111572,-0.0010195464152573663,1739502657.3328412,17.659983158111572,0.004919113042411986,1739502657.3328445,17.659983158111572,2.093570171948545 +1739502657.3522673,17.679983139038086,35.7371920268243,1739502657.3522704,17.679983139038086,0.10371037209999923,1739502657.352275,17.679983139038086,35.263856610985634,1739502657.35228,17.679983139038086,41.44364853815154,1739502657.3522828,17.679983139038086,-0.09132663882193419,1739502657.3522866,17.679983139038086,-0.03416500574983291,1739502657.3522897,17.679983139038086,-0.21728546054547812,1739502657.352293,17.679983139038086,-0.05118110967633384,1739502657.3522964,17.679983139038086,2.1011028287651645,1739502657.3522997,17.679983139038086,0.0,1739502657.3523033,17.679983139038086,0.01173875838587618,1739502657.3523066,17.679983139038086,0.0038990901830875868,1739502657.35231,17.679983139038086,2.0933510432437057 +1739502657.371069,17.6999831199646,35.7371920268243,1739502657.3710713,17.6999831199646,0.10371037209999923,1739502657.3710742,17.6999831199646,35.263856610985634,1739502657.3710768,17.6999831199646,41.44364853815154,1739502657.3710783,17.6999831199646,-0.09132663882193419,1739502657.37108,17.6999831199646,-0.03416500574983291,1739502657.371081,17.6999831199646,-0.21728546054547812,1739502657.3710828,17.6999831199646,-0.05118110967633384,1739502657.3710837,17.6999831199646,2.1011028287651645,1739502657.371086,17.6999831199646,0.0,1739502657.371087,17.6999831199646,0.007751785521458832,1739502657.3710883,17.6999831199646,0.0038990901830875868,1739502657.37109,17.6999831199646,2.0933510432437057 +1739502657.3908415,17.719983100891113,35.7371920268243,1739502657.3908436,17.719983100891113,0.10371037209999923,1739502657.3908465,17.719983100891113,35.263856610985634,1739502657.390849,17.719983100891113,41.44364853815154,1739502657.3908503,17.719983100891113,-0.09132663882193419,1739502657.3908522,17.719983100891113,-0.03416500574983291,1739502657.3908534,17.719983100891113,-0.21728546054547812,1739502657.3908546,17.719983100891113,-0.05118110967633384,1739502657.390856,17.719983100891113,2.1011028287651645,1739502657.3908575,17.719983100891113,0.0,1739502657.3908587,17.719983100891113,0.007751785521458832,1739502657.3908603,17.719983100891113,0.0038990901830875868,1739502657.3908615,17.719983100891113,2.0933510432437057 +1739502657.4110477,17.739983081817627,35.7371920268243,1739502657.4110503,17.739983081817627,0.10371037209999923,1739502657.4110534,17.739983081817627,35.263856610985634,1739502657.4110563,17.739983081817627,41.44364853815154,1739502657.4110577,17.739983081817627,-0.09132663882193419,1739502657.4110591,17.739983081817627,-0.03416500574983291,1739502657.4110608,17.739983081817627,-0.21728546054547812,1739502657.411062,17.739983081817627,-0.05118110967633384,1739502657.4110632,17.739983081817627,2.1011028287651645,1739502657.411065,17.739983081817627,0.0,1739502657.4110663,17.739983081817627,0.007751785521458832,1739502657.411068,17.739983081817627,0.0038990901830875868,1739502657.4110692,17.739983081817627,2.0933510432437057 +1739502657.4314353,17.75998306274414,35.7371920268243,1739502657.4314387,17.75998306274414,0.10371037209999923,1739502657.4314423,17.75998306274414,35.263856610985634,1739502657.431446,17.75998306274414,41.44364853815154,1739502657.4314477,17.75998306274414,-0.09132663882193419,1739502657.4314497,17.75998306274414,-0.03416500574983291,1739502657.4314513,17.75998306274414,-0.21728546054547812,1739502657.4314532,17.75998306274414,-0.05118110967633384,1739502657.4314551,17.75998306274414,2.1011028287651645,1739502657.431457,17.75998306274414,0.0,1739502657.4314585,17.75998306274414,0.007751785521458832,1739502657.4314601,17.75998306274414,0.0038990901830875868,1739502657.431462,17.75998306274414,2.0933510432437057 +1739502657.4515839,17.779983043670654,35.967499829500596,1739502657.4515862,17.779983043670654,0.10450157639324509,1739502657.4515893,17.779983043670654,35.29886418819673,1739502657.4515927,17.779983043670654,41.48033203929768,1739502657.4515944,17.779983043670654,-0.09201256640846867,1739502657.451596,17.779983043670654,-0.035631588780177526,1739502657.4515982,17.779983043670654,-0.21238512149623182,1739502657.4515996,17.779983043670654,-0.05359669991683034,1739502657.4516013,17.779983043670654,2.1093558883019803,1739502657.451603,17.779983043670654,0.0,1739502657.4516044,17.779983043670654,0.01853267853978247,1739502657.451606,17.779983043670654,0.002879067323763187,1739502657.4516075,17.779983043670654,2.094192241039333 +1739502657.4715846,17.799983024597168,35.967499829500596,1739502657.471588,17.799983024597168,0.10450157639324509,1739502657.4715915,17.799983024597168,35.29886418819673,1739502657.4715948,17.799983024597168,41.48033203929768,1739502657.4715962,17.799983024597168,-0.09201256640846867,1739502657.4715989,17.799983024597168,-0.035631588780177526,1739502657.4716005,17.799983024597168,-0.21238512149623182,1739502657.4716024,17.799983024597168,-0.05359669991683034,1739502657.4716039,17.799983024597168,2.1093558883019803,1739502657.471606,17.799983024597168,0.0,1739502657.4716074,17.799983024597168,0.015163647262647295,1739502657.4716094,17.799983024597168,0.002879067323763187,1739502657.4716108,17.799983024597168,2.094192241039333 +1739502657.494845,17.81998300552368,35.967499829500596,1739502657.4948525,17.81998300552368,0.10450157639324509,1739502657.4948633,17.81998300552368,35.29886418819673,1739502657.4948733,17.81998300552368,41.48033203929768,1739502657.4948783,17.81998300552368,-0.09201256640846867,1739502657.4948843,17.81998300552368,-0.035631588780177526,1739502657.4948895,17.81998300552368,-0.21238512149623182,1739502657.494894,17.81998300552368,-0.05359669991683034,1739502657.4948993,17.81998300552368,2.1093558883019803,1739502657.4949045,17.81998300552368,0.0,1739502657.4949095,17.81998300552368,0.015163647262647295,1739502657.4949143,17.81998300552368,0.002879067323763187,1739502657.4949195,17.81998300552368,2.094192241039333 +1739502657.5195978,17.839982986450195,35.967499829500596,1739502657.5196111,17.839982986450195,0.10450157639324509,1739502657.5196245,17.839982986450195,35.29886418819673,1739502657.5196385,17.839982986450195,41.48033203929768,1739502657.5196497,17.839982986450195,-0.09201256640846867,1739502657.5196624,17.839982986450195,-0.035631588780177526,1739502657.5196733,17.839982986450195,-0.21238512149623182,1739502657.5196843,17.839982986450195,-0.05359669991683034,1739502657.5196955,17.839982986450195,2.1093558883019803,1739502657.5197155,17.839982986450195,0.0,1739502657.5197268,17.839982986450195,0.015163647262647295,1739502657.5197382,17.839982986450195,0.002879067323763187,1739502657.5197473,17.839982986450195,2.094192241039333 +1739502657.533767,17.85998296737671,35.967499829500596,1739502657.5337722,17.85998296737671,0.10450157639324509,1739502657.5337787,17.85998296737671,35.29886418819673,1739502657.5337858,17.85998296737671,41.48033203929768,1739502657.5337896,17.85998296737671,-0.09201256640846867,1739502657.533795,17.85998296737671,-0.035631588780177526,1739502657.5337996,17.85998296737671,-0.21238512149623182,1739502657.5338042,17.85998296737671,-0.05359669991683034,1739502657.533809,17.85998296737671,2.1093558883019803,1739502657.5338135,17.85998296737671,0.0,1739502657.533818,17.85998296737671,0.015163647262647295,1739502657.5338228,17.85998296737671,0.002879067323763187,1739502657.5338273,17.85998296737671,2.094192241039333 +1739502657.5526214,17.879982948303223,35.967499829500596,1739502657.5526252,17.879982948303223,0.10450157639324509,1739502657.5526297,17.879982948303223,35.29886418819673,1739502657.5526347,17.879982948303223,41.48033203929768,1739502657.5526373,17.879982948303223,-0.09201256640846867,1739502657.552641,17.879982948303223,-0.035631588780177526,1739502657.5526443,17.879982948303223,-0.21238512149623182,1739502657.5526476,17.879982948303223,-0.05359669991683034,1739502657.5526507,17.879982948303223,2.1093558883019803,1739502657.552654,17.879982948303223,0.0,1739502657.5526574,17.879982948303223,0.015163647262647295,1739502657.5526607,17.879982948303223,0.002879067323763187,1739502657.552664,17.879982948303223,2.094192241039333 +1739502657.5737274,17.899982929229736,36.197949840600515,1739502657.5737305,17.899982929229736,0.10505819533770833,1739502657.5737348,17.899982929229736,35.553284589607145,1739502657.5737395,17.899982929229736,41.73817482639052,1739502657.5737422,17.899982929229736,-0.095890091063972,1739502657.5737457,17.899982929229736,-0.03625488782980238,1739502657.5737488,17.899982929229736,-0.21124745781746013,1739502657.573752,17.899982929229736,-0.05278154819205316,1739502657.5737548,17.899982929229736,2.11127655226103,1739502657.573758,17.899982929229736,0.0,1739502657.573761,17.899982929229736,0.015445117928195919,1739502657.5737643,17.899982929229736,0.0018590444644387876,1739502657.5737674,17.899982929229736,2.095919393973489 +1739502657.591058,17.91998291015625,36.197949840600515,1739502657.5910602,17.91998291015625,0.10505819533770833,1739502657.5910633,17.91998291015625,35.553284589607145,1739502657.591066,17.91998291015625,41.73817482639052,1739502657.591067,17.91998291015625,-0.095890091063972,1739502657.5910687,17.91998291015625,-0.03625488782980238,1739502657.5910704,17.91998291015625,-0.21124745781746013,1739502657.5910716,17.91998291015625,-0.05278154819205316,1739502657.5910728,17.91998291015625,2.11127655226103,1739502657.5910742,17.91998291015625,0.0,1739502657.5910757,17.91998291015625,0.01535715828754114,1739502657.591077,17.91998291015625,0.0018590444644387876,1739502657.5910783,17.91998291015625,2.095919393973489 +1739502657.6114788,17.939982891082764,36.197949840600515,1739502657.6114812,17.939982891082764,0.10505819533770833,1739502657.6114836,17.939982891082764,35.553284589607145,1739502657.6114864,17.939982891082764,41.73817482639052,1739502657.611488,17.939982891082764,-0.095890091063972,1739502657.6114898,17.939982891082764,-0.03625488782980238,1739502657.611491,17.939982891082764,-0.21124745781746013,1739502657.6114924,17.939982891082764,-0.05278154819205316,1739502657.6114936,17.939982891082764,2.11127655226103,1739502657.6114953,17.939982891082764,0.0,1739502657.6114962,17.939982891082764,0.01535715828754114,1739502657.6114976,17.939982891082764,0.0018590444644387876,1739502657.611499,17.939982891082764,2.095919393973489 +1739502657.632011,17.959982872009277,36.197949840600515,1739502657.6320133,17.959982872009277,0.10505819533770833,1739502657.6320162,17.959982872009277,35.553284589607145,1739502657.6320188,17.959982872009277,41.73817482639052,1739502657.63202,17.959982872009277,-0.095890091063972,1739502657.6320214,17.959982872009277,-0.03625488782980238,1739502657.6320229,17.959982872009277,-0.21124745781746013,1739502657.632024,17.959982872009277,-0.05278154819205316,1739502657.632025,17.959982872009277,2.11127655226103,1739502657.6320267,17.959982872009277,0.0,1739502657.6320279,17.959982872009277,0.01535715828754114,1739502657.6320293,17.959982872009277,0.0018590444644387876,1739502657.6320307,17.959982872009277,2.095919393973489 +1739502657.6525455,17.97998285293579,36.197949840600515,1739502657.6525493,17.97998285293579,0.10505819533770833,1739502657.6525545,17.97998285293579,35.553284589607145,1739502657.6525598,17.97998285293579,41.73817482639052,1739502657.6525629,17.97998285293579,-0.095890091063972,1739502657.6525667,17.97998285293579,-0.03625488782980238,1739502657.6525705,17.97998285293579,-0.21124745781746013,1739502657.6525736,17.97998285293579,-0.05278154819205316,1739502657.6525772,17.97998285293579,2.11127655226103,1739502657.652581,17.97998285293579,0.0,1739502657.6525846,17.97998285293579,0.01535715828754114,1739502657.6525881,17.97998285293579,0.0018590444644387876,1739502657.6525917,17.97998285293579,2.095919393973489 +1739502657.6712663,17.999982833862305,36.42858476959887,1739502657.671269,17.999982833862305,0.10538000739741804,1739502657.6712723,17.999982833862305,35.58303681725999,1739502657.6712754,17.999982833862305,41.771280760557694,1739502657.6712766,17.999982833862305,-0.09651473133127722,1739502657.6712782,17.999982833862305,-0.037770952949319425,1739502657.67128,17.999982833862305,-0.2063773045061076,1739502657.6712813,17.999982833862305,-0.055441255187339826,1739502657.6712828,17.999982833862305,2.119518389834024,1739502657.6712842,17.999982833862305,0.0,1739502657.6712854,17.999982833862305,0.024901943912700383,1739502657.671287,17.999982833862305,0.000839021605114388,1739502657.6712883,17.999982833862305,2.0975991933848275 +1739502657.691106,18.01998281478882,36.42858476959887,1739502657.6911087,18.01998281478882,0.10538000739741804,1739502657.6911113,18.01998281478882,35.58303681725999,1739502657.6911142,18.01998281478882,41.771280760557694,1739502657.6911159,18.01998281478882,-0.09651473133127722,1739502657.6911173,18.01998281478882,-0.037770952949319425,1739502657.6911192,18.01998281478882,-0.2063773045061076,1739502657.6911204,18.01998281478882,-0.055441255187339826,1739502657.6911216,18.01998281478882,2.119518389834024,1739502657.6911235,18.01998281478882,0.0,1739502657.6911247,18.01998281478882,0.021919196449196487,1739502657.6911263,18.01998281478882,0.000839021605114388,1739502657.6911278,18.01998281478882,2.0975991933848275 +1739502657.71175,18.039982795715332,36.42858476959887,1739502657.7117527,18.039982795715332,0.10538000739741804,1739502657.7117558,18.039982795715332,35.58303681725999,1739502657.711759,18.039982795715332,41.771280760557694,1739502657.711761,18.039982795715332,-0.09651473133127722,1739502657.7117627,18.039982795715332,-0.037770952949319425,1739502657.7117639,18.039982795715332,-0.2063773045061076,1739502657.7117658,18.039982795715332,-0.055441255187339826,1739502657.711767,18.039982795715332,2.119518389834024,1739502657.7117689,18.039982795715332,0.0,1739502657.71177,18.039982795715332,0.021919196449196487,1739502657.7117715,18.039982795715332,0.000839021605114388,1739502657.711773,18.039982795715332,2.0975991933848275 +1739502657.7328176,18.059982776641846,36.42858476959887,1739502657.7328212,18.059982776641846,0.10538000739741804,1739502657.7328258,18.059982776641846,35.58303681725999,1739502657.7328312,18.059982776641846,41.771280760557694,1739502657.7328343,18.059982776641846,-0.09651473133127722,1739502657.7328382,18.059982776641846,-0.037770952949319425,1739502657.7328417,18.059982776641846,-0.2063773045061076,1739502657.7328453,18.059982776641846,-0.055441255187339826,1739502657.7328486,18.059982776641846,2.119518389834024,1739502657.7328522,18.059982776641846,0.0,1739502657.7328558,18.059982776641846,0.021919196449196487,1739502657.7328594,18.059982776641846,0.000839021605114388,1739502657.732863,18.059982776641846,2.0975991933848275 +1739502657.7514513,18.07998275756836,36.42858476959887,1739502657.751454,18.07998275756836,0.10538000739741804,1739502657.7514572,18.07998275756836,35.58303681725999,1739502657.7514603,18.07998275756836,41.771280760557694,1739502657.751462,18.07998275756836,-0.09651473133127722,1739502657.7514637,18.07998275756836,-0.037770952949319425,1739502657.7514653,18.07998275756836,-0.2063773045061076,1739502657.7514665,18.07998275756836,-0.055441255187339826,1739502657.751468,18.07998275756836,2.119518389834024,1739502657.7514696,18.07998275756836,0.0,1739502657.7514708,18.07998275756836,0.021919196449196487,1739502657.7514725,18.07998275756836,0.000839021605114388,1739502657.751474,18.07998275756836,2.0975991933848275 +1739502657.7727168,18.099982738494873,36.42858476959887,1739502657.7727242,18.099982738494873,0.10538000739741804,1739502657.7727304,18.099982738494873,35.58303681725999,1739502657.7727337,18.099982738494873,41.771280760557694,1739502657.7727363,18.099982738494873,-0.09651473133127722,1739502657.7727382,18.099982738494873,-0.037770952949319425,1739502657.7727406,18.099982738494873,-0.2063773045061076,1739502657.772743,18.099982738494873,-0.055441255187339826,1739502657.772745,18.099982738494873,2.119518389834024,1739502657.7727478,18.099982738494873,0.0,1739502657.7727501,18.099982738494873,0.021919196449196487,1739502657.7727525,18.099982738494873,0.000839021605114388,1739502657.772755,18.099982738494873,2.0975991933848275 +1739502657.7927303,18.119982719421387,36.65944652333276,1739502657.7927356,18.119982719421387,0.105466644449983,1739502657.7927413,18.119982719421387,36.297391000374375,1739502657.7927487,18.119982719421387,42.4904452061596,1739502657.792753,18.119982719421387,-0.10834206286587447,1739502657.7927582,18.119982719421387,-0.03665117646754546,1739502657.792763,18.119982719421387,-0.21275328574439195,1739502657.7927678,18.119982719421387,-0.04798782252039783,1739502657.7927723,18.119982719421387,2.108734708245211,1739502657.7927773,18.119982719421387,0.0,1739502657.7927818,18.119982719421387,0.0026568310093212618,1739502657.7927866,18.119982719421387,6.283004305925377,1739502657.7927914,18.119982719421387,2.1000583840892415 +1739502657.8114529,18.1399827003479,36.65944652333276,1739502657.8114555,18.1399827003479,0.105466644449983,1739502657.8114588,18.1399827003479,36.297391000374375,1739502657.8114617,18.1399827003479,42.4904452061596,1739502657.811463,18.1399827003479,-0.10834206286587447,1739502657.811465,18.1399827003479,-0.03665117646754546,1739502657.8114665,18.1399827003479,-0.21275328574439195,1739502657.8114681,18.1399827003479,-0.04798782252039783,1739502657.8114693,18.1399827003479,2.108734708245211,1739502657.8114717,18.1399827003479,0.0,1739502657.811473,18.1399827003479,0.008676324155969528,1739502657.8114743,18.1399827003479,6.283004305925377,1739502657.811476,18.1399827003479,2.1000583840892415 +1739502657.8309834,18.159982681274414,36.65944652333276,1739502657.830986,18.159982681274414,0.105466644449983,1739502657.830989,18.159982681274414,36.297391000374375,1739502657.830992,18.159982681274414,42.4904452061596,1739502657.8309932,18.159982681274414,-0.10834206286587447,1739502657.8309948,18.159982681274414,-0.03665117646754546,1739502657.8309968,18.159982681274414,-0.21275328574439195,1739502657.830998,18.159982681274414,-0.04798782252039783,1739502657.8309996,18.159982681274414,2.108734708245211,1739502657.831001,18.159982681274414,0.0,1739502657.8310025,18.159982681274414,0.008676324155969528,1739502657.831004,18.159982681274414,6.283004305925377,1739502657.8310053,18.159982681274414,2.1000583840892415 +1739502657.8527472,18.179982662200928,36.65944652333276,1739502657.8527496,18.179982662200928,0.105466644449983,1739502657.8527524,18.179982662200928,36.297391000374375,1739502657.8527553,18.179982662200928,42.4904452061596,1739502657.8527565,18.179982662200928,-0.10834206286587447,1739502657.8527582,18.179982662200928,-0.03665117646754546,1739502657.8527596,18.179982662200928,-0.21275328574439195,1739502657.8527608,18.179982662200928,-0.04798782252039783,1739502657.8527625,18.179982662200928,2.108734708245211,1739502657.852764,18.179982662200928,0.0,1739502657.852765,18.179982662200928,0.008676324155969528,1739502657.8527668,18.179982662200928,6.283004305925377,1739502657.8527684,18.179982662200928,2.1000583840892415 +1739502657.8709714,18.19998264312744,36.65944652333276,1739502657.870974,18.19998264312744,0.105466644449983,1739502657.8709767,18.19998264312744,36.297391000374375,1739502657.87098,18.19998264312744,42.4904452061596,1739502657.8709815,18.19998264312744,-0.10834206286587447,1739502657.8709834,18.19998264312744,-0.03665117646754546,1739502657.8709857,18.19998264312744,-0.21275328574439195,1739502657.8709872,18.19998264312744,-0.04798782252039783,1739502657.8709886,18.19998264312744,2.108734708245211,1739502657.8709903,18.19998264312744,0.0,1739502657.870992,18.19998264312744,0.008676324155969528,1739502657.8709934,18.19998264312744,6.283004305925377,1739502657.870995,18.19998264312744,2.1000583840892415 +1739502657.8915415,18.219982624053955,36.89050324110286,1739502657.8915439,18.219982624053955,0.10531768593398283,1739502657.891547,18.219982624053955,36.32812139487928,1739502657.8915496,18.219982624053955,42.52308840565507,1739502657.891551,18.219982624053955,-0.1089821256010798,1739502657.8915527,18.219982624053955,-0.03802809776985338,1739502657.8915544,18.219982624053955,-0.2075347879979216,1739502657.8915555,18.219982624053955,-0.05016119989417237,1739502657.8915572,18.219982624053955,2.117556652208302,1739502657.891559,18.219982624053955,0.0,1739502657.8915606,18.219982624053955,0.020112551865171868,1739502657.891562,18.219982624053955,6.281984283066052,1739502657.8915632,18.219982624053955,2.101017923845437 +1739502657.9114373,18.23998260498047,36.89050324110286,1739502657.9114404,18.23998260498047,0.10531768593398283,1739502657.9114437,18.23998260498047,36.32812139487928,1739502657.9114468,18.23998260498047,42.52308840565507,1739502657.9114482,18.23998260498047,-0.1089821256010798,1739502657.9114501,18.23998260498047,-0.03802809776985338,1739502657.9114516,18.23998260498047,-0.2075347879979216,1739502657.9114532,18.23998260498047,-0.05016119989417237,1739502657.9114544,18.23998260498047,2.117556652208302,1739502657.911456,18.23998260498047,0.0,1739502657.9114573,18.23998260498047,0.016538728362864852,1739502657.9114587,18.23998260498047,6.281984283066052,1739502657.9114604,18.23998260498047,2.101017923845437 +1739502657.931348,18.259982585906982,36.89050324110286,1739502657.9313505,18.259982585906982,0.10531768593398283,1739502657.9313538,18.259982585906982,36.32812139487928,1739502657.931357,18.259982585906982,42.52308840565507,1739502657.9313586,18.259982585906982,-0.1089821256010798,1739502657.9313605,18.259982585906982,-0.03802809776985338,1739502657.9313622,18.259982585906982,-0.2075347879979216,1739502657.9313638,18.259982585906982,-0.05016119989417237,1739502657.931365,18.259982585906982,2.117556652208302,1739502657.931367,18.259982585906982,0.0,1739502657.9313684,18.259982585906982,0.016538728362864852,1739502657.93137,18.259982585906982,6.281984283066052,1739502657.9313715,18.259982585906982,2.101017923845437 +1739502657.951649,18.279982566833496,36.89050324110286,1739502657.9516516,18.279982566833496,0.10531768593398283,1739502657.951655,18.279982566833496,36.32812139487928,1739502657.951658,18.279982566833496,42.52308840565507,1739502657.9516594,18.279982566833496,-0.1089821256010798,1739502657.9516613,18.279982566833496,-0.03802809776985338,1739502657.9516628,18.279982566833496,-0.2075347879979216,1739502657.9516644,18.279982566833496,-0.05016119989417237,1739502657.9516656,18.279982566833496,2.117556652208302,1739502657.9516678,18.279982566833496,0.0,1739502657.9516695,18.279982566833496,0.016538728362864852,1739502657.9516711,18.279982566833496,6.281984283066052,1739502657.9516726,18.279982566833496,2.101017923845437 +1739502657.9728963,18.29998254776001,36.89050324110286,1739502657.972899,18.29998254776001,0.10531768593398283,1739502657.972902,18.29998254776001,36.32812139487928,1739502657.9729054,18.29998254776001,42.52308840565507,1739502657.972907,18.29998254776001,-0.1089821256010798,1739502657.9729087,18.29998254776001,-0.03802809776985338,1739502657.9729106,18.29998254776001,-0.2075347879979216,1739502657.972912,18.29998254776001,-0.05016119989417237,1739502657.9729135,18.29998254776001,2.117556652208302,1739502657.9729152,18.29998254776001,0.0,1739502657.9729168,18.29998254776001,0.016538728362864852,1739502657.9729185,18.29998254776001,6.281984283066052,1739502657.9729202,18.29998254776001,2.101017923845437 +1739502657.9916844,18.319982528686523,36.89050324110286,1739502657.9916878,18.319982528686523,0.10531768593398283,1739502657.991691,18.319982528686523,36.32812139487928,1739502657.991694,18.319982528686523,42.52308840565507,1739502657.9916956,18.319982528686523,-0.1089821256010798,1739502657.9916973,18.319982528686523,-0.03802809776985338,1739502657.9916992,18.319982528686523,-0.2075347879979216,1739502657.9917006,18.319982528686523,-0.05016119989417237,1739502657.9917023,18.319982528686523,2.117556652208302,1739502657.9917042,18.319982528686523,0.0,1739502657.991706,18.319982528686523,0.016538728362864852,1739502657.9917073,18.319982528686523,6.281984283066052,1739502657.9917092,18.319982528686523,2.101017923845437 +1739502658.012938,18.339982509613037,37.1217123584171,1739502658.012942,18.339982509613037,0.10493278123846217,1739502658.0129476,18.339982509613037,36.358871822577385,1739502658.0129535,18.339982509613037,42.557595603315,1739502658.0129569,18.339982509613037,-0.10966525947158418,1739502658.0129614,18.339982509613037,-0.03945755461532591,1739502658.0129652,18.339982509613037,-0.20252416929937744,1739502658.012969,18.339982509613037,-0.05255052854743525,1739502658.0129728,18.339982509613037,2.126061902611861,1739502658.012977,18.339982509613037,0.0,1739502658.0129807,18.339982509613037,0.026172890900288917,1739502658.0129845,18.339982509613037,6.280964260206727,1739502658.0129886,18.339982509613037,2.102899689478471 +1739502658.0415154,18.35998249053955,37.1217123584171,1739502658.0415242,18.35998249053955,0.10493278123846217,1739502658.0415344,18.35998249053955,36.358871822577385,1739502658.0415444,18.35998249053955,42.557595603315,1739502658.0415497,18.35998249053955,-0.10966525947158418,1739502658.0415554,18.35998249053955,-0.03945755461532591,1739502658.0415604,18.35998249053955,-0.20252416929937744,1739502658.0415652,18.35998249053955,-0.05255052854743525,1739502658.04157,18.35998249053955,2.126061902611861,1739502658.0415757,18.35998249053955,0.0,1739502658.041581,18.35998249053955,0.02316221313338973,1739502658.041586,18.35998249053955,6.280964260206727,1739502658.041591,18.35998249053955,2.102899689478471 +1739502658.072805,18.379982471466064,37.1217123584171,1739502658.0728106,18.379982471466064,0.10493278123846217,1739502658.0728178,18.379982471466064,36.358871822577385,1739502658.0728245,18.379982471466064,42.557595603315,1739502658.0728278,18.379982471466064,-0.10966525947158418,1739502658.0728323,18.379982471466064,-0.03945755461532591,1739502658.072836,18.379982471466064,-0.20252416929937744,1739502658.0728395,18.379982471466064,-0.05255052854743525,1739502658.0728428,18.379982471466064,2.126061902611861,1739502658.072847,18.379982471466064,0.0,1739502658.0728502,18.379982471466064,0.02316221313338973,1739502658.0728543,18.379982471466064,6.280964260206727,1739502658.0728579,18.379982471466064,2.102899689478471 +1739502658.084484,18.409982442855835,37.1217123584171,1739502658.084491,18.409982442855835,0.10493278123846217,1739502658.0844991,18.409982442855835,36.358871822577385,1739502658.084507,18.409982442855835,42.557595603315,1739502658.0845106,18.409982442855835,-0.10966525947158418,1739502658.084515,18.409982442855835,-0.03945755461532591,1739502658.0845187,18.409982442855835,-0.20252416929937744,1739502658.0845225,18.409982442855835,-0.05255052854743525,1739502658.084526,18.409982442855835,2.126061902611861,1739502658.08453,18.409982442855835,0.0,1739502658.0845337,18.409982442855835,0.02316221313338973,1739502658.0845373,18.409982442855835,6.280964260206727,1739502658.084541,18.409982442855835,2.102899689478471 +1739502658.1030002,18.42998242378235,37.1217123584171,1739502658.1030045,18.42998242378235,0.10493278123846217,1739502658.1030087,18.42998242378235,36.358871822577385,1739502658.1030123,18.42998242378235,42.557595603315,1739502658.1030145,18.42998242378235,-0.10966525947158418,1739502658.1030166,18.42998242378235,-0.03945755461532591,1739502658.103019,18.42998242378235,-0.20252416929937744,1739502658.103021,18.42998242378235,-0.05255052854743525,1739502658.1030226,18.42998242378235,2.126061902611861,1739502658.1030252,18.42998242378235,0.0,1739502658.103027,18.42998242378235,0.02316221313338973,1739502658.103029,18.42998242378235,6.280964260206727,1739502658.1030312,18.42998242378235,2.102899689478471 +1739502658.122973,18.449982404708862,37.35315795462964,1739502658.1229773,18.449982404708862,0.10431139501524544,1739502658.1229827,18.449982404708862,36.85321938278743,1739502658.1229868,18.449982404708862,43.05696260827141,1739502658.1229887,18.449982404708862,-0.11880601008184657,1739502658.122991,18.449982404708862,-0.039097360626499315,1739502658.1229932,18.449982404708862,-0.20462983639958746,1739502658.122995,18.449982404708862,-0.04822802111464228,1739502658.1229968,18.449982404708862,2.1224834945514286,1739502658.1229987,18.449982404708862,0.0,1739502658.1230006,18.449982404708862,0.01423585718074313,1739502658.1230028,18.449982404708862,6.279944237347403,1739502658.123005,18.449982404708862,2.1054581493065525 +1739502658.1428711,18.469982385635376,37.35315795462964,1739502658.1428766,18.469982385635376,0.10431139501524544,1739502658.1428833,18.469982385635376,36.85321938278743,1739502658.1428907,18.469982385635376,43.05696260827141,1739502658.1428947,18.469982385635376,-0.11880601008184657,1739502658.1428998,18.469982385635376,-0.039097360626499315,1739502658.1429045,18.469982385635376,-0.20462983639958746,1739502658.1429088,18.469982385635376,-0.04822802111464228,1739502658.142913,18.469982385635376,2.1224834945514286,1739502658.1429176,18.469982385635376,0.0,1739502658.142922,18.469982385635376,0.01702534524487609,1739502658.1429265,18.469982385635376,6.279944237347403,1739502658.1429307,18.469982385635376,2.1054581493065525 +1739502658.1623652,18.48998236656189,37.35315795462964,1739502658.1623712,18.48998236656189,0.10431139501524544,1739502658.1623778,18.48998236656189,36.85321938278743,1739502658.162385,18.48998236656189,43.05696260827141,1739502658.1623893,18.48998236656189,-0.11880601008184657,1739502658.1623943,18.48998236656189,-0.039097360626499315,1739502658.1623993,18.48998236656189,-0.20462983639958746,1739502658.1624036,18.48998236656189,-0.04822802111464228,1739502658.1624074,18.48998236656189,2.1224834945514286,1739502658.1624124,18.48998236656189,0.0,1739502658.162417,18.48998236656189,0.01702534524487609,1739502658.1624217,18.48998236656189,6.279944237347403,1739502658.1624267,18.48998236656189,2.1054581493065525 +1739502658.1875331,18.509982347488403,37.35315795462964,1739502658.1875427,18.509982347488403,0.10431139501524544,1739502658.1875541,18.509982347488403,36.85321938278743,1739502658.1875656,18.509982347488403,43.05696260827141,1739502658.1875699,18.509982347488403,-0.11880601008184657,1739502658.1875763,18.509982347488403,-0.039097360626499315,1739502658.1875813,18.509982347488403,-0.20462983639958746,1739502658.1875858,18.509982347488403,-0.04822802111464228,1739502658.1875906,18.509982347488403,2.1224834945514286,1739502658.187596,18.509982347488403,0.0,1739502658.1876009,18.509982347488403,0.01702534524487609,1739502658.1876063,18.509982347488403,6.279944237347403,1739502658.1876113,18.509982347488403,2.1054581493065525 +1739502658.2071366,18.529982328414917,37.35315795462964,1739502658.2071428,18.529982328414917,0.10431139501524544,1739502658.207151,18.529982328414917,36.85321938278743,1739502658.2071579,18.529982328414917,43.05696260827141,1739502658.207161,18.529982328414917,-0.11880601008184657,1739502658.2071652,18.529982328414917,-0.039097360626499315,1739502658.2071688,18.529982328414917,-0.20462983639958746,1739502658.2071726,18.529982328414917,-0.04822802111464228,1739502658.2071762,18.529982328414917,2.1224834945514286,1739502658.2071803,18.529982328414917,0.0,1739502658.2071838,18.529982328414917,0.01702534524487609,1739502658.2071874,18.529982328414917,6.279944237347403,1739502658.207191,18.529982328414917,2.1054581493065525 +1739502658.2274983,18.54998230934143,37.58485128328884,1739502658.2275057,18.54998230934143,0.10345301594667067,1739502658.2275155,18.54998230934143,36.88426543044869,1739502658.227526,18.54998230934143,43.091738484634746,1739502658.2275317,18.54998230934143,-0.11938240582267541,1739502658.2275393,18.54998230934143,-0.04044279627242325,1739502658.2275462,18.54998230934143,-0.19936811297401408,1739502658.2275527,18.54998230934143,-0.05040262517869,1739502658.2275593,18.54998230934143,2.1314366618664495,1739502658.2275662,18.54998230934143,0.0,1739502658.2275732,18.54998230934143,0.027332060677027432,1739502658.22758,18.54998230934143,6.278924214488079,1739502658.2275867,18.54998230934143,2.1073254518737237 +1739502658.2432277,18.569982290267944,37.58485128328884,1739502658.2432325,18.569982290267944,0.10345301594667067,1739502658.243237,18.569982290267944,36.88426543044869,1739502658.243241,18.569982290267944,43.091738484634746,1739502658.2432427,18.569982290267944,-0.11938240582267541,1739502658.2432454,18.569982290267944,-0.04044279627242325,1739502658.2432473,18.569982290267944,-0.19936811297401408,1739502658.2432494,18.569982290267944,-0.05040262517869,1739502658.2432516,18.569982290267944,2.1314366618664495,1739502658.2432537,18.569982290267944,0.0,1739502658.2432556,18.569982290267944,0.02411120999272587,1739502658.2432575,18.569982290267944,6.278924214488079,1739502658.2432594,18.569982290267944,2.1073254518737237 +1739502658.2634673,18.589982271194458,37.58485128328884,1739502658.2634716,18.589982271194458,0.10345301594667067,1739502658.263476,18.589982271194458,36.88426543044869,1739502658.2634797,18.589982271194458,43.091738484634746,1739502658.2634816,18.589982271194458,-0.11938240582267541,1739502658.2634842,18.589982271194458,-0.04044279627242325,1739502658.2634864,18.589982271194458,-0.19936811297401408,1739502658.263489,18.589982271194458,-0.05040262517869,1739502658.263491,18.589982271194458,2.1314366618664495,1739502658.2634933,18.589982271194458,0.0,1739502658.263496,18.589982271194458,0.02411120999272587,1739502658.263498,18.589982271194458,6.278924214488079,1739502658.2635,18.589982271194458,2.1073254518737237 +1739502658.2839692,18.60998225212097,37.58485128328884,1739502658.2839742,18.60998225212097,0.10345301594667067,1739502658.2839792,18.60998225212097,36.88426543044869,1739502658.283985,18.60998225212097,43.091738484634746,1739502658.283988,18.60998225212097,-0.11938240582267541,1739502658.283992,18.60998225212097,-0.04044279627242325,1739502658.2839956,18.60998225212097,-0.19936811297401408,1739502658.2839992,18.60998225212097,-0.05040262517869,1739502658.2840028,18.60998225212097,2.1314366618664495,1739502658.2840064,18.60998225212097,0.0,1739502658.28401,18.60998225212097,0.02411120999272587,1739502658.2840137,18.60998225212097,6.278924214488079,1739502658.2840176,18.60998225212097,2.1073254518737237 +1739502658.312004,18.629982233047485,37.58485128328884,1739502658.3120115,18.629982233047485,0.10345301594667067,1739502658.3120208,18.629982233047485,36.88426543044869,1739502658.3120315,18.629982233047485,43.091738484634746,1739502658.3120375,18.629982233047485,-0.11938240582267541,1739502658.312045,18.629982233047485,-0.04044279627242325,1739502658.312052,18.629982233047485,-0.19936811297401408,1739502658.3120587,18.629982233047485,-0.05040262517869,1739502658.3120654,18.629982233047485,2.1314366618664495,1739502658.3120728,18.629982233047485,0.0,1739502658.3120794,18.629982233047485,0.02411120999272587,1739502658.3120863,18.629982233047485,6.278924214488079,1739502658.3120933,18.629982233047485,2.1073254518737237 +1739502658.3257742,18.649982213974,37.58485128328884,1739502658.3257804,18.649982213974,0.10345301594667067,1739502658.3257885,18.649982213974,36.88426543044869,1739502658.3257966,18.649982213974,43.091738484634746,1739502658.3257995,18.649982213974,-0.11938240582267541,1739502658.325804,18.649982213974,-0.04044279627242325,1739502658.3258102,18.649982213974,-0.19936811297401408,1739502658.3258154,18.649982213974,-0.05040262517869,1739502658.3258183,18.649982213974,2.1314366618664495,1739502658.3258207,18.649982213974,0.0,1739502658.325823,18.649982213974,0.02411120999272587,1739502658.325825,18.649982213974,6.278924214488079,1739502658.3258271,18.649982213974,2.1073254518737237 +1739502658.3445892,18.669982194900513,37.8167928253646,1739502658.3445942,18.669982194900513,0.10235711953415816,1739502658.3445995,18.669982194900513,37.03230602530713,1739502658.344605,18.669982194900513,43.24517595310344,1739502658.344608,18.669982194900513,-0.12116175953103442,1739502658.3446136,18.669982194900513,-0.041152711544168184,1739502658.3446171,18.669982194900513,-0.19484797678833315,1739502658.3446214,18.669982194900513,-0.050691961408393195,1739502658.344625,18.669982194900513,2.1391581214582716,1739502658.3446286,18.669982194900513,0.0,1739502658.344632,18.669982194900513,0.03140948059587006,1739502658.3446357,18.669982194900513,6.277904191628754,1739502658.344639,18.669982194900513,2.1100293519212348 +1739502658.366459,18.689982175827026,37.8167928253646,1739502658.3664641,18.689982175827026,0.10235711953415816,1739502658.3664708,18.689982175827026,37.03230602530713,1739502658.3664784,18.689982175827026,43.24517595310344,1739502658.3664825,18.689982175827026,-0.12116175953103442,1739502658.3664887,18.689982175827026,-0.041152711544168184,1739502658.3664935,18.689982175827026,-0.19484797678833315,1739502658.3664982,18.689982175827026,-0.050691961408393195,1739502658.366503,18.689982175827026,2.1391581214582716,1739502658.366508,18.689982175827026,0.0,1739502658.366513,18.689982175827026,0.029128769537036803,1739502658.3665178,18.689982175827026,6.277904191628754,1739502658.3665228,18.689982175827026,2.1100293519212348 +1739502658.3861039,18.70998215675354,37.8167928253646,1739502658.38611,18.70998215675354,0.10235711953415816,1739502658.386118,18.70998215675354,37.03230602530713,1739502658.3861268,18.70998215675354,43.24517595310344,1739502658.3861322,18.70998215675354,-0.12116175953103442,1739502658.3861387,18.70998215675354,-0.041152711544168184,1739502658.3861442,18.70998215675354,-0.19484797678833315,1739502658.3861501,18.70998215675354,-0.050691961408393195,1739502658.3861558,18.70998215675354,2.1391581214582716,1739502658.3861616,18.70998215675354,0.0,1739502658.3861673,18.70998215675354,0.029128769537036803,1739502658.3861732,18.70998215675354,6.277904191628754,1739502658.386179,18.70998215675354,2.1100293519212348 +1739502658.4040189,18.729982137680054,37.8167928253646,1739502658.404022,18.729982137680054,0.10235711953415816,1739502658.4040265,18.729982137680054,37.03230602530713,1739502658.4040318,18.729982137680054,43.24517595310344,1739502658.4040346,18.729982137680054,-0.12116175953103442,1739502658.4040382,18.729982137680054,-0.041152711544168184,1739502658.4040413,18.729982137680054,-0.19484797678833315,1739502658.4040446,18.729982137680054,-0.050691961408393195,1739502658.404048,18.729982137680054,2.1391581214582716,1739502658.4040513,18.729982137680054,0.0,1739502658.4040542,18.729982137680054,0.029128769537036803,1739502658.4040575,18.729982137680054,6.277904191628754,1739502658.4040608,18.729982137680054,2.1100293519212348 +1739502658.4231608,18.749982118606567,37.8167928253646,1739502658.4231637,18.749982118606567,0.10235711953415816,1739502658.4231675,18.749982118606567,37.03230602530713,1739502658.4231706,18.749982118606567,43.24517595310344,1739502658.4231718,18.749982118606567,-0.12116175953103442,1739502658.4231734,18.749982118606567,-0.041152711544168184,1739502658.4231746,18.749982118606567,-0.19484797678833315,1739502658.4231763,18.749982118606567,-0.050691961408393195,1739502658.4231775,18.749982118606567,2.1391581214582716,1739502658.4231791,18.749982118606567,0.0,1739502658.4231806,18.749982118606567,0.029128769537036803,1739502658.4231818,18.749982118606567,6.277904191628754,1739502658.4231834,18.749982118606567,2.1100293519212348 +1739502658.4427974,18.76998209953308,38.04905059597657,1739502658.4428,18.76998209953308,0.10102280937972985,1739502658.4428036,18.76998209953308,37.6444682091934,1739502658.4428062,18.76998209953308,43.86362133344525,1739502658.442808,18.76998209953308,-0.13062616501871785,1739502658.4428093,18.76998209953308,-0.039818336629110496,1739502658.4428108,18.76998209953308,-0.19500620311602937,1739502658.4428122,18.76998209953308,-0.04422360216641291,1739502658.4428134,18.76998209953308,2.138887361688027,1739502658.4428153,18.76998209953308,0.0,1739502658.4428165,18.76998209953308,0.02410583801880153,1739502658.4428182,18.76998209953308,6.2768841687694295,1739502658.4428198,18.76998209953308,2.113211856540623 +1739502658.463943,18.789982080459595,38.04905059597657,1739502658.463947,18.789982080459595,0.10102280937972985,1739502658.4639518,18.789982080459595,37.6444682091934,1739502658.4639573,18.789982080459595,43.86362133344525,1739502658.4639602,18.789982080459595,-0.13062616501871785,1739502658.4639642,18.789982080459595,-0.039818336629110496,1739502658.4639676,18.789982080459595,-0.19500620311602937,1739502658.4639711,18.789982080459595,-0.04422360216641291,1739502658.4639747,18.789982080459595,2.138887361688027,1739502658.4639783,18.789982080459595,0.0,1739502658.4639816,18.789982080459595,0.02567550514740402,1739502658.4639852,18.789982080459595,6.2768841687694295,1739502658.4639885,18.789982080459595,2.113211856540623 +1739502658.483652,18.80998206138611,38.04905059597657,1739502658.483656,18.80998206138611,0.10102280937972985,1739502658.4836605,18.80998206138611,37.6444682091934,1739502658.483666,18.80998206138611,43.86362133344525,1739502658.4836688,18.80998206138611,-0.13062616501871785,1739502658.4836726,18.80998206138611,-0.039818336629110496,1739502658.4836762,18.80998206138611,-0.19500620311602937,1739502658.4836795,18.80998206138611,-0.04422360216641291,1739502658.4836829,18.80998206138611,2.138887361688027,1739502658.4836864,18.80998206138611,0.0,1739502658.4836898,18.80998206138611,0.02567550514740402,1739502658.4836936,18.80998206138611,6.2768841687694295,1739502658.483697,18.80998206138611,2.113211856540623 +1739502658.5038214,18.829982042312622,38.04905059597657,1739502658.5038252,18.829982042312622,0.10102280937972985,1739502658.5038297,18.829982042312622,37.6444682091934,1739502658.503835,18.829982042312622,43.86362133344525,1739502658.5038376,18.829982042312622,-0.13062616501871785,1739502658.5038416,18.829982042312622,-0.039818336629110496,1739502658.5038452,18.829982042312622,-0.19500620311602937,1739502658.5038486,18.829982042312622,-0.04422360216641291,1739502658.503852,18.829982042312622,2.138887361688027,1739502658.5038555,18.829982042312622,0.0,1739502658.503859,18.829982042312622,0.02567550514740402,1739502658.5038626,18.829982042312622,6.2768841687694295,1739502658.5038662,18.829982042312622,2.113211856540623 +1739502658.5238023,18.849982023239136,38.04905059597657,1739502658.5238066,18.849982023239136,0.10102280937972985,1739502658.5238113,18.849982023239136,37.6444682091934,1739502658.5238166,18.849982023239136,43.86362133344525,1739502658.5238197,18.849982023239136,-0.13062616501871785,1739502658.5238235,18.849982023239136,-0.039818336629110496,1739502658.5238268,18.849982023239136,-0.19500620311602937,1739502658.5238304,18.849982023239136,-0.04422360216641291,1739502658.5238338,18.849982023239136,2.138887361688027,1739502658.5238378,18.849982023239136,0.0,1739502658.5238414,18.849982023239136,0.02567550514740402,1739502658.5238447,18.849982023239136,6.2768841687694295,1739502658.5238483,18.849982023239136,2.113211856540623 +1739502658.5437942,18.86998200416565,38.04905059597657,1739502658.5437984,18.86998200416565,0.10102280937972985,1739502658.5438032,18.86998200416565,37.6444682091934,1739502658.5438085,18.86998200416565,43.86362133344525,1739502658.5438113,18.86998200416565,-0.13062616501871785,1739502658.5438151,18.86998200416565,-0.039818336629110496,1739502658.5438187,18.86998200416565,-0.19500620311602937,1739502658.543822,18.86998200416565,-0.04422360216641291,1739502658.5438254,18.86998200416565,2.138887361688027,1739502658.543829,18.86998200416565,0.0,1739502658.5438323,18.86998200416565,0.02567550514740402,1739502658.5438359,18.86998200416565,6.2768841687694295,1739502658.5438395,18.86998200416565,2.113211856540623 +1739502658.5637972,18.889981985092163,38.28163642249572,1739502658.563801,18.889981985092163,0.09944936634930457,1739502658.5638056,18.889981985092163,37.67563313650393,1739502658.563811,18.889981985092163,43.90033944404947,1739502658.563814,18.889981985092163,-0.13135325631781136,1739502658.5638177,18.889981985092163,-0.04105448123484763,1739502658.5638213,18.889981985092163,-0.18966137377874817,1739502658.5638247,18.889981985092163,-0.046057635334871366,1739502658.5638282,18.889981985092163,2.1480525325697193,1739502658.5638318,18.889981985092163,0.0,1739502658.5638351,18.889981985092163,0.034962751734506095,1739502658.5638387,18.889981985092163,6.275864145910106,1739502658.563842,18.889981985092163,2.1159920472965568 +1739502658.5837896,18.909981966018677,38.28163642249572,1739502658.5837932,18.909981966018677,0.09944936634930457,1739502658.5837982,18.909981966018677,37.67563313650393,1739502658.5838034,18.909981966018677,43.90033944404947,1739502658.5838065,18.909981966018677,-0.13135325631781136,1739502658.5838106,18.909981966018677,-0.04105448123484763,1739502658.583814,18.909981966018677,-0.18966137377874817,1739502658.5838172,18.909981966018677,-0.046057635334871366,1739502658.5838208,18.909981966018677,2.1480525325697193,1739502658.5838242,18.909981966018677,0.0,1739502658.5838277,18.909981966018677,0.03206048527316252,1739502658.5838313,18.909981966018677,6.275864145910106,1739502658.5838346,18.909981966018677,2.1159920472965568 +1739502658.6039953,18.92998194694519,38.28163642249572,1739502658.6039994,18.92998194694519,0.09944936634930457,1739502658.6040044,18.92998194694519,37.67563313650393,1739502658.6040096,18.92998194694519,43.90033944404947,1739502658.6040125,18.92998194694519,-0.13135325631781136,1739502658.6040163,18.92998194694519,-0.04105448123484763,1739502658.6040196,18.92998194694519,-0.18966137377874817,1739502658.6040232,18.92998194694519,-0.046057635334871366,1739502658.6040266,18.92998194694519,2.1480525325697193,1739502658.6040301,18.92998194694519,0.0,1739502658.6040335,18.92998194694519,0.03206048527316252,1739502658.604037,18.92998194694519,6.275864145910106,1739502658.6040406,18.92998194694519,2.1159920472965568 +1739502658.6235466,18.949981927871704,38.28163642249572,1739502658.6235504,18.949981927871704,0.09944936634930457,1739502658.6235554,18.949981927871704,37.67563313650393,1739502658.6235607,18.949981927871704,43.90033944404947,1739502658.6235635,18.949981927871704,-0.13135325631781136,1739502658.6235673,18.949981927871704,-0.04105448123484763,1739502658.623571,18.949981927871704,-0.18966137377874817,1739502658.6235743,18.949981927871704,-0.046057635334871366,1739502658.6235778,18.949981927871704,2.1480525325697193,1739502658.6235814,18.949981927871704,0.0,1739502658.6235847,18.949981927871704,0.03206048527316252,1739502658.6235883,18.949981927871704,6.275864145910106,1739502658.623592,18.949981927871704,2.1159920472965568 +1739502658.6438987,18.969981908798218,38.28163642249572,1739502658.6439025,18.969981908798218,0.09944936634930457,1739502658.643907,18.969981908798218,37.67563313650393,1739502658.6439126,18.969981908798218,43.90033944404947,1739502658.6439152,18.969981908798218,-0.13135325631781136,1739502658.6439188,18.969981908798218,-0.04105448123484763,1739502658.643922,18.969981908798218,-0.18966137377874817,1739502658.6439254,18.969981908798218,-0.046057635334871366,1739502658.643929,18.969981908798218,2.1480525325697193,1739502658.6439326,18.969981908798218,0.0,1739502658.643936,18.969981908798218,0.03206048527316252,1739502658.6439393,18.969981908798218,6.275864145910106,1739502658.6439428,18.969981908798218,2.1159920472965568 +1739502658.6683123,18.98998188972473,38.51456262701955,1739502658.6683192,18.98998188972473,0.09763601110562181,1739502658.6683283,18.98998188972473,37.706843434554884,1739502658.6683388,18.98998188972473,43.93854774296237,1739502658.6683445,18.98998188972473,-0.132,1739502658.668352,18.98998188972473,-0.04231187054420462,1739502658.6683588,18.98998188972473,-0.18438608870957382,1739502658.6683657,18.98998188972473,-0.048043818427826235,1739502658.6683724,18.98998188972473,2.157136959826355,1739502658.6683793,18.98998188972473,0.0,1739502658.6683862,18.98998188972473,0.040180088330181246,1739502658.6683931,18.98998188972473,6.274844123050781,1739502658.6684,18.98998188972473,2.1194942491151263 +1739502658.6844344,19.009981870651245,38.51456262701955,1739502658.6844385,19.009981870651245,0.09763601110562181,1739502658.6844437,19.009981870651245,37.706843434554884,1739502658.6844494,19.009981870651245,43.93854774296237,1739502658.6844528,19.009981870651245,-0.132,1739502658.6844575,19.009981870651245,-0.04231187054420462,1739502658.6844614,19.009981870651245,-0.18438608870957382,1739502658.6844654,19.009981870651245,-0.048043818427826235,1739502658.6844692,19.009981870651245,2.157136959826355,1739502658.6844733,19.009981870651245,0.0,1739502658.684477,19.009981870651245,0.03764271071122849,1739502658.6844814,19.009981870651245,6.274844123050781,1739502658.6844854,19.009981870651245,2.1194942491151263 +1739502658.7064257,19.02998185157776,38.51456262701955,1739502658.7064304,19.02998185157776,0.09763601110562181,1739502658.7064369,19.02998185157776,37.706843434554884,1739502658.7064445,19.02998185157776,43.93854774296237,1739502658.7064486,19.02998185157776,-0.132,1739502658.706454,19.02998185157776,-0.04231187054420462,1739502658.7064586,19.02998185157776,-0.18438608870957382,1739502658.7064636,19.02998185157776,-0.048043818427826235,1739502658.706468,19.02998185157776,2.157136959826355,1739502658.7064729,19.02998185157776,0.0,1739502658.7064779,19.02998185157776,0.03764271071122849,1739502658.7064826,19.02998185157776,6.274844123050781,1739502658.7064877,19.02998185157776,2.1194942491151263 +1739502658.7239916,19.049981832504272,38.51456262701955,1739502658.723995,19.049981832504272,0.09763601110562181,1739502658.7239995,19.049981832504272,37.706843434554884,1739502658.7240043,19.049981832504272,43.93854774296237,1739502658.724007,19.049981832504272,-0.132,1739502658.7240105,19.049981832504272,-0.04231187054420462,1739502658.7240138,19.049981832504272,-0.18438608870957382,1739502658.7240174,19.049981832504272,-0.048043818427826235,1739502658.7240205,19.049981832504272,2.157136959826355,1739502658.7240238,19.049981832504272,0.0,1739502658.7240272,19.049981832504272,0.03764271071122849,1739502658.7240305,19.049981832504272,6.274844123050781,1739502658.7240338,19.049981832504272,2.1194942491151263 +1739502658.7442322,19.069981813430786,38.51456262701955,1739502658.744236,19.069981813430786,0.09763601110562181,1739502658.7442403,19.069981813430786,37.706843434554884,1739502658.7442665,19.069981813430786,43.93854774296237,1739502658.7442694,19.069981813430786,-0.132,1739502658.7442732,19.069981813430786,-0.04231187054420462,1739502658.7442765,19.069981813430786,-0.18438608870957382,1739502658.7442799,19.069981813430786,-0.048043818427826235,1739502658.7442832,19.069981813430786,2.157136959826355,1739502658.744287,19.069981813430786,0.0,1739502658.7442904,19.069981813430786,0.03764271071122849,1739502658.744294,19.069981813430786,6.274844123050781,1739502658.7442975,19.069981813430786,2.1194942491151263 +1739502658.7640023,19.0899817943573,38.51456262701955,1739502658.764006,19.0899817943573,0.09763601110562181,1739502658.76401,19.0899817943573,37.706843434554884,1739502658.764015,19.0899817943573,43.93854774296237,1739502658.7640176,19.0899817943573,-0.132,1739502658.764021,19.0899817943573,-0.04231187054420462,1739502658.764024,19.0899817943573,-0.18438608870957382,1739502658.764027,19.0899817943573,-0.048043818427826235,1739502658.7640302,19.0899817943573,2.157136959826355,1739502658.7640336,19.0899817943573,0.0,1739502658.7640367,19.0899817943573,0.03764271071122849,1739502658.7640398,19.0899817943573,6.274844123050781,1739502658.7640429,19.0899817943573,2.1194942491151263 +1739502658.7826607,19.109981775283813,38.74790920273608,1739502658.782663,19.109981775283813,0.09558134231027626,1739502658.7826664,19.109981775283813,37.969294643120705,1739502658.782669,19.109981775283813,44.209317236571664,1739502658.7826705,19.109981775283813,-0.13547162844696373,1739502658.7826722,19.109981775283813,-0.042281270324604145,1739502658.7826736,19.109981775283813,-0.17991822264164736,1739502658.7826753,19.109981775283813,-0.04623981701455994,1739502658.7826762,19.109981775283813,2.1648609948059705,1739502658.7826781,19.109981775283813,0.0,1739502658.7826793,19.109981775283813,0.04280942285894622,1739502658.7826805,19.109981775283813,6.273824100191456,1739502658.782682,19.109981775283813,2.1236661705517994 +1739502658.8034465,19.129981756210327,38.74790920273608,1739502658.80345,19.129981756210327,0.09558134231027626,1739502658.8034546,19.129981756210327,37.969294643120705,1739502658.8034601,19.129981756210327,44.209317236571664,1739502658.803463,19.129981756210327,-0.13547162844696373,1739502658.8034666,19.129981756210327,-0.042281270324604145,1739502658.8034701,19.129981756210327,-0.17991822264164736,1739502658.8034735,19.129981756210327,-0.04623981701455994,1739502658.8034766,19.129981756210327,2.1648609948059705,1739502658.8034801,19.129981756210327,0.0,1739502658.8034835,19.129981756210327,0.04119482425417109,1739502658.8034868,19.129981756210327,6.273824100191456,1739502658.8034902,19.129981756210327,2.1236661705517994 +1739502658.8290312,19.14998173713684,38.74790920273608,1739502658.8290455,19.14998173713684,0.09558134231027626,1739502658.829062,19.14998173713684,37.969294643120705,1739502658.8290796,19.14998173713684,44.209317236571664,1739502658.829089,19.14998173713684,-0.13547162844696373,1739502658.8291001,19.14998173713684,-0.042281270324604145,1739502658.82911,19.14998173713684,-0.17991822264164736,1739502658.829119,19.14998173713684,-0.04623981701455994,1739502658.8291266,19.14998173713684,2.1648609948059705,1739502658.829143,19.14998173713684,0.0,1739502658.829159,19.14998173713684,0.04119482425417109,1739502658.829174,19.14998173713684,6.273824100191456,1739502658.8291905,19.14998173713684,2.1236661705517994 +1739502658.8456774,19.169981718063354,38.74790920273608,1739502658.8456836,19.169981718063354,0.09558134231027626,1739502658.8456914,19.169981718063354,37.969294643120705,1739502658.8456998,19.169981718063354,44.209317236571664,1739502658.8457048,19.169981718063354,-0.13547162844696373,1739502658.8457108,19.169981718063354,-0.042281270324604145,1739502658.8457162,19.169981718063354,-0.17991822264164736,1739502658.8457215,19.169981718063354,-0.04623981701455994,1739502658.845727,19.169981718063354,2.1648609948059705,1739502658.845733,19.169981718063354,0.0,1739502658.8457382,19.169981718063354,0.04119482425417109,1739502658.845744,19.169981718063354,6.273824100191456,1739502658.8457496,19.169981718063354,2.1236661705517994 +1739502658.8639627,19.189981698989868,38.74790920273608,1739502658.8639662,19.189981698989868,0.09558134231027626,1739502658.8639708,19.189981698989868,37.969294643120705,1739502658.8639762,19.189981698989868,44.209317236571664,1739502658.8639793,19.189981698989868,-0.13547162844696373,1739502658.8639832,19.189981698989868,-0.042281270324604145,1739502658.8639865,19.189981698989868,-0.17991822264164736,1739502658.86399,19.189981698989868,-0.04623981701455994,1739502658.8639934,19.189981698989868,2.1648609948059705,1739502658.863997,19.189981698989868,0.0,1739502658.8640003,19.189981698989868,0.04119482425417109,1739502658.8640041,19.189981698989868,6.273824100191456,1739502658.8640077,19.189981698989868,2.1236661705517994 +1739502658.8839974,19.209981679916382,38.98172594357323,1739502658.884001,19.209981679916382,0.09328401113110818,1739502658.8840053,19.209981679916382,38.45781427977909,1739502658.8840108,19.209981679916382,44.70681545192054,1739502658.8840137,19.209981679916382,-0.1406417371477281,1739502658.8840175,19.209981679916382,-0.04083703791673779,1739502658.8840208,19.209981679916382,-0.17448074074527922,1739502658.8840241,19.209981679916382,-0.04081247218378629,1739502658.8840275,19.209981679916382,2.17429862066595,1739502658.884031,19.209981679916382,0.0,1739502658.8840344,19.209981679916382,0.04837165707602269,1739502658.884038,19.209981679916382,6.2728040773321325,1739502658.8840415,19.209981679916382,2.128169725317225 +1739502658.9042616,19.229981660842896,38.98172594357323,1739502658.9042652,19.229981660842896,0.09328401113110818,1739502658.90427,19.229981660842896,38.45781427977909,1739502658.904275,19.229981660842896,44.70681545192054,1739502658.9042778,19.229981660842896,-0.1406417371477281,1739502658.9042816,19.229981660842896,-0.04083703791673779,1739502658.9042852,19.229981660842896,-0.17448074074527922,1739502658.9042885,19.229981660842896,-0.04081247218378629,1739502658.9042919,19.229981660842896,2.17429862066595,1739502658.9042957,19.229981660842896,0.0,1739502658.9042993,19.229981660842896,0.046128895348724885,1739502658.9043026,19.229981660842896,6.2728040773321325,1739502658.9043062,19.229981660842896,2.128169725317225 +1739502658.9234936,19.24998164176941,38.98172594357323,1739502658.9234977,19.24998164176941,0.09328401113110818,1739502658.9235024,19.24998164176941,38.45781427977909,1739502658.923507,19.24998164176941,44.70681545192054,1739502658.9235096,19.24998164176941,-0.1406417371477281,1739502658.923513,19.24998164176941,-0.04083703791673779,1739502658.923515,19.24998164176941,-0.17448074074527922,1739502658.923518,19.24998164176941,-0.04081247218378629,1739502658.92352,19.24998164176941,2.17429862066595,1739502658.9235227,19.24998164176941,0.0,1739502658.9235253,19.24998164176941,0.046128895348724885,1739502658.923528,19.24998164176941,6.2728040773321325,1739502658.9235303,19.24998164176941,2.128169725317225 +1739502658.9436426,19.269981622695923,38.98172594357323,1739502658.9436464,19.269981622695923,0.09328401113110818,1739502658.943651,19.269981622695923,38.45781427977909,1739502658.9436553,19.269981622695923,44.70681545192054,1739502658.9436574,19.269981622695923,-0.1406417371477281,1739502658.9436605,19.269981622695923,-0.04083703791673779,1739502658.9436631,19.269981622695923,-0.17448074074527922,1739502658.9436655,19.269981622695923,-0.04081247218378629,1739502658.943668,19.269981622695923,2.17429862066595,1739502658.9436703,19.269981622695923,0.0,1739502658.9436724,19.269981622695923,0.046128895348724885,1739502658.9436748,19.269981622695923,6.2728040773321325,1739502658.9436774,19.269981622695923,2.128169725317225 +1739502658.9641783,19.289981603622437,38.98172594357323,1739502658.964183,19.289981603622437,0.09328401113110818,1739502658.9641883,19.289981603622437,38.45781427977909,1739502658.964195,19.289981603622437,44.70681545192054,1739502658.964198,19.289981603622437,-0.1406417371477281,1739502658.9642026,19.289981603622437,-0.04083703791673779,1739502658.9642055,19.289981603622437,-0.17448074074527922,1739502658.9642105,19.289981603622437,-0.04081247218378629,1739502658.964214,19.289981603622437,2.17429862066595,1739502658.9642177,19.289981603622437,0.0,1739502658.9642217,19.289981603622437,0.046128895348724885,1739502658.9642243,19.289981603622437,6.2728040773321325,1739502658.9642289,19.289981603622437,2.128169725317225 +1739502658.9836915,19.30998158454895,38.98172594357323,1739502658.9836946,19.30998158454895,0.09328401113110818,1739502658.9836988,19.30998158454895,38.45781427977909,1739502658.983704,19.30998158454895,44.70681545192054,1739502658.9837067,19.30998158454895,-0.1406417371477281,1739502658.9837103,19.30998158454895,-0.04083703791673779,1739502658.9837136,19.30998158454895,-0.17448074074527922,1739502658.983717,19.30998158454895,-0.04081247218378629,1739502658.9837198,19.30998158454895,2.17429862066595,1739502658.9837232,19.30998158454895,0.0,1739502658.9837263,19.30998158454895,0.046128895348724885,1739502658.9837296,19.30998158454895,6.2728040773321325,1739502658.983733,19.30998158454895,2.128169725317225 +1739502659.0039394,19.329981565475464,39.21606807144092,1739502659.003943,19.329981565475464,0.09074245288718874,1739502659.0039473,19.329981565475464,38.48851055697151,1739502659.003952,19.329981565475464,44.74770015654981,1739502659.003955,19.329981565475464,-0.1410460799661746,1739502659.0039585,19.329981565475464,-0.041877878574052826,1739502659.0039618,19.329981565475464,-0.16870729913828691,1739502659.003965,19.329981565475464,-0.04226665827122026,1739502659.0039682,19.329981565475464,2.184364397339225,1739502659.0039716,19.329981565475464,0.0,1739502659.003975,19.329981565475464,0.05335880768372137,1739502659.0039783,19.329981565475464,6.271784054472808,1739502659.0039816,19.329981565475464,2.1332649387415348 +1739502659.0227807,19.349981546401978,39.21606807144092,1739502659.0227828,19.349981546401978,0.09074245288718874,1739502659.0227854,19.349981546401978,38.48851055697151,1739502659.0227883,19.349981546401978,44.74770015654981,1739502659.0227897,19.349981546401978,-0.1410460799661746,1739502659.0227914,19.349981546401978,-0.041877878574052826,1739502659.0227928,19.349981546401978,-0.16870729913828691,1739502659.022794,19.349981546401978,-0.04226665827122026,1739502659.0227952,19.349981546401978,2.184364397339225,1739502659.0227969,19.349981546401978,0.0,1739502659.022798,19.349981546401978,0.05109945859769027,1739502659.0227993,19.349981546401978,6.271784054472808,1739502659.022801,19.349981546401978,2.1332649387415348 +1739502659.0434108,19.36998152732849,39.21606807144092,1739502659.0434148,19.36998152732849,0.09074245288718874,1739502659.0434191,19.36998152732849,38.48851055697151,1739502659.043424,19.36998152732849,44.74770015654981,1739502659.0434265,19.36998152732849,-0.1410460799661746,1739502659.04343,19.36998152732849,-0.041877878574052826,1739502659.0434332,19.36998152732849,-0.16870729913828691,1739502659.0434363,19.36998152732849,-0.04226665827122026,1739502659.0434394,19.36998152732849,2.184364397339225,1739502659.043443,19.36998152732849,0.0,1739502659.043446,19.36998152732849,0.05109945859769027,1739502659.0434494,19.36998152732849,6.271784054472808,1739502659.0434527,19.36998152732849,2.1332649387415348 +1739502659.0636923,19.389981508255005,39.21606807144092,1739502659.063696,19.389981508255005,0.09074245288718874,1739502659.0637004,19.389981508255005,38.48851055697151,1739502659.0637057,19.389981508255005,44.74770015654981,1739502659.0637083,19.389981508255005,-0.1410460799661746,1739502659.063712,19.389981508255005,-0.041877878574052826,1739502659.0637152,19.389981508255005,-0.16870729913828691,1739502659.0637186,19.389981508255005,-0.04226665827122026,1739502659.063722,19.389981508255005,2.184364397339225,1739502659.0637255,19.389981508255005,0.0,1739502659.0637288,19.389981508255005,0.05109945859769027,1739502659.0637321,19.389981508255005,6.271784054472808,1739502659.0637355,19.389981508255005,2.1332649387415348 +1739502659.083228,19.40998148918152,39.21606807144092,1739502659.0832317,19.40998148918152,0.09074245288718874,1739502659.0832365,19.40998148918152,38.48851055697151,1739502659.0832415,19.40998148918152,44.74770015654981,1739502659.0832443,19.40998148918152,-0.1410460799661746,1739502659.0832481,19.40998148918152,-0.041877878574052826,1739502659.0832515,19.40998148918152,-0.16870729913828691,1739502659.0832548,19.40998148918152,-0.04226665827122026,1739502659.083258,19.40998148918152,2.184364397339225,1739502659.0832617,19.40998148918152,0.0,1739502659.083265,19.40998148918152,0.05109945859769027,1739502659.0832684,19.40998148918152,6.271784054472808,1739502659.0832717,19.40998148918152,2.1332649387415348 +1739502659.107262,19.429981470108032,39.45098934205834,1739502659.1072688,19.429981470108032,0.0879549527286656,1739502659.1072779,19.429981470108032,38.53428442613373,1739502659.1072884,19.429981470108032,44.80464302818419,1739502659.1072943,19.429981470108032,-0.14160434341357045,1739502659.107302,19.429981470108032,-0.042852745940663774,1739502659.1073089,19.429981470108032,-0.16304408950951235,1739502659.1073155,19.429981470108032,-0.04360510948579184,1739502659.1073225,19.429981470108032,2.1942832602030613,1739502659.1073294,19.429981470108032,0.0,1739502659.107336,19.429981470108032,0.05740199628380625,1739502659.107343,19.429981470108032,6.270764031613483,1739502659.1073499,19.429981470108032,2.1388508082375 +1739502659.1241326,19.449981451034546,39.45098934205834,1739502659.1241362,19.449981451034546,0.0879549527286656,1739502659.124141,19.449981451034546,38.53428442613373,1739502659.1241465,19.449981451034546,44.80464302818419,1739502659.1241493,19.449981451034546,-0.14160434341357045,1739502659.1241534,19.449981451034546,-0.042852745940663774,1739502659.1241567,19.449981451034546,-0.16304408950951235,1739502659.1241603,19.449981451034546,-0.04360510948579184,1739502659.1241639,19.449981451034546,2.1942832602030613,1739502659.1241674,19.449981451034546,0.0,1739502659.124171,19.449981451034546,0.055432451965561125,1739502659.1241746,19.449981451034546,6.270764031613483,1739502659.1241782,19.449981451034546,2.1388508082375 +1739502659.1474955,19.46998143196106,39.45098934205834,1739502659.1475,19.46998143196106,0.0879549527286656,1739502659.1475067,19.46998143196106,38.53428442613373,1739502659.147514,19.46998143196106,44.80464302818419,1739502659.1475182,19.46998143196106,-0.14160434341357045,1739502659.1475236,19.46998143196106,-0.042852745940663774,1739502659.1475282,19.46998143196106,-0.16304408950951235,1739502659.147533,19.46998143196106,-0.04360510948579184,1739502659.1475377,19.46998143196106,2.1942832602030613,1739502659.1475427,19.46998143196106,0.0,1739502659.1475475,19.46998143196106,0.055432451965561125,1739502659.1475523,19.46998143196106,6.270764031613483,1739502659.1475573,19.46998143196106,2.1388508082375 +1739502659.1639361,19.489981412887573,39.45098934205834,1739502659.1639395,19.489981412887573,0.0879549527286656,1739502659.163944,19.489981412887573,38.53428442613373,1739502659.1639488,19.489981412887573,44.80464302818419,1739502659.1639516,19.489981412887573,-0.14160434341357045,1739502659.1639552,19.489981412887573,-0.042852745940663774,1739502659.1639583,19.489981412887573,-0.16304408950951235,1739502659.1639616,19.489981412887573,-0.04360510948579184,1739502659.163965,19.489981412887573,2.1942832602030613,1739502659.1639683,19.489981412887573,0.0,1739502659.1639714,19.489981412887573,0.055432451965561125,1739502659.1639748,19.489981412887573,6.270764031613483,1739502659.163978,19.489981412887573,2.1388508082375 +1739502659.183833,19.509981393814087,39.45098934205834,1739502659.183836,19.509981393814087,0.0879549527286656,1739502659.18384,19.509981393814087,38.53428442613373,1739502659.1838446,19.509981393814087,44.80464302818419,1739502659.1838472,19.509981393814087,-0.14160434341357045,1739502659.1838508,19.509981393814087,-0.042852745940663774,1739502659.1838539,19.509981393814087,-0.16304408950951235,1739502659.183857,19.509981393814087,-0.04360510948579184,1739502659.1838598,19.509981393814087,2.1942832602030613,1739502659.183863,19.509981393814087,0.0,1739502659.183866,19.509981393814087,0.055432451965561125,1739502659.1838691,19.509981393814087,6.270764031613483,1739502659.1838722,19.509981393814087,2.1388508082375 +1739502659.2040389,19.5299813747406,39.45098934205834,1739502659.2040417,19.5299813747406,0.0879549527286656,1739502659.2040458,19.5299813747406,38.53428442613373,1739502659.2040508,19.5299813747406,44.80464302818419,1739502659.2040532,19.5299813747406,-0.14160434341357045,1739502659.2040565,19.5299813747406,-0.042852745940663774,1739502659.2040596,19.5299813747406,-0.16304408950951235,1739502659.2040627,19.5299813747406,-0.04360510948579184,1739502659.2040658,19.5299813747406,2.1942832602030613,1739502659.2040691,19.5299813747406,0.0,1739502659.2040725,19.5299813747406,0.055432451965561125,1739502659.2040756,19.5299813747406,6.270764031613483,1739502659.2040787,19.5299813747406,2.1388508082375 +1739502659.223525,19.549981355667114,39.68655112322249,1739502659.2235284,19.549981355667114,0.08491953293289267,1739502659.2235332,19.549981355667114,39.19712879404457,1739502659.223538,19.549981355667114,45.47956584271043,1739502659.2235408,19.549981355667114,-0.1324384460098159,1739502659.2235444,19.549981355667114,-0.03750310959935965,1739502659.2235477,19.549981355667114,-0.13947504936400498,1739502659.2235513,19.549981355667114,-0.03187286973987029,1739502659.2235544,19.549981355667114,2.2360494990813407,1739502659.2235577,19.549981355667114,0.0,1739502659.223561,19.549981355667114,0.10729842115744835,1739502659.2235646,19.549981355667114,6.269744008754159,1739502659.223568,19.549981355667114,2.1449592039232326 +1739502659.243819,19.569981336593628,39.68655112322249,1739502659.2438223,19.569981336593628,0.08491953293289267,1739502659.2438266,19.569981336593628,39.19712879404457,1739502659.2438314,19.569981336593628,45.47956584271043,1739502659.2438338,19.569981336593628,-0.1324384460098159,1739502659.2438374,19.569981336593628,-0.03750310959935965,1739502659.2438405,19.569981336593628,-0.13947504936400498,1739502659.2438436,19.569981336593628,-0.03187286973987029,1739502659.2438467,19.569981336593628,2.2360494990813407,1739502659.24385,19.569981336593628,0.0,1739502659.243853,19.569981336593628,0.09109029515810807,1739502659.2438564,19.569981336593628,6.269744008754159,1739502659.2438595,19.569981336593628,2.1449592039232326 +1739502659.2637582,19.58998131752014,39.68655112322249,1739502659.2637618,19.58998131752014,0.08491953293289267,1739502659.2637665,19.58998131752014,39.19712879404457,1739502659.2637713,19.58998131752014,45.47956584271043,1739502659.2637742,19.58998131752014,-0.1324384460098159,1739502659.2637777,19.58998131752014,-0.03750310959935965,1739502659.263781,19.58998131752014,-0.13947504936400498,1739502659.2637844,19.58998131752014,-0.03187286973987029,1739502659.2637877,19.58998131752014,2.2360494990813407,1739502659.263791,19.58998131752014,0.0,1739502659.2637944,19.58998131752014,0.09109029515810807,1739502659.263814,19.58998131752014,6.269744008754159,1739502659.2638173,19.58998131752014,2.1449592039232326 +1739502659.291945,19.609981298446655,39.68655112322249,1739502659.2919579,19.609981298446655,0.08491953293289267,1739502659.2919753,19.609981298446655,39.19712879404457,1739502659.2919946,19.609981298446655,45.47956584271043,1739502659.2920055,19.609981298446655,-0.1324384460098159,1739502659.2920196,19.609981298446655,-0.03750310959935965,1739502659.2920325,19.609981298446655,-0.13947504936400498,1739502659.292045,19.609981298446655,-0.03187286973987029,1739502659.2920582,19.609981298446655,2.2360494990813407,1739502659.292071,19.609981298446655,0.0,1739502659.2920837,19.609981298446655,0.09109029515810807,1739502659.2920966,19.609981298446655,6.269744008754159,1739502659.2921095,19.609981298446655,2.1449592039232326 +1739502659.3091893,19.62998127937317,39.68655112322249,1739502659.3091948,19.62998127937317,0.08491953293289267,1739502659.3092022,19.62998127937317,39.19712879404457,1739502659.3092105,19.62998127937317,45.47956584271043,1739502659.3092153,19.62998127937317,-0.1324384460098159,1739502659.3092213,19.62998127937317,-0.03750310959935965,1739502659.3092268,19.62998127937317,-0.13947504936400498,1739502659.3092325,19.62998127937317,-0.03187286973987029,1739502659.3092377,19.62998127937317,2.2360494990813407,1739502659.3092437,19.62998127937317,0.0,1739502659.309249,19.62998127937317,0.09109029515810807,1739502659.309255,19.62998127937317,6.269744008754159,1739502659.3092606,19.62998127937317,2.1449592039232326 +1739502659.3266795,19.649981260299683,39.92296475340714,1739502659.3266838,19.649981260299683,0.08163190846436308,1739502659.3266885,19.649981260299683,39.74725553608601,1739502659.3266943,19.649981260299683,46.04903991578192,1739502659.326697,19.649981260299683,-0.10830180106475606,1739502659.3267012,19.649981260299683,-0.030994214274446034,1739502659.326705,19.649981260299683,-0.10132579614616812,1739502659.3267086,19.649981260299683,-0.020715357483663446,1739502659.3267121,19.649981260299683,2.305344435394214,1739502659.3267157,19.649981260299683,0.0,1739502659.3267195,19.649981260299683,0.1774302978328441,1739502659.326723,19.649981260299683,6.268723985894835,1739502659.3267272,19.649981260299683,2.154895406087523 +1739502659.3472812,19.669981241226196,39.92296475340714,1739502659.3472846,19.669981241226196,0.08163190846436308,1739502659.3472886,19.669981241226196,39.74725553608601,1739502659.3472931,19.669981241226196,46.04903991578192,1739502659.3472958,19.669981241226196,-0.10830180106475606,1739502659.3472993,19.669981241226196,-0.030994214274446034,1739502659.3473024,19.669981241226196,-0.10132579614616812,1739502659.3473058,19.669981241226196,-0.020715357483663446,1739502659.3473089,19.669981241226196,2.305344435394214,1739502659.347312,19.669981241226196,0.0,1739502659.3473148,19.669981241226196,0.1504490293066909,1739502659.347318,19.669981241226196,6.268723985894835,1739502659.3473213,19.669981241226196,2.154895406087523 +1739502659.3673012,19.68998122215271,39.92296475340714,1739502659.3673046,19.68998122215271,0.08163190846436308,1739502659.3673089,19.68998122215271,39.74725553608601,1739502659.3673134,19.68998122215271,46.04903991578192,1739502659.367316,19.68998122215271,-0.10830180106475606,1739502659.3673193,19.68998122215271,-0.030994214274446034,1739502659.3673224,19.68998122215271,-0.10132579614616812,1739502659.3673255,19.68998122215271,-0.020715357483663446,1739502659.3673284,19.68998122215271,2.305344435394214,1739502659.3673317,19.68998122215271,0.0,1739502659.3673346,19.68998122215271,0.1504490293066909,1739502659.367338,19.68998122215271,6.268723985894835,1739502659.367341,19.68998122215271,2.154895406087523 +1739502659.3869097,19.709981203079224,39.92296475340714,1739502659.3869128,19.709981203079224,0.08163190846436308,1739502659.3869169,19.709981203079224,39.74725553608601,1739502659.3869214,19.709981203079224,46.04903991578192,1739502659.3869243,19.709981203079224,-0.10830180106475606,1739502659.3869276,19.709981203079224,-0.030994214274446034,1739502659.3869307,19.709981203079224,-0.10132579614616812,1739502659.3869338,19.709981203079224,-0.020715357483663446,1739502659.386937,19.709981203079224,2.305344435394214,1739502659.38694,19.709981203079224,0.0,1739502659.3869429,19.709981203079224,0.1504490293066909,1739502659.3869462,19.709981203079224,6.268723985894835,1739502659.3869495,19.709981203079224,2.154895406087523 +1739502659.407457,19.729981184005737,39.92296475340714,1739502659.4074602,19.729981184005737,0.08163190846436308,1739502659.4074643,19.729981184005737,39.74725553608601,1739502659.407469,19.729981184005737,46.04903991578192,1739502659.4074717,19.729981184005737,-0.10830180106475606,1739502659.407475,19.729981184005737,-0.030994214274446034,1739502659.407478,19.729981184005737,-0.10132579614616812,1739502659.4074812,19.729981184005737,-0.020715357483663446,1739502659.407484,19.729981184005737,2.305344435394214,1739502659.4074872,19.729981184005737,0.0,1739502659.4074903,19.729981184005737,0.1504490293066909,1739502659.4074936,19.729981184005737,6.268723985894835,1739502659.4074967,19.729981184005737,2.154895406087523 +1739502659.4271233,19.74998116493225,39.92296475340714,1739502659.4271266,19.74998116493225,0.08163190846436308,1739502659.427131,19.74998116493225,39.74725553608601,1739502659.427136,19.74998116493225,46.04903991578192,1739502659.4271395,19.74998116493225,-0.10830180106475606,1739502659.4271436,19.74998116493225,-0.030994214274446034,1739502659.4271455,19.74998116493225,-0.10132579614616812,1739502659.4271476,19.74998116493225,-0.020715357483663446,1739502659.4271493,19.74998116493225,2.305344435394214,1739502659.4271517,19.74998116493225,0.0,1739502659.427154,19.74998116493225,0.1504490293066909,1739502659.4271584,19.74998116493225,6.268723985894835,1739502659.4271622,19.74998116493225,2.154895406087523 +1739502659.4477305,19.769981145858765,40.160852959886405,1739502659.447734,19.769981145858765,0.07808101464133355,1739502659.4477386,19.769981145858765,39.75296485304151,1739502659.4477434,19.769981145858765,46.08873324830353,1739502659.4477463,19.769981145858765,-0.10674082731390637,1739502659.4477499,19.769981145858765,-0.031168306355030487,1739502659.4477532,19.769981145858765,-0.09303180509761641,1739502659.4477563,19.769981145858765,-0.020312585772937833,1739502659.4477596,19.769981145858765,2.3206917000068925,1739502659.447763,19.769981145858765,0.0,1739502659.4477663,19.769981145858765,0.14803436110558169,1739502659.4477696,19.769981145858765,6.26770396303551,1739502659.447773,19.769981145858765,2.17190275459372 +1739502659.4733646,19.78998112678528,40.160852959886405,1739502659.4733703,19.78998112678528,0.07808101464133355,1739502659.4733777,19.78998112678528,39.75296485304151,1739502659.4733846,19.78998112678528,46.08873324830353,1739502659.4733882,19.78998112678528,-0.10674082731390637,1739502659.4733927,19.78998112678528,-0.031168306355030487,1739502659.4733963,19.78998112678528,-0.09303180509761641,1739502659.4733999,19.78998112678528,-0.020312585772937833,1739502659.473403,19.78998112678528,2.3206917000068925,1739502659.473407,19.78998112678528,0.0,1739502659.4734106,19.78998112678528,0.14878894541317234,1739502659.4734142,19.78998112678528,6.26770396303551,1739502659.4734178,19.78998112678528,2.17190275459372 +1739502659.4884408,19.809981107711792,40.160852959886405,1739502659.4884462,19.809981107711792,0.07808101464133355,1739502659.4884524,19.809981107711792,39.75296485304151,1739502659.4884596,19.809981107711792,46.08873324830353,1739502659.4884634,19.809981107711792,-0.10674082731390637,1739502659.4884684,19.809981107711792,-0.031168306355030487,1739502659.4884732,19.809981107711792,-0.09303180509761641,1739502659.4884777,19.809981107711792,-0.020312585772937833,1739502659.4884822,19.809981107711792,2.3206917000068925,1739502659.4884872,19.809981107711792,0.0,1739502659.4884918,19.809981107711792,0.14878894541317234,1739502659.4884965,19.809981107711792,6.26770396303551,1739502659.4885013,19.809981107711792,2.17190275459372 +1739502659.507277,19.829981088638306,40.160852959886405,1739502659.5072803,19.829981088638306,0.07808101464133355,1739502659.5072844,19.829981088638306,39.75296485304151,1739502659.5072894,19.829981088638306,46.08873324830353,1739502659.5072923,19.829981088638306,-0.10674082731390637,1739502659.5072958,19.829981088638306,-0.031168306355030487,1739502659.5072987,19.829981088638306,-0.09303180509761641,1739502659.5073018,19.829981088638306,-0.020312585772937833,1739502659.507305,19.829981088638306,2.3206917000068925,1739502659.5073082,19.829981088638306,0.0,1739502659.5073113,19.829981088638306,0.14878894541317234,1739502659.5073147,19.829981088638306,6.26770396303551,1739502659.507318,19.829981088638306,2.17190275459372 +1739502659.527499,19.84998106956482,40.160852959886405,1739502659.5275025,19.84998106956482,0.07808101464133355,1739502659.5275073,19.84998106956482,39.75296485304151,1739502659.5275118,19.84998106956482,46.08873324830353,1739502659.5275147,19.84998106956482,-0.10674082731390637,1739502659.5275183,19.84998106956482,-0.031168306355030487,1739502659.5275216,19.84998106956482,-0.09303180509761641,1739502659.5275247,19.84998106956482,-0.020312585772937833,1739502659.5275276,19.84998106956482,2.3206917000068925,1739502659.5275307,19.84998106956482,0.0,1739502659.527534,19.84998106956482,0.14878894541317234,1739502659.5275373,19.84998106956482,6.26770396303551,1739502659.5275407,19.84998106956482,2.17190275459372 +1739502659.5475645,19.869981050491333,40.40054661975757,1739502659.547568,19.869981050491333,0.07425862647786019,1739502659.5475721,19.869981050491333,39.75871750087842,1739502659.5475771,19.869981050491333,46.1270087284999,1739502659.5475798,19.869981050491333,-0.10523561180056575,1739502659.5475833,19.869981050491333,-0.031334441007508484,1739502659.547586,19.869981050491333,-0.08497963658148133,1739502659.5475895,19.869981050491333,-0.019882476025351446,1739502659.5475924,19.869981050491333,2.3356892337270203,1739502659.5475957,19.869981050491333,0.0,1739502659.5475988,19.869981050491333,0.14692905364489622,1739502659.547602,19.869981050491333,6.266683940176186,1739502659.547605,19.869981050491333,2.1881789635234625 +1739502659.5671763,19.889981031417847,40.40054661975757,1739502659.5671794,19.889981031417847,0.07425862647786019,1739502659.5671837,19.889981031417847,39.75871750087842,1739502659.5671883,19.889981031417847,46.1270087284999,1739502659.567191,19.889981031417847,-0.10523561180056575,1739502659.5671947,19.889981031417847,-0.031334441007508484,1739502659.5671978,19.889981031417847,-0.08497963658148133,1739502659.5672007,19.889981031417847,-0.019882476025351446,1739502659.5672038,19.889981031417847,2.3356892337270203,1739502659.5672069,19.889981031417847,0.0,1739502659.56721,19.889981031417847,0.14751027020355778,1739502659.567213,19.889981031417847,6.266683940176186,1739502659.5672164,19.889981031417847,2.1881789635234625 +1739502659.5870697,19.90998101234436,40.40054661975757,1739502659.5870733,19.90998101234436,0.07425862647786019,1739502659.5870776,19.90998101234436,39.75871750087842,1739502659.5870829,19.90998101234436,46.1270087284999,1739502659.5870855,19.90998101234436,-0.10523561180056575,1739502659.5870893,19.90998101234436,-0.031334441007508484,1739502659.5870924,19.90998101234436,-0.08497963658148133,1739502659.587096,19.90998101234436,-0.019882476025351446,1739502659.587099,19.90998101234436,2.3356892337270203,1739502659.5871024,19.90998101234436,0.0,1739502659.5871055,19.90998101234436,0.14751027020355778,1739502659.5871089,19.90998101234436,6.266683940176186,1739502659.5871124,19.90998101234436,2.1881789635234625 +1739502659.6072528,19.929980993270874,40.40054661975757,1739502659.6072562,19.929980993270874,0.07425862647786019,1739502659.6072607,19.929980993270874,39.75871750087842,1739502659.6072657,19.929980993270874,46.1270087284999,1739502659.6072683,19.929980993270874,-0.10523561180056575,1739502659.6072721,19.929980993270874,-0.031334441007508484,1739502659.6072752,19.929980993270874,-0.08497963658148133,1739502659.6072786,19.929980993270874,-0.019882476025351446,1739502659.607303,19.929980993270874,2.3356892337270203,1739502659.6073065,19.929980993270874,0.0,1739502659.6073096,19.929980993270874,0.14751027020355778,1739502659.6073132,19.929980993270874,6.266683940176186,1739502659.6073165,19.929980993270874,2.1881789635234625 +1739502659.6272595,19.949980974197388,40.40054661975757,1739502659.6272633,19.949980974197388,0.07425862647786019,1739502659.6272678,19.949980974197388,39.75871750087842,1739502659.6272728,19.949980974197388,46.1270087284999,1739502659.6272757,19.949980974197388,-0.10523561180056575,1739502659.6272795,19.949980974197388,-0.031334441007508484,1739502659.6272829,19.949980974197388,-0.08497963658148133,1739502659.6272864,19.949980974197388,-0.019882476025351446,1739502659.6272898,19.949980974197388,2.3356892337270203,1739502659.6272933,19.949980974197388,0.0,1739502659.627297,19.949980974197388,0.14751027020355778,1739502659.6273005,19.949980974197388,6.266683940176186,1739502659.6273038,19.949980974197388,2.1881789635234625 +1739502659.6462579,19.9699809551239,40.40054661975757,1739502659.6462603,19.9699809551239,0.07425862647786019,1739502659.6462634,19.9699809551239,39.75871750087842,1739502659.6462822,19.9699809551239,46.1270087284999,1739502659.6462839,19.9699809551239,-0.10523561180056575,1739502659.6462855,19.9699809551239,-0.031334441007508484,1739502659.646287,19.9699809551239,-0.08497963658148133,1739502659.6462882,19.9699809551239,-0.019882476025351446,1739502659.646289,19.9699809551239,2.3356892337270203,1739502659.646291,19.9699809551239,0.0,1739502659.6462922,19.9699809551239,0.14751027020355778,1739502659.6462934,19.9699809551239,6.266683940176186,1739502659.6462948,19.9699809551239,2.1881789635234625 +1739502659.6699843,19.989980936050415,40.6420194662428,1739502659.6699927,19.989980936050415,0.07016149347742928,1739502659.6700032,19.989980936050415,39.76451284919406,1739502659.6700137,19.989980936050415,46.16505063178227,1739502659.670019,19.989980936050415,-0.10370502497849401,1739502659.670025,19.989980936050415,-0.03146987823053875,1739502659.6700304,19.989980936050415,-0.07707359979906735,1739502659.6700351,19.989980936050415,-0.019385439659725175,1739502659.67004,19.989980936050415,2.3505088862062786,1739502659.6700451,19.989980936050415,0.0,1739502659.6700501,19.989980936050415,0.1455917012841062,1739502659.6700552,19.989980936050415,6.265663917316862,1739502659.6700604,19.989980936050415,2.204317631741746 +1739502659.689889,20.00998091697693,40.6420194662428,1739502659.6898975,20.00998091697693,0.07016149347742928,1739502659.689908,20.00998091697693,39.76451284919406,1739502659.6899178,20.00998091697693,46.16505063178227,1739502659.6899226,20.00998091697693,-0.10370502497849401,1739502659.6899288,20.00998091697693,-0.03146987823053875,1739502659.6899335,20.00998091697693,-0.07707359979906735,1739502659.6899385,20.00998091697693,-0.019385439659725175,1739502659.6899428,20.00998091697693,2.3505088862062786,1739502659.689948,20.00998091697693,0.0,1739502659.6899533,20.00998091697693,0.14619125446453252,1739502659.6899583,20.00998091697693,6.265663917316862,1739502659.6899633,20.00998091697693,2.204317631741746 +1739502659.7230983,20.0399808883667,40.6420194662428,1739502659.7231045,20.0399808883667,0.07016149347742928,1739502659.7231123,20.0399808883667,39.76451284919406,1739502659.7231195,20.0399808883667,46.16505063178227,1739502659.7231238,20.0399808883667,-0.10370502497849401,1739502659.7231283,20.0399808883667,-0.03146987823053875,1739502659.723132,20.0399808883667,-0.07707359979906735,1739502659.7231355,20.0399808883667,-0.019385439659725175,1739502659.723139,20.0399808883667,2.3505088862062786,1739502659.723143,20.0399808883667,0.0,1739502659.723147,20.0399808883667,0.14619125446453252,1739502659.7231505,20.0399808883667,6.265663917316862,1739502659.723155,20.0399808883667,2.204317631741746 +1739502659.7381604,20.059980869293213,40.6420194662428,1739502659.7381651,20.059980869293213,0.07016149347742928,1739502659.7381713,20.059980869293213,39.76451284919406,1739502659.7381785,20.059980869293213,46.16505063178227,1739502659.7381825,20.059980869293213,-0.10370502497849401,1739502659.7381878,20.059980869293213,-0.03146987823053875,1739502659.7381923,20.059980869293213,-0.07707359979906735,1739502659.738197,20.059980869293213,-0.019385439659725175,1739502659.7382016,20.059980869293213,2.3505088862062786,1739502659.7382064,20.059980869293213,0.0,1739502659.7382112,20.059980869293213,0.14619125446453252,1739502659.7382157,20.059980869293213,6.265663917316862,1739502659.7382205,20.059980869293213,2.204317631741746 +1739502659.756106,20.079980850219727,40.6420194662428,1739502659.7561092,20.079980850219727,0.07016149347742928,1739502659.7561138,20.079980850219727,39.76451284919406,1739502659.7561185,20.079980850219727,46.16505063178227,1739502659.7561212,20.079980850219727,-0.10370502497849401,1739502659.7561247,20.079980850219727,-0.03146987823053875,1739502659.7561278,20.079980850219727,-0.07707359979906735,1739502659.7561312,20.079980850219727,-0.019385439659725175,1739502659.756134,20.079980850219727,2.3505088862062786,1739502659.7561376,20.079980850219727,0.0,1739502659.7561407,20.079980850219727,0.14619125446453252,1739502659.756144,20.079980850219727,6.265663917316862,1739502659.7561471,20.079980850219727,2.204317631741746 +1739502659.775386,20.09998083114624,40.88525562182719,1739502659.775389,20.09998083114624,0.06578626219164718,1739502659.775393,20.09998083114624,40.23545844303586,1739502659.7753978,20.09998083114624,46.66726649226565,1739502659.7754004,20.09998083114624,-0.077323722127898,1739502659.7754037,20.09998083114624,-0.02474584964688027,1739502659.7754068,20.09998083114624,-0.03588487820101388,1739502659.77541,20.09998083114624,-0.008238493942223545,1739502659.775413,20.09998083114624,2.4292506354334176,1739502659.7754161,20.09998083114624,0.0,1739502659.7754195,20.09998083114624,0.23746411794082622,1739502659.7754226,20.09998083114624,6.264643894457537,1739502659.7754254,20.09998083114624,2.2203093060299306 +1739502659.7954724,20.119980812072754,40.88525562182719,1739502659.7954755,20.119980812072754,0.06578626219164718,1739502659.7954795,20.119980812072754,40.23545844303586,1739502659.795484,20.119980812072754,46.66726649226565,1739502659.7954867,20.119980812072754,-0.077323722127898,1739502659.79549,20.119980812072754,-0.02474584964688027,1739502659.7954934,20.119980812072754,-0.03588487820101388,1739502659.7954965,20.119980812072754,-0.008238493942223545,1739502659.7954993,20.119980812072754,2.4292506354334176,1739502659.7955027,20.119980812072754,0.0,1739502659.7955058,20.119980812072754,0.20894132940348698,1739502659.7955086,20.119980812072754,6.264643894457537,1739502659.7955117,20.119980812072754,2.2203093060299306 +1739502659.8156025,20.139980792999268,40.88525562182719,1739502659.8156059,20.139980792999268,0.06578626219164718,1739502659.81561,20.139980792999268,40.23545844303586,1739502659.815615,20.139980792999268,46.66726649226565,1739502659.8156176,20.139980792999268,-0.077323722127898,1739502659.8156211,20.139980792999268,-0.02474584964688027,1739502659.8156247,20.139980792999268,-0.03588487820101388,1739502659.815628,20.139980792999268,-0.008238493942223545,1739502659.8156312,20.139980792999268,2.4292506354334176,1739502659.8156345,20.139980792999268,0.0,1739502659.8156378,20.139980792999268,0.20894132940348698,1739502659.8156412,20.139980792999268,6.264643894457537,1739502659.8156445,20.139980792999268,2.2203093060299306 +1739502659.8348165,20.15998077392578,40.88525562182719,1739502659.8348196,20.15998077392578,0.06578626219164718,1739502659.8348236,20.15998077392578,40.23545844303586,1739502659.8348284,20.15998077392578,46.66726649226565,1739502659.8348308,20.15998077392578,-0.077323722127898,1739502659.8348343,20.15998077392578,-0.02474584964688027,1739502659.8348377,20.15998077392578,-0.03588487820101388,1739502659.8348408,20.15998077392578,-0.008238493942223545,1739502659.8348436,20.15998077392578,2.4292506354334176,1739502659.834847,20.15998077392578,0.0,1739502659.83485,20.15998077392578,0.20894132940348698,1739502659.8348534,20.15998077392578,6.264643894457537,1739502659.8348565,20.15998077392578,2.2203093060299306 +1739502659.8555822,20.179980754852295,40.88525562182719,1739502659.8555872,20.179980754852295,0.06578626219164718,1739502659.8555932,20.179980754852295,40.23545844303586,1739502659.8555996,20.179980754852295,46.66726649226565,1739502659.8556032,20.179980754852295,-0.077323722127898,1739502659.8556077,20.179980754852295,-0.02474584964688027,1739502659.8556125,20.179980754852295,-0.03588487820101388,1739502659.8556166,20.179980754852295,-0.008238493942223545,1739502659.8556206,20.179980754852295,2.4292506354334176,1739502659.8556325,20.179980754852295,0.0,1739502659.8556368,20.179980754852295,0.20894132940348698,1739502659.8556404,20.179980754852295,6.264643894457537,1739502659.8556447,20.179980754852295,2.2203093060299306 +1739502659.8757665,20.19998073577881,41.130575577449626,1739502659.8757699,20.19998073577881,0.06112316558355069,1739502659.8757741,20.19998073577881,40.24674316099449,1739502659.8757792,20.19998073577881,46.724049539602554,1739502659.8757818,20.19998073577881,-0.07377763773731365,1739502659.8757856,20.19998073577881,-0.02411286046801753,1739502659.8757887,20.19998073577881,-0.02546559156880641,1739502659.8757918,20.19998073577881,-0.00624738950560594,1739502659.8757951,20.19998073577881,2.4495841087561443,1739502659.8757982,20.19998073577881,0.0,1739502659.8758016,20.19998073577881,0.2053470182717255,1739502659.875805,20.19998073577881,6.263623871598213,1739502659.875808,20.19998073577881,2.243113867519301 +1739502659.8961296,20.219980716705322,41.130575577449626,1739502659.8961327,20.219980716705322,0.06112316558355069,1739502659.896137,20.219980716705322,40.24674316099449,1739502659.896142,20.219980716705322,46.724049539602554,1739502659.8961449,20.219980716705322,-0.07377763773731365,1739502659.8961484,20.219980716705322,-0.02411286046801753,1739502659.8961518,20.219980716705322,-0.02546559156880641,1739502659.896155,20.219980716705322,-0.00624738950560594,1739502659.8961582,20.219980716705322,2.4495841087561443,1739502659.8961616,20.219980716705322,0.0,1739502659.8961647,20.219980716705322,0.20647024123684332,1739502659.896168,20.219980716705322,6.263623871598213,1739502659.8961713,20.219980716705322,2.243113867519301 +1739502659.9141448,20.239980697631836,41.130575577449626,1739502659.9141474,20.239980697631836,0.06112316558355069,1739502659.9141502,20.239980697631836,40.24674316099449,1739502659.9141526,20.239980697631836,46.724049539602554,1739502659.9141543,20.239980697631836,-0.07377763773731365,1739502659.9141557,20.239980697631836,-0.02411286046801753,1739502659.9141572,20.239980697631836,-0.02546559156880641,1739502659.9141583,20.239980697631836,-0.00624738950560594,1739502659.9141595,20.239980697631836,2.4495841087561443,1739502659.9141612,20.239980697631836,0.0,1739502659.9141624,20.239980697631836,0.20647024123684332,1739502659.9141638,20.239980697631836,6.263623871598213,1739502659.9141653,20.239980697631836,2.243113867519301 +1739502659.934189,20.25998067855835,41.130575577449626,1739502659.9341917,20.25998067855835,0.06112316558355069,1739502659.9341943,20.25998067855835,40.24674316099449,1739502659.934197,20.25998067855835,46.724049539602554,1739502659.9341986,20.25998067855835,-0.07377763773731365,1739502659.9342,20.25998067855835,-0.02411286046801753,1739502659.9342012,20.25998067855835,-0.02546559156880641,1739502659.9342027,20.25998067855835,-0.00624738950560594,1739502659.9342039,20.25998067855835,2.4495841087561443,1739502659.9342055,20.25998067855835,0.0,1739502659.9342067,20.25998067855835,0.20647024123684332,1739502659.934208,20.25998067855835,6.263623871598213,1739502659.9342093,20.25998067855835,2.243113867519301 +1739502659.954159,20.279980659484863,41.130575577449626,1739502659.9541616,20.279980659484863,0.06112316558355069,1739502659.9541643,20.279980659484863,40.24674316099449,1739502659.9541671,20.279980659484863,46.724049539602554,1739502659.9541686,20.279980659484863,-0.07377763773731365,1739502659.9541702,20.279980659484863,-0.02411286046801753,1739502659.9541714,20.279980659484863,-0.02546559156880641,1739502659.9541726,20.279980659484863,-0.00624738950560594,1739502659.954174,20.279980659484863,2.4495841087561443,1739502659.9541755,20.279980659484863,0.0,1739502659.9541764,20.279980659484863,0.20647024123684332,1739502659.954178,20.279980659484863,6.263623871598213,1739502659.9541793,20.279980659484863,2.243113867519301 +1739502659.973975,20.299980640411377,41.130575577449626,1739502659.973977,20.299980640411377,0.06112316558355069,1739502659.97398,20.299980640411377,40.24674316099449,1739502659.9739826,20.299980640411377,46.724049539602554,1739502659.9739838,20.299980640411377,-0.07377763773731365,1739502659.9739854,20.299980640411377,-0.02411286046801753,1739502659.9739869,20.299980640411377,-0.02546559156880641,1739502659.973988,20.299980640411377,-0.00624738950560594,1739502659.9739895,20.299980640411377,2.4495841087561443,1739502659.973991,20.299980640411377,0.0,1739502659.973992,20.299980640411377,0.20647024123684332,1739502659.9739935,20.299980640411377,6.263623871598213,1739502659.9739947,20.299980640411377,2.243113867519301 +1739502659.9941995,20.31998062133789,41.37839862243923,1739502659.9942021,20.31998062133789,0.05615961564114702,1739502659.9942048,20.31998062133789,40.53216636987814,1739502659.9942071,20.31998062133789,47.05343377051037,1739502659.9942086,20.31998062133789,-0.04576913105106447,1739502659.99421,20.31998062133789,-0.017958970406470008,1739502659.9942114,20.31998062133789,0.014885095050759455,1739502659.9942126,20.31998062133789,0.0035484234466033617,1739502659.9942138,20.31998062133789,2.470406361251696,1739502659.9942155,20.31998062133789,0.0,1739502659.9942167,20.31998062133789,0.20391077768701377,1739502659.9942183,20.31998062133789,6.262603848738888,1739502659.9942195,20.31998062133789,2.2656957506809494 +1739502660.0140076,20.339980602264404,41.37839862243923,1739502660.0140097,20.339980602264404,0.05615961564114702,1739502660.014012,20.339980602264404,40.53216636987814,1739502660.0140147,20.339980602264404,47.05343377051037,1739502660.014016,20.339980602264404,-0.04576913105106447,1739502660.0140178,20.339980602264404,-0.017958970406470008,1739502660.014019,20.339980602264404,0.014885095050759455,1739502660.0140204,20.339980602264404,0.0035484234466033617,1739502660.0140216,20.339980602264404,2.470406361251696,1739502660.014023,20.339980602264404,0.0,1739502660.0140243,20.339980602264404,0.2047106105707468,1739502660.0140254,20.339980602264404,6.262603848738888,1739502660.014027,20.339980602264404,2.2656957506809494 +1739502660.033994,20.359980583190918,41.37839862243923,1739502660.033996,20.359980583190918,0.05615961564114702,1739502660.033999,20.359980583190918,40.53216636987814,1739502660.0340016,20.359980583190918,47.05343377051037,1739502660.034003,20.359980583190918,-0.04576913105106447,1739502660.0340044,20.359980583190918,-0.017958970406470008,1739502660.034006,20.359980583190918,0.014885095050759455,1739502660.0340073,20.359980583190918,0.0035484234466033617,1739502660.0340087,20.359980583190918,2.470406361251696,1739502660.0340104,20.359980583190918,0.0,1739502660.0340116,20.359980583190918,0.2047106105707468,1739502660.034013,20.359980583190918,6.262603848738888,1739502660.0340142,20.359980583190918,2.2656957506809494 +1739502660.054201,20.37998056411743,41.37839862243923,1739502660.0542035,20.37998056411743,0.05615961564114702,1739502660.0542061,20.37998056411743,40.53216636987814,1739502660.054209,20.37998056411743,47.05343377051037,1739502660.0542102,20.37998056411743,-0.04576913105106447,1739502660.054212,20.37998056411743,-0.017958970406470008,1739502660.0542133,20.37998056411743,0.014885095050759455,1739502660.0542147,20.37998056411743,0.0035484234466033617,1739502660.054216,20.37998056411743,2.470406361251696,1739502660.0542176,20.37998056411743,0.0,1739502660.054219,20.37998056411743,0.2047106105707468,1739502660.0542202,20.37998056411743,6.262603848738888,1739502660.0542219,20.37998056411743,2.2656957506809494 +1739502660.0740569,20.399980545043945,41.37839862243923,1739502660.0740592,20.399980545043945,0.05615961564114702,1739502660.074062,20.399980545043945,40.53216636987814,1739502660.074065,20.399980545043945,47.05343377051037,1739502660.0740662,20.399980545043945,-0.04576913105106447,1739502660.074068,20.399980545043945,-0.017958970406470008,1739502660.0740693,20.399980545043945,0.014885095050759455,1739502660.0740705,20.399980545043945,0.0035484234466033617,1739502660.074072,20.399980545043945,2.470406361251696,1739502660.0740733,20.399980545043945,0.0,1739502660.0740743,20.399980545043945,0.2047106105707468,1739502660.074076,20.399980545043945,6.262603848738888,1739502660.0740771,20.399980545043945,2.2656957506809494 +1739502660.094172,20.41998052597046,41.62869065371662,1739502660.0941744,20.41998052597046,0.050891207946068384,1739502660.0941772,20.41998052597046,41.09075082753695,1739502660.09418,20.41998052597046,47.65183856766991,1739502660.0941813,20.41998052597046,0.030463601223921777,1739502660.0941832,20.41998052597046,-0.003391503694155559,1739502660.0941844,20.41998052597046,0.10967595770776628,1739502660.0941858,20.41998052597046,0.023217311722467934,1739502660.094187,20.41998052597046,2.2899957592486344,1739502660.0941887,20.41998052597046,0.0,1739502660.0941901,20.41998052597046,-0.09027405052829474,1739502660.0941916,20.41998052597046,6.261583825879564,1739502660.094193,20.41998052597046,2.2880870427437467 +1739502660.1140144,20.439980506896973,41.62869065371662,1739502660.1140165,20.439980506896973,0.050891207946068384,1739502660.1140194,20.439980506896973,41.09075082753695,1739502660.1140223,20.439980506896973,47.65183856766991,1739502660.1140237,20.439980506896973,0.030463601223921777,1739502660.114025,20.439980506896973,-0.003391503694155559,1739502660.1140265,20.439980506896973,0.10967595770776628,1739502660.114028,20.439980506896973,0.023217311722467934,1739502660.1140294,20.439980506896973,2.2899957592486344,1739502660.1140308,20.439980506896973,0.0,1739502660.114032,20.439980506896973,0.0019087165048876642,1739502660.1140337,20.439980506896973,6.261583825879564,1739502660.114035,20.439980506896973,2.2880870427437467 +1739502660.1340258,20.459980487823486,41.62869065371662,1739502660.1340277,20.459980487823486,0.050891207946068384,1739502660.1340306,20.459980487823486,41.09075082753695,1739502660.1340334,20.459980487823486,47.65183856766991,1739502660.1340346,20.459980487823486,0.030463601223921777,1739502660.1340363,20.459980487823486,-0.003391503694155559,1739502660.1340377,20.459980487823486,0.10967595770776628,1739502660.134039,20.459980487823486,0.023217311722467934,1739502660.1340404,20.459980487823486,2.2899957592486344,1739502660.1340418,20.459980487823486,0.0,1739502660.1340432,20.459980487823486,0.0019087165048876642,1739502660.1340446,20.459980487823486,6.261583825879564,1739502660.1340458,20.459980487823486,2.2880870427437467 +1739502660.154517,20.47998046875,41.62869065371662,1739502660.1545203,20.47998046875,0.050891207946068384,1739502660.1545236,20.47998046875,41.09075082753695,1739502660.1545267,20.47998046875,47.65183856766991,1739502660.1545286,20.47998046875,0.030463601223921777,1739502660.1545303,20.47998046875,-0.003391503694155559,1739502660.1545322,20.47998046875,0.10967595770776628,1739502660.1545336,20.47998046875,0.023217311722467934,1739502660.1545348,20.47998046875,2.2899957592486344,1739502660.154537,20.47998046875,0.0,1739502660.1545384,20.47998046875,0.0019087165048876642,1739502660.15454,20.47998046875,6.261583825879564,1739502660.1545417,20.47998046875,2.2880870427437467 +1739502660.1748147,20.499980449676514,41.62869065371662,1739502660.1748183,20.499980449676514,0.050891207946068384,1739502660.1748223,20.499980449676514,41.09075082753695,1739502660.1748264,20.499980449676514,47.65183856766991,1739502660.1748288,20.499980449676514,0.030463601223921777,1739502660.1748312,20.499980449676514,-0.003391503694155559,1739502660.174833,20.499980449676514,0.10967595770776628,1739502660.1748352,20.499980449676514,0.023217311722467934,1739502660.1748369,20.499980449676514,2.2899957592486344,1739502660.1748393,20.499980449676514,0.0,1739502660.1748414,20.499980449676514,0.0019087165048876642,1739502660.1748433,20.499980449676514,6.261583825879564,1739502660.1748455,20.499980449676514,2.2880870427437467 +1739502660.1958978,20.519980430603027,41.62869065371662,1739502660.1959014,20.519980430603027,0.050891207946068384,1739502660.1959062,20.519980430603027,41.09075082753695,1739502660.1959107,20.519980430603027,47.65183856766991,1739502660.1959126,20.519980430603027,0.030463601223921777,1739502660.1959155,20.519980430603027,-0.003391503694155559,1739502660.1959176,20.519980430603027,0.10967595770776628,1739502660.19592,20.519980430603027,0.023217311722467934,1739502660.195922,20.519980430603027,2.2899957592486344,1739502660.1959248,20.519980430603027,0.0,1739502660.1959267,20.519980430603027,0.0019087165048876642,1739502660.195929,20.519980430603027,6.261583825879564,1739502660.1959314,20.519980430603027,2.2880870427437467 +1739502660.215594,20.53998041152954,41.880155505141815,1739502660.2155983,20.53998041152954,0.04536335382304735,1739502660.2156034,20.53998041152954,41.10131235129681,1739502660.2156084,20.53998041152954,47.65907257186002,1739502660.215611,20.53998041152954,0.03161796359468503,1739502660.2156136,20.53998041152954,-0.002378536350053623,1739502660.215616,20.53998041152954,0.1155448740919237,1739502660.2156184,20.53998041152954,0.02657083279398141,1739502660.2156203,20.53998041152954,2.2792691255353534,1739502660.2156231,20.53998041152954,0.0,1739502660.2156255,20.53998041152954,-0.011340212720350714,1739502660.2156281,20.53998041152954,6.260811286249056,1739502660.2156303,20.53998041152954,2.2864690451582295 +1739502660.234198,20.559980392456055,41.880155505141815,1739502660.2342012,20.559980392456055,0.04536335382304735,1739502660.2342038,20.559980392456055,41.10131235129681,1739502660.2342064,20.559980392456055,47.65907257186002,1739502660.234208,20.559980392456055,0.03161796359468503,1739502660.2342095,20.559980392456055,-0.002378536350053623,1739502660.2342107,20.559980392456055,0.1155448740919237,1739502660.2342122,20.559980392456055,0.02657083279398141,1739502660.234213,20.559980392456055,2.2792691255353534,1739502660.234215,20.559980392456055,0.0,1739502660.2342162,20.559980392456055,-0.007199919622876028,1739502660.2342174,20.559980392456055,6.260811286249056,1739502660.2342188,20.559980392456055,2.2864690451582295 +1739502660.254254,20.57998037338257,41.880155505141815,1739502660.254257,20.57998037338257,0.04536335382304735,1739502660.2542593,20.57998037338257,41.10131235129681,1739502660.254262,20.57998037338257,47.65907257186002,1739502660.2542634,20.57998037338257,0.03161796359468503,1739502660.2542648,20.57998037338257,-0.002378536350053623,1739502660.2542658,20.57998037338257,0.1155448740919237,1739502660.2542675,20.57998037338257,0.02657083279398141,1739502660.2542684,20.57998037338257,2.2792691255353534,1739502660.2542698,20.57998037338257,0.0,1739502660.2542715,20.57998037338257,-0.007199919622876028,1739502660.2542727,20.57998037338257,6.260811286249056,1739502660.2542741,20.57998037338257,2.2864690451582295 +1739502660.2739797,20.599980354309082,41.880155505141815,1739502660.2739818,20.599980354309082,0.04536335382304735,1739502660.2739842,20.599980354309082,41.10131235129681,1739502660.2739866,20.599980354309082,47.65907257186002,1739502660.2739878,20.599980354309082,0.03161796359468503,1739502660.2739894,20.599980354309082,-0.002378536350053623,1739502660.2739906,20.599980354309082,0.1155448740919237,1739502660.2739918,20.599980354309082,0.02657083279398141,1739502660.273993,20.599980354309082,2.2792691255353534,1739502660.2739942,20.599980354309082,0.0,1739502660.2739956,20.599980354309082,-0.007199919622876028,1739502660.2739968,20.599980354309082,6.260811286249056,1739502660.273998,20.599980354309082,2.2864690451582295 +1739502660.2941225,20.619980335235596,41.880155505141815,1739502660.294125,20.619980335235596,0.04536335382304735,1739502660.2941277,20.619980335235596,41.10131235129681,1739502660.29413,20.619980335235596,47.65907257186002,1739502660.2941315,20.619980335235596,0.03161796359468503,1739502660.294133,20.619980335235596,-0.002378536350053623,1739502660.2941344,20.619980335235596,0.1155448740919237,1739502660.2941356,20.619980335235596,0.02657083279398141,1739502660.2941368,20.619980335235596,2.2792691255353534,1739502660.2941382,20.619980335235596,0.0,1739502660.2941391,20.619980335235596,-0.007199919622876028,1739502660.2941403,20.619980335235596,6.260811286249056,1739502660.2941418,20.619980335235596,2.2864690451582295 +1739502660.3140323,20.63998031616211,42.13156532001124,1739502660.3140345,20.63998031616211,0.03966803554498899,1739502660.314037,20.63998031616211,41.36633345458069,1739502660.3140395,20.63998031616211,47.91861408684147,1739502660.314041,20.63998031616211,0.07681892802389217,1739502660.3140423,20.63998031616211,0.006419573021337762,1739502660.3140438,20.63998031616211,0.16994116767759024,1739502660.314045,20.63998031616211,0.03896755978940899,1739502660.314046,20.63998031616211,2.1822092863570672,1739502660.3140476,20.63998031616211,0.0,1739502660.3140488,20.63998031616211,-0.14724540986905693,1739502660.31405,20.63998031616211,6.260235489074008,1739502660.3140514,20.63998031616211,2.285690451830118 +1739502660.3342206,20.659980297088623,42.13156532001124,1739502660.3342228,20.659980297088623,0.03966803554498899,1739502660.334226,20.659980297088623,41.36633345458069,1739502660.3342285,20.659980297088623,47.91861408684147,1739502660.33423,20.659980297088623,0.07681892802389217,1739502660.3342316,20.659980297088623,0.006419573021337762,1739502660.334233,20.659980297088623,0.16994116767759024,1739502660.3342345,20.659980297088623,0.03896755978940899,1739502660.3342357,20.659980297088623,2.1822092863570672,1739502660.334237,20.659980297088623,0.0,1739502660.3342385,20.659980297088623,-0.10348116547305075,1739502660.33424,20.659980297088623,6.260235489074008,1739502660.3342416,20.659980297088623,2.285690451830118 +1739502660.3542445,20.679980278015137,42.13156532001124,1739502660.3542469,20.679980278015137,0.03966803554498899,1739502660.35425,20.679980278015137,41.36633345458069,1739502660.3542528,20.679980278015137,47.91861408684147,1739502660.3542542,20.679980278015137,0.07681892802389217,1739502660.3542562,20.679980278015137,0.006419573021337762,1739502660.3542573,20.679980278015137,0.16994116767759024,1739502660.354259,20.679980278015137,0.03896755978940899,1739502660.3542602,20.679980278015137,2.1822092863570672,1739502660.3542619,20.679980278015137,0.0,1739502660.354263,20.679980278015137,-0.10348116547305075,1739502660.3542645,20.679980278015137,6.260235489074008,1739502660.3542662,20.679980278015137,2.285690451830118 +1739502660.3740783,20.69998025894165,42.13156532001124,1739502660.3740807,20.69998025894165,0.03966803554498899,1739502660.3740835,20.69998025894165,41.36633345458069,1739502660.3740866,20.69998025894165,47.91861408684147,1739502660.3740883,20.69998025894165,0.07681892802389217,1739502660.3740897,20.69998025894165,0.006419573021337762,1739502660.3740911,20.69998025894165,0.16994116767759024,1739502660.3740928,20.69998025894165,0.03896755978940899,1739502660.374094,20.69998025894165,2.1822092863570672,1739502660.374096,20.69998025894165,0.0,1739502660.3740973,20.69998025894165,-0.10348116547305075,1739502660.3740988,20.69998025894165,6.260235489074008,1739502660.3741002,20.69998025894165,2.285690451830118 +1739502660.3944814,20.719980239868164,42.13156532001124,1739502660.3944845,20.719980239868164,0.03966803554498899,1739502660.394488,20.719980239868164,41.36633345458069,1739502660.3944912,20.719980239868164,47.91861408684147,1739502660.3944926,20.719980239868164,0.07681892802389217,1739502660.3944948,20.719980239868164,0.006419573021337762,1739502660.3944962,20.719980239868164,0.16994116767759024,1739502660.394498,20.719980239868164,0.03896755978940899,1739502660.3944993,20.719980239868164,2.1822092863570672,1739502660.3945012,20.719980239868164,0.0,1739502660.3945026,20.719980239868164,-0.10348116547305075,1739502660.3945043,20.719980239868164,6.260235489074008,1739502660.3945057,20.719980239868164,2.285690451830118 +1739502660.4142923,20.739980220794678,42.13156532001124,1739502660.4142947,20.739980220794678,0.03966803554498899,1739502660.4142978,20.739980220794678,41.36633345458069,1739502660.4143012,20.739980220794678,47.91861408684147,1739502660.4143028,20.739980220794678,0.07681892802389217,1739502660.4143045,20.739980220794678,0.006419573021337762,1739502660.4143062,20.739980220794678,0.16994116767759024,1739502660.4143076,20.739980220794678,0.03896755978940899,1739502660.414309,20.739980220794678,2.1822092863570672,1739502660.414311,20.739980220794678,0.0,1739502660.4143121,20.739980220794678,-0.10348116547305075,1739502660.4143138,20.739980220794678,6.260235489074008,1739502660.4143152,20.739980220794678,2.285690451830118 +1739502660.4343798,20.75998020172119,42.38227410688138,1739502660.434382,20.75998020172119,0.03387879092921953,1739502660.4343853,20.75998020172119,41.92004264356099,1739502660.4343886,20.75998020172119,48.436127982190776,1739502660.4343903,20.75998020172119,0.18737848983622982,1739502660.434392,20.75998020172119,0.025350267644062417,1739502660.4343936,20.75998020172119,0.2934677824597324,1739502660.434395,20.75998020172119,0.06144943808479767,1739502660.4343965,20.75998020172119,1.9768734003699218,1739502660.4343982,20.75998020172119,0.0,1739502660.4343998,20.75998020172119,-0.38441196485050616,1739502660.4344013,20.75998020172119,6.260055970508774,1739502660.4344027,20.75998020172119,2.2734944328547524 +1739502660.4544842,20.779980182647705,42.38227410688138,1739502660.4544878,20.779980182647705,0.03387879092921953,1739502660.454492,20.779980182647705,41.92004264356099,1739502660.4544954,20.779980182647705,48.436127982190776,1739502660.4544973,20.779980182647705,0.18737848983622982,1739502660.4544992,20.779980182647705,0.025350267644062417,1739502660.454501,20.779980182647705,0.2934677824597324,1739502660.4545026,20.779980182647705,0.06144943808479767,1739502660.4545043,20.779980182647705,1.9768734003699218,1739502660.454506,20.779980182647705,0.0,1739502660.4545076,20.779980182647705,-0.2966210324848306,1739502660.454509,20.779980182647705,6.260055970508774,1739502660.454511,20.779980182647705,2.2734944328547524 +1739502660.474235,20.79998016357422,42.38227410688138,1739502660.4742374,20.79998016357422,0.03387879092921953,1739502660.4742408,20.79998016357422,41.92004264356099,1739502660.4742439,20.79998016357422,48.436127982190776,1739502660.4742453,20.79998016357422,0.18737848983622982,1739502660.4742472,20.79998016357422,0.025350267644062417,1739502660.4742486,20.79998016357422,0.2934677824597324,1739502660.4742503,20.79998016357422,0.06144943808479767,1739502660.4742517,20.79998016357422,1.9768734003699218,1739502660.4742537,20.79998016357422,0.0,1739502660.474255,20.79998016357422,-0.2966210324848306,1739502660.4742568,20.79998016357422,6.260055970508774,1739502660.4742582,20.79998016357422,2.2734944328547524 +1739502660.4944742,20.819980144500732,42.38227410688138,1739502660.4944777,20.819980144500732,0.03387879092921953,1739502660.494481,20.819980144500732,41.92004264356099,1739502660.4944842,20.819980144500732,48.436127982190776,1739502660.4944859,20.819980144500732,0.18737848983622982,1739502660.4944875,20.819980144500732,0.025350267644062417,1739502660.4944894,20.819980144500732,0.2934677824597324,1739502660.4944909,20.819980144500732,0.06144943808479767,1739502660.494492,20.819980144500732,1.9768734003699218,1739502660.4944942,20.819980144500732,0.0,1739502660.4944956,20.819980144500732,-0.2966210324848306,1739502660.4944973,20.819980144500732,6.260055970508774,1739502660.4944987,20.819980144500732,2.2734944328547524 +1739502660.5142438,20.839980125427246,42.38227410688138,1739502660.5142465,20.839980125427246,0.03387879092921953,1739502660.5142498,20.839980125427246,41.92004264356099,1739502660.514253,20.839980125427246,48.436127982190776,1739502660.5142546,20.839980125427246,0.18737848983622982,1739502660.5142567,20.839980125427246,0.025350267644062417,1739502660.5142581,20.839980125427246,0.2934677824597324,1739502660.5142598,20.839980125427246,0.06144943808479767,1739502660.5142612,20.839980125427246,1.9768734003699218,1739502660.5142632,20.839980125427246,0.0,1739502660.5142646,20.839980125427246,-0.2966210324848306,1739502660.514266,20.839980125427246,6.260055970508774,1739502660.5142677,20.839980125427246,2.2734944328547524 +1739502660.5342624,20.85998010635376,42.63055076206798,1739502660.534265,20.85998010635376,0.028158289059372343,1739502660.5342684,20.85998010635376,41.92525645331991,1739502660.5342712,20.85998010635376,48.36851127783877,1739502660.534273,20.85998010635376,0.17100270668130552,1739502660.534275,20.85998010635376,0.02488949153065129,1739502660.5342767,20.85998010635376,0.2734403215586774,1739502660.5342782,20.85998010635376,0.06373445146946112,1739502660.5342796,20.85998010635376,2.0088018998555888,1739502660.5342817,20.85998010635376,0.0,1739502660.534283,20.85998010635376,-0.19578897123722167,1739502660.5342846,20.85998010635376,6.260416901114716,1739502660.534286,20.85998010635376,2.2361009108922802 +1739502660.5544887,20.879980087280273,42.63055076206798,1739502660.554492,20.879980087280273,0.028158289059372343,1739502660.554496,20.879980087280273,41.92525645331991,1739502660.5544994,20.879980087280273,48.36851127783877,1739502660.5545008,20.879980087280273,0.17100270668130552,1739502660.5545032,20.879980087280273,0.02488949153065129,1739502660.5545046,20.879980087280273,0.2734403215586774,1739502660.5545068,20.879980087280273,0.06373445146946112,1739502660.5545082,20.879980087280273,2.0088018998555888,1739502660.55451,20.879980087280273,0.0,1739502660.5545118,20.879980087280273,-0.22729901103669148,1739502660.5545135,20.879980087280273,6.260416901114716,1739502660.5545151,20.879980087280273,2.2361009108922802 +1739502660.574253,20.899980068206787,42.63055076206798,1739502660.5742555,20.899980068206787,0.028158289059372343,1739502660.5742588,20.899980068206787,41.92525645331991,1739502660.5742617,20.899980068206787,48.36851127783877,1739502660.5742633,20.899980068206787,0.17100270668130552,1739502660.574265,20.899980068206787,0.02488949153065129,1739502660.5742667,20.899980068206787,0.2734403215586774,1739502660.5742679,20.899980068206787,0.06373445146946112,1739502660.5742695,20.899980068206787,2.0088018998555888,1739502660.5742712,20.899980068206787,0.0,1739502660.5742729,20.899980068206787,-0.22729901103669148,1739502660.5742743,20.899980068206787,6.260416901114716,1739502660.5742757,20.899980068206787,2.2361009108922802 +1739502660.5944765,20.9199800491333,42.63055076206798,1739502660.5944796,20.9199800491333,0.028158289059372343,1739502660.5944836,20.9199800491333,41.92525645331991,1739502660.5944867,20.9199800491333,48.36851127783877,1739502660.5944884,20.9199800491333,0.17100270668130552,1739502660.5944903,20.9199800491333,0.02488949153065129,1739502660.594492,20.9199800491333,0.2734403215586774,1739502660.5944934,20.9199800491333,0.06373445146946112,1739502660.594495,20.9199800491333,2.0088018998555888,1739502660.5944967,20.9199800491333,0.0,1739502660.5944984,20.9199800491333,-0.22729901103669148,1739502660.5944998,20.9199800491333,6.260416901114716,1739502660.5945013,20.9199800491333,2.2361009108922802 +1739502660.614257,20.939980030059814,42.63055076206798,1739502660.6142595,20.939980030059814,0.028158289059372343,1739502660.6142628,20.939980030059814,41.92525645331991,1739502660.6142657,20.939980030059814,48.36851127783877,1739502660.6142673,20.939980030059814,0.17100270668130552,1739502660.6142693,20.939980030059814,0.02488949153065129,1739502660.6142712,20.939980030059814,0.2734403215586774,1739502660.6142726,20.939980030059814,0.06373445146946112,1739502660.614274,20.939980030059814,2.0088018998555888,1739502660.614276,20.939980030059814,0.0,1739502660.6142774,20.939980030059814,-0.22729901103669148,1739502660.6142788,20.939980030059814,6.260416901114716,1739502660.6142805,20.939980030059814,2.2361009108922802 +1739502660.6342993,20.959980010986328,42.63055076206798,1739502660.6343017,20.959980010986328,0.028158289059372343,1739502660.634305,20.959980010986328,41.92525645331991,1739502660.634308,20.959980010986328,48.36851127783877,1739502660.6343095,20.959980010986328,0.17100270668130552,1739502660.6343114,20.959980010986328,0.02488949153065129,1739502660.6343129,20.959980010986328,0.2734403215586774,1739502660.6343145,20.959980010986328,0.06373445146946112,1739502660.634316,20.959980010986328,2.0088018998555888,1739502660.6343179,20.959980010986328,0.0,1739502660.634319,20.959980010986328,-0.22729901103669148,1739502660.634321,20.959980010986328,6.260416901114716,1739502660.6343224,20.959980010986328,2.2361009108922802 +1739502660.6570318,20.979979991912842,42.87527395127038,1739502660.6570354,20.979979991912842,0.02269722461958068,1739502660.6570399,20.979979991912842,41.930395640293156,1739502660.6570454,20.979979991912842,48.32632746985634,1739502660.657048,20.979979991912842,0.16087859276552233,1739502660.6570518,20.979979991912842,0.02534405153281382,1739502660.6570554,20.979979991912842,0.2565498885888257,1739502660.6570587,20.979979991912842,0.06625559435617998,1739502660.657062,20.979979991912842,2.0361297427666805,1739502660.6570656,20.979979991912842,0.0,1739502660.657069,20.979979991912842,-0.1522614858501486,1739502660.6570728,20.979979991912842,6.261462821346988,1739502660.6570766,20.979979991912842,2.211840470612145 +1739502660.6740088,20.999979972839355,42.87527395127038,1739502660.674011,20.999979972839355,0.02269722461958068,1739502660.6740134,20.999979972839355,41.930395640293156,1739502660.6740158,20.999979972839355,48.32632746985634,1739502660.674017,20.999979972839355,0.16087859276552233,1739502660.6740186,20.999979972839355,0.02534405153281382,1739502660.67402,20.999979972839355,0.2565498885888257,1739502660.6740215,20.999979972839355,0.06625559435617998,1739502660.6740224,20.999979972839355,2.0361297427666805,1739502660.6740239,20.999979972839355,0.0,1739502660.6740253,20.999979972839355,-0.17571072784546438,1739502660.6740265,20.999979972839355,6.261462821346988,1739502660.674028,20.999979972839355,2.211840470612145 +1739502660.6942549,21.01997995376587,42.87527395127038,1739502660.6942573,21.01997995376587,0.02269722461958068,1739502660.6942601,21.01997995376587,41.930395640293156,1739502660.6942627,21.01997995376587,48.32632746985634,1739502660.6942644,21.01997995376587,0.16087859276552233,1739502660.694266,21.01997995376587,0.02534405153281382,1739502660.6942673,21.01997995376587,0.2565498885888257,1739502660.6942687,21.01997995376587,0.06625559435617998,1739502660.6942697,21.01997995376587,2.0361297427666805,1739502660.6942713,21.01997995376587,0.0,1739502660.6942725,21.01997995376587,-0.17571072784546438,1739502660.694274,21.01997995376587,6.261462821346988,1739502660.6942756,21.01997995376587,2.211840470612145 +1739502660.7140412,21.039979934692383,42.87527395127038,1739502660.7140434,21.039979934692383,0.02269722461958068,1739502660.7140462,21.039979934692383,41.930395640293156,1739502660.7140489,21.039979934692383,48.32632746985634,1739502660.71405,21.039979934692383,0.16087859276552233,1739502660.7140517,21.039979934692383,0.02534405153281382,1739502660.7140532,21.039979934692383,0.2565498885888257,1739502660.7140543,21.039979934692383,0.06625559435617998,1739502660.7140558,21.039979934692383,2.0361297427666805,1739502660.7140572,21.039979934692383,0.0,1739502660.7140584,21.039979934692383,-0.17571072784546438,1739502660.71406,21.039979934692383,6.261462821346988,1739502660.7140615,21.039979934692383,2.211840470612145 +1739502660.7340472,21.059979915618896,42.87527395127038,1739502660.7340493,21.059979915618896,0.02269722461958068,1739502660.7340522,21.059979915618896,41.930395640293156,1739502660.7340546,21.059979915618896,48.32632746985634,1739502660.734056,21.059979915618896,0.16087859276552233,1739502660.7340574,21.059979915618896,0.02534405153281382,1739502660.734059,21.059979915618896,0.2565498885888257,1739502660.7340603,21.059979915618896,0.06625559435617998,1739502660.7340615,21.059979915618896,2.0361297427666805,1739502660.7340631,21.059979915618896,0.0,1739502660.7340643,21.059979915618896,-0.17571072784546438,1739502660.7340658,21.059979915618896,6.261462821346988,1739502660.734067,21.059979915618896,2.211840470612145 +1739502660.754207,21.07997989654541,43.117548869564786,1739502660.7542093,21.07997989654541,0.017559468562168057,1739502660.7542124,21.07997989654541,42.405758107181526,1739502660.7542152,21.07997989654541,48.74665945257205,1739502660.7542164,21.07997989654541,0.2792485856695426,1739502660.7542183,21.07997989654541,0.04645509052929829,1739502660.7542198,21.07997989654541,0.3773862329052562,1739502660.7542212,21.07997989654541,0.09124229402122258,1739502660.7542226,21.07997989654541,1.8485133945667873,1739502660.7542238,21.07997989654541,0.0,1739502660.7542253,21.07997989654541,-0.4205919200284161,1739502660.7542267,21.07997989654541,6.262620671619223,1739502660.7542279,21.07997989654541,2.192579891864054 +1739502660.774067,21.099979877471924,43.117548869564786,1739502660.774069,21.099979877471924,0.017559468562168057,1739502660.7740717,21.099979877471924,42.405758107181526,1739502660.7740746,21.099979877471924,48.74665945257205,1739502660.774076,21.099979877471924,0.2792485856695426,1739502660.7740777,21.099979877471924,0.04645509052929829,1739502660.7740793,21.099979877471924,0.3773862329052562,1739502660.7740805,21.099979877471924,0.09124229402122258,1739502660.7740817,21.099979877471924,1.8485133945667873,1739502660.7740834,21.099979877471924,0.0,1739502660.7740848,21.099979877471924,-0.3440664972972667,1739502660.7740862,21.099979877471924,6.262620671619223,1739502660.7740877,21.099979877471924,2.192579891864054 +1739502660.7941985,21.119979858398438,43.117548869564786,1739502660.7942011,21.119979858398438,0.017559468562168057,1739502660.7942045,21.119979858398438,42.405758107181526,1739502660.7942076,21.119979858398438,48.74665945257205,1739502660.794209,21.119979858398438,0.2792485856695426,1739502660.7942111,21.119979858398438,0.04645509052929829,1739502660.7942128,21.119979858398438,0.3773862329052562,1739502660.7942147,21.119979858398438,0.09124229402122258,1739502660.7942162,21.119979858398438,1.8485133945667873,1739502660.7942183,21.119979858398438,0.0,1739502660.7942197,21.119979858398438,-0.3440664972972667,1739502660.7942214,21.119979858398438,6.262620671619223,1739502660.794223,21.119979858398438,2.192579891864054 +1739502660.8141124,21.13997983932495,43.117548869564786,1739502660.8141148,21.13997983932495,0.017559468562168057,1739502660.8141177,21.13997983932495,42.405758107181526,1739502660.8141203,21.13997983932495,48.74665945257205,1739502660.8141217,21.13997983932495,0.2792485856695426,1739502660.8141232,21.13997983932495,0.04645509052929829,1739502660.8141248,21.13997983932495,0.3773862329052562,1739502660.8141263,21.13997983932495,0.09124229402122258,1739502660.8141277,21.13997983932495,1.8485133945667873,1739502660.814129,21.13997983932495,0.0,1739502660.8141305,21.13997983932495,-0.3440664972972667,1739502660.814132,21.13997983932495,6.262620671619223,1739502660.8141332,21.13997983932495,2.192579891864054 +1739502660.8340619,21.159979820251465,43.117548869564786,1739502660.8340642,21.159979820251465,0.017559468562168057,1739502660.8340669,21.159979820251465,42.405758107181526,1739502660.8340697,21.159979820251465,48.74665945257205,1739502660.834071,21.159979820251465,0.2792485856695426,1739502660.8340728,21.159979820251465,0.04645509052929829,1739502660.834074,21.159979820251465,0.3773862329052562,1739502660.8340757,21.159979820251465,0.09124229402122258,1739502660.834077,21.159979820251465,1.8485133945667873,1739502660.8340786,21.159979820251465,0.0,1739502660.8340797,21.159979820251465,-0.3440664972972667,1739502660.8340812,21.159979820251465,6.262620671619223,1739502660.8340826,21.159979820251465,2.192579891864054 +1739502660.8542502,21.17997980117798,43.117548869564786,1739502660.8542528,21.17997980117798,0.017559468562168057,1739502660.8542562,21.17997980117798,42.405758107181526,1739502660.8542588,21.17997980117798,48.74665945257205,1739502660.85426,21.17997980117798,0.2792485856695426,1739502660.8542619,21.17997980117798,0.04645509052929829,1739502660.854263,21.17997980117798,0.3773862329052562,1739502660.8542643,21.17997980117798,0.09124229402122258,1739502660.8542657,21.17997980117798,1.8485133945667873,1739502660.8542671,21.17997980117798,0.0,1739502660.8542683,21.17997980117798,-0.3440664972972667,1739502660.85427,21.17997980117798,6.262620671619223,1739502660.8542714,21.17997980117798,2.192579891864054 +1739502660.874129,21.199979782104492,43.35672332394124,1739502660.8741314,21.199979782104492,0.012794452863626127,1739502660.8741345,21.199979782104492,42.94373257370135,1739502660.8741372,21.199979782104492,49.17603044332558,1739502660.8741386,21.199979782104492,0.44277049110782046,1739502660.8741403,21.199979782104492,0.07375381816577531,1739502660.8741417,21.199979782104492,0.5403121025338296,1739502660.874143,21.199979782104492,0.12180358883113859,1739502660.8741443,21.199979782104492,1.6226182525163046,1739502660.874146,21.199979782104492,0.0,1739502660.8741477,21.199979782104492,-0.615675943420431,1739502660.874149,21.199979782104492,6.264210523691987,1739502660.8741505,21.199979782104492,2.1534161883728884 +1739502660.8942347,21.219979763031006,43.35672332394124,1739502660.8942373,21.219979763031006,0.012794452863626127,1739502660.8942401,21.219979763031006,42.94373257370135,1739502660.894243,21.219979763031006,49.17603044332558,1739502660.8942444,21.219979763031006,0.44277049110782046,1739502660.894246,21.219979763031006,0.07375381816577531,1739502660.8942478,21.219979763031006,0.5403121025338296,1739502660.894249,21.219979763031006,0.12180358883113859,1739502660.8942502,21.219979763031006,1.6226182525163046,1739502660.8942518,21.219979763031006,0.0,1739502660.8942533,21.219979763031006,-0.5307979358565837,1739502660.8942547,21.219979763031006,6.264210523691987,1739502660.8942564,21.219979763031006,2.1534161883728884 +1739502660.9140916,21.23997974395752,43.35672332394124,1739502660.9140937,21.23997974395752,0.012794452863626127,1739502660.9140966,21.23997974395752,42.94373257370135,1739502660.9140995,21.23997974395752,49.17603044332558,1739502660.9141006,21.23997974395752,0.44277049110782046,1739502660.9141023,21.23997974395752,0.07375381816577531,1739502660.9141037,21.23997974395752,0.5403121025338296,1739502660.9141052,21.23997974395752,0.12180358883113859,1739502660.9141064,21.23997974395752,1.6226182525163046,1739502660.9141078,21.23997974395752,0.0,1739502660.9141092,21.23997974395752,-0.5307979358565837,1739502660.9141104,21.23997974395752,6.264210523691987,1739502660.914112,21.23997974395752,2.1534161883728884 +1739502660.9341705,21.259979724884033,43.35672332394124,1739502660.9341726,21.259979724884033,0.012794452863626127,1739502660.9341757,21.259979724884033,42.94373257370135,1739502660.9341784,21.259979724884033,49.17603044332558,1739502660.9341798,21.259979724884033,0.44277049110782046,1739502660.9341817,21.259979724884033,0.07375381816577531,1739502660.934183,21.259979724884033,0.5403121025338296,1739502660.9341846,21.259979724884033,0.12180358883113859,1739502660.9341857,21.259979724884033,1.6226182525163046,1739502660.9341872,21.259979724884033,0.0,1739502660.9341886,21.259979724884033,-0.5307979358565837,1739502660.9341898,21.259979724884033,6.264210523691987,1739502660.9341915,21.259979724884033,2.1534161883728884 +1739502660.9542522,21.279979705810547,43.35672332394124,1739502660.9542546,21.279979705810547,0.012794452863626127,1739502660.9542577,21.279979705810547,42.94373257370135,1739502660.9542606,21.279979705810547,49.17603044332558,1739502660.9542618,21.279979705810547,0.44277049110782046,1739502660.9542634,21.279979705810547,0.07375381816577531,1739502660.9542649,21.279979705810547,0.5403121025338296,1739502660.9542665,21.279979705810547,0.12180358883113859,1739502660.9542677,21.279979705810547,1.6226182525163046,1739502660.9542694,21.279979705810547,0.0,1739502660.9542704,21.279979705810547,-0.5307979358565837,1739502660.954272,21.279979705810547,6.264210523691987,1739502660.9542735,21.279979705810547,2.1534161883728884 +1739502660.9740949,21.29997968673706,43.59068245067479,1739502660.9740973,21.29997968673706,0.008602700397869256,1739502660.9740999,21.29997968673706,42.94841175623602,1739502660.9741027,21.29997968673706,49.07335127787854,1739502660.9741042,21.29997968673706,0.39950501165073327,1739502660.9741058,21.29997968673706,0.07117737152277856,1739502660.9741075,21.29997968673706,0.48108943951323746,1739502660.9741087,21.29997968673706,0.12222513875244176,1739502660.97411,21.29997968673706,1.701345111516238,1739502660.9741116,21.29997968673706,0.0,1739502660.9741127,21.29997968673706,-0.33184840220635603,1739502660.974114,21.29997968673706,6.266725411821695,1739502660.9741156,21.29997968673706,2.095365283751279 +1739502660.9942439,21.319979667663574,43.59068245067479,1739502660.9942467,21.319979667663574,0.008602700397869256,1739502660.9942498,21.319979667663574,42.94841175623602,1739502660.9942524,21.319979667663574,49.07335127787854,1739502660.9942539,21.319979667663574,0.39950501165073327,1739502660.9942555,21.319979667663574,0.07117737152277856,1739502660.9942572,21.319979667663574,0.48108943951323746,1739502660.9942586,21.319979667663574,0.12222513875244176,1739502660.99426,21.319979667663574,1.701345111516238,1739502660.9942615,21.319979667663574,0.0,1739502660.9942627,21.319979667663574,-0.39402017223504116,1739502660.9942648,21.319979667663574,6.266725411821695,1739502660.994266,21.319979667663574,2.095365283751279 +1739502661.0140936,21.339979648590088,43.59068245067479,1739502661.0140958,21.339979648590088,0.008602700397869256,1739502661.0140986,21.339979648590088,42.94841175623602,1739502661.0141015,21.339979648590088,49.07335127787854,1739502661.0141027,21.339979648590088,0.39950501165073327,1739502661.0141044,21.339979648590088,0.07117737152277856,1739502661.0141058,21.339979648590088,0.48108943951323746,1739502661.0141072,21.339979648590088,0.12222513875244176,1739502661.0141084,21.339979648590088,1.701345111516238,1739502661.0141103,21.339979648590088,0.0,1739502661.0141118,21.339979648590088,-0.39402017223504116,1739502661.014113,21.339979648590088,6.266725411821695,1739502661.0141146,21.339979648590088,2.095365283751279 +1739502661.034077,21.3599796295166,43.59068245067479,1739502661.0340793,21.3599796295166,0.008602700397869256,1739502661.034082,21.3599796295166,42.94841175623602,1739502661.034085,21.3599796295166,49.07335127787854,1739502661.0340865,21.3599796295166,0.39950501165073327,1739502661.0340881,21.3599796295166,0.07117737152277856,1739502661.0340896,21.3599796295166,0.48108943951323746,1739502661.034091,21.3599796295166,0.12222513875244176,1739502661.0340922,21.3599796295166,1.701345111516238,1739502661.0340939,21.3599796295166,0.0,1739502661.034095,21.3599796295166,-0.39402017223504116,1739502661.0340967,21.3599796295166,6.266725411821695,1739502661.034098,21.3599796295166,2.095365283751279 +1739502661.0542245,21.379979610443115,43.59068245067479,1739502661.0542266,21.379979610443115,0.008602700397869256,1739502661.0542297,21.379979610443115,42.94841175623602,1739502661.0542328,21.379979610443115,49.07335127787854,1739502661.054234,21.379979610443115,0.39950501165073327,1739502661.054236,21.379979610443115,0.07117737152277856,1739502661.0542371,21.379979610443115,0.48108943951323746,1739502661.0542386,21.379979610443115,0.12222513875244176,1739502661.0542397,21.379979610443115,1.701345111516238,1739502661.0542414,21.379979610443115,0.0,1739502661.0542428,21.379979610443115,-0.39402017223504116,1739502661.0542443,21.379979610443115,6.266725411821695,1739502661.0542462,21.379979610443115,2.095365283751279 +1739502661.0741367,21.39997959136963,43.59068245067479,1739502661.0741389,21.39997959136963,0.008602700397869256,1739502661.074142,21.39997959136963,42.94841175623602,1739502661.0741446,21.39997959136963,49.07335127787854,1739502661.0741458,21.39997959136963,0.39950501165073327,1739502661.0741477,21.39997959136963,0.07117737152277856,1739502661.0741491,21.39997959136963,0.48108943951323746,1739502661.0741503,21.39997959136963,0.12222513875244176,1739502661.0741518,21.39997959136963,1.701345111516238,1739502661.0741532,21.39997959136963,0.0,1739502661.0741544,21.39997959136963,-0.39402017223504116,1739502661.074156,21.39997959136963,6.266725411821695,1739502661.0741572,21.39997959136963,2.095365283751279 +1739502661.094312,21.419979572296143,43.81923445255131,1739502661.0943148,21.419979572296143,0.005179654825904656,1739502661.094318,21.419979572296143,42.95298279627355,1739502661.0943205,21.419979572296143,49.006764324617464,1739502661.094322,21.419979572296143,0.3726888414326589,1739502661.0943236,21.419979572296143,0.07072656939836411,1739502661.094325,21.419979572296143,0.43519119564320213,1739502661.0943263,21.419979572296143,0.1235095019090525,1739502661.0943274,21.419979572296143,1.7649772051268966,1739502661.0943294,21.419979572296143,0.0,1739502661.0943305,21.419979572296143,-0.2459315288323591,1739502661.0943322,21.419979572296143,6.270131841702156,1739502661.0943336,21.419979572296143,2.057186465364639 +1739502661.1140788,21.439979553222656,43.81923445255131,1739502661.1140807,21.439979553222656,0.005179654825904656,1739502661.1140838,21.439979553222656,42.95298279627355,1739502661.1140866,21.439979553222656,49.006764324617464,1739502661.1140878,21.439979553222656,0.3726888414326589,1739502661.1140897,21.439979553222656,0.07072656939836411,1739502661.114091,21.439979553222656,0.43519119564320213,1739502661.1140924,21.439979553222656,0.1235095019090525,1739502661.1140938,21.439979553222656,1.7649772051268966,1739502661.1140954,21.439979553222656,0.0,1739502661.1140966,21.439979553222656,-0.2922092602377424,1739502661.1140978,21.439979553222656,6.270131841702156,1739502661.1140995,21.439979553222656,2.057186465364639 +1739502661.1340783,21.45997953414917,43.81923445255131,1739502661.1340802,21.45997953414917,0.005179654825904656,1739502661.1340833,21.45997953414917,42.95298279627355,1739502661.1340861,21.45997953414917,49.006764324617464,1739502661.1340876,21.45997953414917,0.3726888414326589,1739502661.1340895,21.45997953414917,0.07072656939836411,1739502661.1340907,21.45997953414917,0.43519119564320213,1739502661.1340923,21.45997953414917,0.1235095019090525,1739502661.1340933,21.45997953414917,1.7649772051268966,1739502661.1340952,21.45997953414917,0.0,1739502661.1340964,21.45997953414917,-0.2922092602377424,1739502661.1340976,21.45997953414917,6.270131841702156,1739502661.1340992,21.45997953414917,2.057186465364639 +1739502661.1542597,21.479979515075684,43.81923445255131,1739502661.154262,21.479979515075684,0.005179654825904656,1739502661.1542652,21.479979515075684,42.95298279627355,1739502661.1542678,21.479979515075684,49.006764324617464,1739502661.1542692,21.479979515075684,0.3726888414326589,1739502661.154271,21.479979515075684,0.07072656939836411,1739502661.1542726,21.479979515075684,0.43519119564320213,1739502661.1542737,21.479979515075684,0.1235095019090525,1739502661.1542752,21.479979515075684,1.7649772051268966,1739502661.1542768,21.479979515075684,0.0,1739502661.154278,21.479979515075684,-0.2922092602377424,1739502661.1542797,21.479979515075684,6.270131841702156,1739502661.1542811,21.479979515075684,2.057186465364639 +1739502661.174088,21.499979496002197,43.81923445255131,1739502661.1740901,21.499979496002197,0.005179654825904656,1739502661.1740928,21.499979496002197,42.95298279627355,1739502661.1740956,21.499979496002197,49.006764324617464,1739502661.1740968,21.499979496002197,0.3726888414326589,1739502661.1740985,21.499979496002197,0.07072656939836411,1739502661.1741,21.499979496002197,0.43519119564320213,1739502661.1741018,21.499979496002197,0.1235095019090525,1739502661.174103,21.499979496002197,1.7649772051268966,1739502661.1741047,21.499979496002197,0.0,1739502661.174106,21.499979496002197,-0.2922092602377424,1739502661.1741073,21.499979496002197,6.270131841702156,1739502661.1741087,21.499979496002197,2.057186465364639 +1739502661.1944008,21.51997947692871,44.043616915300525,1739502661.1944034,21.51997947692871,0.0026189383493440133,1739502661.1944065,21.51997947692871,43.227522039985416,1739502661.1944091,21.51997947692871,49.19051556706408,1739502661.1944108,21.51997947692871,0.44891569511809554,1739502661.1944122,21.51997947692871,0.08649543106632505,1739502661.1944144,21.51997947692871,0.49480920330763933,1739502661.1944156,21.51997947692871,0.14227505863441503,1739502661.194417,21.51997947692871,1.68277357434728,1739502661.1944184,21.51997947692871,0.0,1739502661.1944196,21.51997947692871,-0.35679981824989687,1739502661.1944213,21.51997947692871,6.273755743763933,1739502661.1944225,21.51997947692871,2.019388829984348 +1739502661.214485,21.539979457855225,44.043616915300525,1739502661.2144873,21.539979457855225,0.0026189383493440133,1739502661.2144902,21.539979457855225,43.227522039985416,1739502661.214493,21.539979457855225,49.19051556706408,1739502661.2144942,21.539979457855225,0.44891569511809554,1739502661.214496,21.539979457855225,0.08649543106632505,1739502661.2144976,21.539979457855225,0.49480920330763933,1739502661.214502,21.539979457855225,0.14227505863441503,1739502661.2145052,21.539979457855225,1.68277357434728,1739502661.214508,21.539979457855225,0.0,1739502661.214512,21.539979457855225,-0.33661525563706807,1739502661.2145157,21.539979457855225,6.273755743763933,1739502661.2145174,21.539979457855225,2.019388829984348 +1739502661.2362552,21.55997943878174,44.043616915300525,1739502661.2362604,21.55997943878174,0.0026189383493440133,1739502661.2362652,21.55997943878174,43.227522039985416,1739502661.2362707,21.55997943878174,49.19051556706408,1739502661.2362745,21.55997943878174,0.44891569511809554,1739502661.2362783,21.55997943878174,0.08649543106632505,1739502661.2362828,21.55997943878174,0.49480920330763933,1739502661.2362864,21.55997943878174,0.14227505863441503,1739502661.2362897,21.55997943878174,1.68277357434728,1739502661.2362933,21.55997943878174,0.0,1739502661.236297,21.55997943878174,-0.33661525563706807,1739502661.2363002,21.55997943878174,6.273755743763933,1739502661.2363038,21.55997943878174,2.019388829984348 +1739502661.2553933,21.579979419708252,44.043616915300525,1739502661.2553968,21.579979419708252,0.0026189383493440133,1739502661.2554014,21.579979419708252,43.227522039985416,1739502661.2554061,21.579979419708252,49.19051556706408,1739502661.2554083,21.579979419708252,0.44891569511809554,1739502661.2554114,21.579979419708252,0.08649543106632505,1739502661.255414,21.579979419708252,0.49480920330763933,1739502661.2554164,21.579979419708252,0.14227505863441503,1739502661.2554185,21.579979419708252,1.68277357434728,1739502661.2554212,21.579979419708252,0.0,1739502661.2554235,21.579979419708252,-0.33661525563706807,1739502661.255426,21.579979419708252,6.273755743763933,1739502661.2554286,21.579979419708252,2.019388829984348 +1739502661.2753942,21.599979400634766,44.043616915300525,1739502661.2753983,21.599979400634766,0.0026189383493440133,1739502661.2754025,21.599979400634766,43.227522039985416,1739502661.2754073,21.599979400634766,49.19051556706408,1739502661.2754097,21.599979400634766,0.44891569511809554,1739502661.2754128,21.599979400634766,0.08649543106632505,1739502661.275416,21.599979400634766,0.49480920330763933,1739502661.2754183,21.599979400634766,0.14227505863441503,1739502661.2754207,21.599979400634766,1.68277357434728,1739502661.2754238,21.599979400634766,0.0,1739502661.2754261,21.599979400634766,-0.33661525563706807,1739502661.2754283,21.599979400634766,6.273755743763933,1739502661.2754312,21.599979400634766,2.019388829984348 +1739502661.295403,21.61997938156128,44.043616915300525,1739502661.2954063,21.61997938156128,0.0026189383493440133,1739502661.2954106,21.61997938156128,43.227522039985416,1739502661.2954147,21.61997938156128,49.19051556706408,1739502661.2954168,21.61997938156128,0.44891569511809554,1739502661.2954197,21.61997938156128,0.08649543106632505,1739502661.2954218,21.61997938156128,0.49480920330763933,1739502661.2954242,21.61997938156128,0.14227505863441503,1739502661.2954266,21.61997938156128,1.68277357434728,1739502661.2954295,21.61997938156128,0.0,1739502661.2954316,21.61997938156128,-0.33661525563706807,1739502661.2954342,21.61997938156128,6.273755743763933,1739502661.295437,21.61997938156128,2.019388829984348 +1739502661.3154833,21.639979362487793,44.26386852039332,1739502661.3154879,21.639979362487793,0.0009294907662944496,1739502661.3154924,21.639979362487793,43.946901560230636,1739502661.3154967,21.639979362487793,49.762856721833494,1739502661.3154993,21.639979362487793,0.7443527028027865,1739502661.3155022,21.639979362487793,0.13437800077265769,1739502661.3155048,21.639979362487793,0.7729543995269351,1739502661.3155074,21.639979362487793,0.19252484193364278,1739502661.3155098,21.639979362487793,1.3470637345762233,1739502661.3155127,21.639979362487793,0.0,1739502661.3155148,21.639979362487793,-0.7704866074387532,1739502661.3155174,21.639979362487793,6.277813035669526,1739502661.31552,21.639979362487793,1.981965455680571 +1739502661.3340776,21.659979343414307,44.26386852039332,1739502661.3340797,21.659979343414307,0.0009294907662944496,1739502661.3340828,21.659979343414307,43.946901560230636,1739502661.3340855,21.659979343414307,49.762856721833494,1739502661.3340867,21.659979343414307,0.7443527028027865,1739502661.334088,21.659979343414307,0.13437800077265769,1739502661.3340895,21.659979343414307,0.7729543995269351,1739502661.3340907,21.659979343414307,0.19252484193364278,1739502661.3340917,21.659979343414307,1.3470637345762233,1739502661.3340933,21.659979343414307,0.0,1739502661.3340945,21.659979343414307,-0.6349017211043477,1739502661.334096,21.659979343414307,6.277813035669526,1739502661.3340971,21.659979343414307,1.981965455680571 +1739502661.3543134,21.67997932434082,44.26386852039332,1739502661.354316,21.67997932434082,0.0009294907662944496,1739502661.3543186,21.67997932434082,43.946901560230636,1739502661.3543212,21.67997932434082,49.762856721833494,1739502661.3543222,21.67997932434082,0.7443527028027865,1739502661.3543243,21.67997932434082,0.13437800077265769,1739502661.3543255,21.67997932434082,0.7729543995269351,1739502661.3543267,21.67997932434082,0.19252484193364278,1739502661.354328,21.67997932434082,1.3470637345762233,1739502661.3543293,21.67997932434082,0.0,1739502661.3543305,21.67997932434082,-0.6349017211043477,1739502661.354332,21.67997932434082,6.277813035669526,1739502661.3543332,21.67997932434082,1.981965455680571 +1739502661.3740542,21.699979305267334,44.26386852039332,1739502661.374056,21.699979305267334,0.0009294907662944496,1739502661.374059,21.699979305267334,43.946901560230636,1739502661.3740613,21.699979305267334,49.762856721833494,1739502661.3740625,21.699979305267334,0.7443527028027865,1739502661.3740642,21.699979305267334,0.13437800077265769,1739502661.3740654,21.699979305267334,0.7729543995269351,1739502661.3740666,21.699979305267334,0.19252484193364278,1739502661.3740678,21.699979305267334,1.3470637345762233,1739502661.3740692,21.699979305267334,0.0,1739502661.3740706,21.699979305267334,-0.6349017211043477,1739502661.3740718,21.699979305267334,6.277813035669526,1739502661.374073,21.699979305267334,1.981965455680571 +1739502661.3942375,21.719979286193848,44.26386852039332,1739502661.39424,21.719979286193848,0.0009294907662944496,1739502661.3942428,21.719979286193848,43.946901560230636,1739502661.3942451,21.719979286193848,49.762856721833494,1739502661.3942463,21.719979286193848,0.7443527028027865,1739502661.394248,21.719979286193848,0.13437800077265769,1739502661.3942492,21.719979286193848,0.7729543995269351,1739502661.3942504,21.719979286193848,0.19252484193364278,1739502661.3942518,21.719979286193848,1.3470637345762233,1739502661.3942533,21.719979286193848,0.0,1739502661.3942547,21.719979286193848,-0.6349017211043477,1739502661.3942559,21.719979286193848,6.277813035669526,1739502661.394257,21.719979286193848,1.981965455680571 +1739502661.4141238,21.73997926712036,44.478466370170636,1739502661.4141262,21.73997926712036,0.0002307082061516752,1739502661.4141285,21.73997926712036,43.95119351722618,1739502661.4141312,21.73997926712036,49.64601443322917,1739502661.4141326,21.73997926712036,0.6781993482253393,1739502661.414134,21.73997926712036,0.1304522797327586,1739502661.4141355,21.73997926712036,0.6806227207257947,1739502661.414137,21.73997926712036,0.1921729359682519,1739502661.4141378,21.73997926712036,1.4503320863707516,1739502661.4141395,21.73997926712036,0.0,1739502661.4141407,21.73997926712036,-0.3839209272895449,1739502661.4141421,21.73997926712036,6.2826716844289505,1739502661.4141436,21.73997926712036,1.9126845631511535 +1739502661.4343123,21.759979248046875,44.478466370170636,1739502661.4343147,21.759979248046875,0.0002307082061516752,1739502661.434318,21.759979248046875,43.95119351722618,1739502661.434321,21.759979248046875,49.64601443322917,1739502661.434322,21.759979248046875,0.6781993482253393,1739502661.434324,21.759979248046875,0.1304522797327586,1739502661.4343252,21.759979248046875,0.6806227207257947,1739502661.434327,21.759979248046875,0.1921729359682519,1739502661.434328,21.759979248046875,1.4503320863707516,1739502661.4343297,21.759979248046875,0.0,1739502661.4343312,21.759979248046875,-0.4623524767804019,1739502661.4343326,21.759979248046875,6.2826716844289505,1739502661.434334,21.759979248046875,1.9126845631511535 +1739502661.4545097,21.77997922897339,44.478466370170636,1739502661.4545126,21.77997922897339,0.0002307082061516752,1739502661.4545162,21.77997922897339,43.95119351722618,1739502661.454519,21.77997922897339,49.64601443322917,1739502661.4545205,21.77997922897339,0.6781993482253393,1739502661.4545221,21.77997922897339,0.1304522797327586,1739502661.4545238,21.77997922897339,0.6806227207257947,1739502661.4545255,21.77997922897339,0.1921729359682519,1739502661.4545267,21.77997922897339,1.4503320863707516,1739502661.4545283,21.77997922897339,0.0,1739502661.4545298,21.77997922897339,-0.4623524767804019,1739502661.4545314,21.77997922897339,6.2826716844289505,1739502661.4545329,21.77997922897339,1.9126845631511535 +1739502661.4744189,21.799979209899902,44.478466370170636,1739502661.4744213,21.799979209899902,0.0002307082061516752,1739502661.4744246,21.799979209899902,43.95119351722618,1739502661.4744277,21.799979209899902,49.64601443322917,1739502661.4744291,21.799979209899902,0.6781993482253393,1739502661.4744313,21.799979209899902,0.1304522797327586,1739502661.4744327,21.799979209899902,0.6806227207257947,1739502661.4744344,21.799979209899902,0.1921729359682519,1739502661.4744358,21.799979209899902,1.4503320863707516,1739502661.4744377,21.799979209899902,0.0,1739502661.4744391,21.799979209899902,-0.4623524767804019,1739502661.474441,21.799979209899902,6.2826716844289505,1739502661.4744425,21.799979209899902,1.9126845631511535 +1739502661.4945774,21.819979190826416,44.478466370170636,1739502661.4945807,21.819979190826416,0.0002307082061516752,1739502661.4945846,21.819979190826416,43.95119351722618,1739502661.494588,21.819979190826416,49.64601443322917,1739502661.4945898,21.819979190826416,0.6781993482253393,1739502661.4945922,21.819979190826416,0.1304522797327586,1739502661.494594,21.819979190826416,0.6806227207257947,1739502661.494596,21.819979190826416,0.1921729359682519,1739502661.4945977,21.819979190826416,1.4503320863707516,1739502661.4945996,21.819979190826416,0.0,1739502661.4946012,21.819979190826416,-0.4623524767804019,1739502661.4946039,21.819979190826416,6.2826716844289505,1739502661.4946055,21.819979190826416,1.9126845631511535 +1739502661.5143974,21.83997917175293,44.478466370170636,1739502661.5144,21.83997917175293,0.0002307082061516752,1739502661.5144033,21.83997917175293,43.95119351722618,1739502661.5144067,21.83997917175293,49.64601443322917,1739502661.514408,21.83997917175293,0.6781993482253393,1739502661.51441,21.83997917175293,0.1304522797327586,1739502661.514412,21.83997917175293,0.6806227207257947,1739502661.5144136,21.83997917175293,0.1921729359682519,1739502661.514415,21.83997917175293,1.4503320863707516,1739502661.514417,21.83997917175293,0.0,1739502661.5144184,21.83997917175293,-0.4623524767804019,1739502661.51442,21.83997917175293,6.2826716844289505,1739502661.5144215,21.83997917175293,1.9126845631511535 +1739502661.5346913,21.859979152679443,44.6865710430066,1739502661.5346947,21.859979152679443,0.0006567275120659133,1739502661.5346985,21.859979152679443,43.9553556106829,1739502661.534702,21.859979152679443,49.56552173107943,1739502661.534704,21.859979152679443,0.6337620092807383,1739502661.534706,21.859979152679443,0.12904153332234125,1739502661.5347083,21.859979152679443,0.6071014307674599,1739502661.53471,21.859979152679443,0.19236317501357147,1739502661.5347116,21.859979152679443,1.5381949018281647,1739502661.5347135,21.859979152679443,0.0,1739502661.5347157,21.859979152679443,-0.264654240426957,1739502661.5347173,21.859979152679443,0.005327987419951665,1739502661.5347192,21.859979152679443,1.8646298816221825 +1739502661.5552423,21.879979133605957,44.6865710430066,1739502661.5552454,21.879979133605957,0.0006567275120659133,1739502661.55525,21.879979133605957,43.9553556106829,1739502661.5552537,21.879979133605957,49.56552173107943,1739502661.555256,21.879979133605957,0.6337620092807383,1739502661.5552583,21.879979133605957,0.12904153332234125,1739502661.5552602,21.879979133605957,0.6071014307674599,1739502661.5552623,21.879979133605957,0.19236317501357147,1739502661.555264,21.879979133605957,1.5381949018281647,1739502661.5552664,21.879979133605957,0.0,1739502661.5552683,21.879979133605957,-0.3264349797940178,1739502661.5552704,21.879979133605957,0.005327987419951665,1739502661.555272,21.879979133605957,1.8646298816221825 +1739502661.5749238,21.89997911453247,44.6865710430066,1739502661.5749276,21.89997911453247,0.0006567275120659133,1739502661.5749328,21.89997911453247,43.9553556106829,1739502661.5749369,21.89997911453247,49.56552173107943,1739502661.5749388,21.89997911453247,0.6337620092807383,1739502661.5749412,21.89997911453247,0.12904153332234125,1739502661.5749433,21.89997911453247,0.6071014307674599,1739502661.5749452,21.89997911453247,0.19236317501357147,1739502661.5749474,21.89997911453247,1.5381949018281647,1739502661.5749497,21.89997911453247,0.0,1739502661.5749516,21.89997911453247,-0.3264349797940178,1739502661.5749543,21.89997911453247,0.005327987419951665,1739502661.5749562,21.89997911453247,1.8646298816221825 +1739502661.5948505,21.919979095458984,44.6865710430066,1739502661.5948536,21.919979095458984,0.0006567275120659133,1739502661.594858,21.919979095458984,43.9553556106829,1739502661.594862,21.919979095458984,49.56552173107943,1739502661.594864,21.919979095458984,0.6337620092807383,1739502661.5948663,21.919979095458984,0.12904153332234125,1739502661.5948682,21.919979095458984,0.6071014307674599,1739502661.59487,21.919979095458984,0.19236317501357147,1739502661.5948718,21.919979095458984,1.5381949018281647,1739502661.5948741,21.919979095458984,0.0,1739502661.594876,21.919979095458984,-0.3264349797940178,1739502661.594878,21.919979095458984,0.005327987419951665,1739502661.59488,21.919979095458984,1.8646298816221825 +1739502661.6152291,21.939979076385498,44.6865710430066,1739502661.6152332,21.939979076385498,0.0006567275120659133,1739502661.6152377,21.939979076385498,43.9553556106829,1739502661.6152418,21.939979076385498,49.56552173107943,1739502661.6152437,21.939979076385498,0.6337620092807383,1739502661.6152463,21.939979076385498,0.12904153332234125,1739502661.6152484,21.939979076385498,0.6071014307674599,1739502661.61525,21.939979076385498,0.19236317501357147,1739502661.6152523,21.939979076385498,1.5381949018281647,1739502661.6152546,21.939979076385498,0.0,1739502661.6152563,21.939979076385498,-0.3264349797940178,1739502661.6152585,21.939979076385498,0.005327987419951665,1739502661.6152604,21.939979076385498,1.8646298816221825 +1739502661.6351442,21.95997905731201,44.88974404350032,1739502661.6351478,21.95997905731201,0.0023432854094140865,1739502661.6351519,21.95997905731201,43.959419070692775,1739502661.635156,21.95997905731201,49.5038365202575,1739502661.6351578,21.95997905731201,0.5999108292313629,1739502661.6351602,21.95997905731201,0.12879235571702313,1739502661.6351624,21.95997905731201,0.5424564410522004,1739502661.6351643,21.95997905731201,0.19219183717616228,1739502661.6351662,21.95997905731201,1.6198370844490884,1739502661.6351686,21.95997905731201,0.0,1739502661.6351702,21.95997905731201,-0.15355405267168853,1739502661.6351726,21.95997905731201,0.011935142161647386,1739502661.6351748,21.95997905731201,1.8274164622682683 +1739502661.6550295,21.979979038238525,44.88974404350032,1739502661.6550329,21.979979038238525,0.0023432854094140865,1739502661.6550372,21.979979038238525,43.959419070692775,1739502661.6550412,21.979979038238525,49.5038365202575,1739502661.6550431,21.979979038238525,0.5999108292313629,1739502661.6550453,21.979979038238525,0.12879235571702313,1739502661.6550474,21.979979038238525,0.5424564410522004,1739502661.6550496,21.979979038238525,0.19219183717616228,1739502661.6550515,21.979979038238525,1.6198370844490884,1739502661.6550539,21.979979038238525,0.0,1739502661.6550558,21.979979038238525,-0.2075793778191799,1739502661.6550577,21.979979038238525,0.011935142161647386,1739502661.6550598,21.979979038238525,1.8274164622682683 +1739502661.6751018,21.99997901916504,44.88974404350032,1739502661.6751053,21.99997901916504,0.0023432854094140865,1739502661.6751096,21.99997901916504,43.959419070692775,1739502661.6751134,21.99997901916504,49.5038365202575,1739502661.6751156,21.99997901916504,0.5999108292313629,1739502661.675118,21.99997901916504,0.12879235571702313,1739502661.67512,21.99997901916504,0.5424564410522004,1739502661.675122,21.99997901916504,0.19219183717616228,1739502661.675124,21.99997901916504,1.6198370844490884,1739502661.675126,21.99997901916504,0.0,1739502661.675128,21.99997901916504,-0.2075793778191799,1739502661.6751301,21.99997901916504,0.011935142161647386,1739502661.6751323,21.99997901916504,1.8274164622682683 +1739502661.6952977,22.019979000091553,44.88974404350032,1739502661.695301,22.019979000091553,0.0023432854094140865,1739502661.695305,22.019979000091553,43.959419070692775,1739502661.6953096,22.019979000091553,49.5038365202575,1739502661.6953115,22.019979000091553,0.5999108292313629,1739502661.695314,22.019979000091553,0.12879235571702313,1739502661.695316,22.019979000091553,0.5424564410522004,1739502661.695318,22.019979000091553,0.19219183717616228,1739502661.69532,22.019979000091553,1.6198370844490884,1739502661.6953218,22.019979000091553,0.0,1739502661.695324,22.019979000091553,-0.2075793778191799,1739502661.6953259,22.019979000091553,0.011935142161647386,1739502661.695328,22.019979000091553,1.8274164622682683 +1739502661.715127,22.039978981018066,44.88974404350032,1739502661.7151308,22.039978981018066,0.0023432854094140865,1739502661.7151353,22.039978981018066,43.959419070692775,1739502661.7151392,22.039978981018066,49.5038365202575,1739502661.715141,22.039978981018066,0.5999108292313629,1739502661.7151437,22.039978981018066,0.12879235571702313,1739502661.7151458,22.039978981018066,0.5424564410522004,1739502661.7151477,22.039978981018066,0.19219183717616228,1739502661.7151496,22.039978981018066,1.6198370844490884,1739502661.7151518,22.039978981018066,0.0,1739502661.7151537,22.039978981018066,-0.2075793778191799,1739502661.715156,22.039978981018066,0.011935142161647386,1739502661.715158,22.039978981018066,1.8274164622682683 +1739502661.7351003,22.05997896194458,44.88974404350032,1739502661.7351038,22.05997896194458,0.0023432854094140865,1739502661.7351081,22.05997896194458,43.959419070692775,1739502661.7351122,22.05997896194458,49.5038365202575,1739502661.7351146,22.05997896194458,0.5999108292313629,1739502661.7351167,22.05997896194458,0.12879235571702313,1739502661.7351189,22.05997896194458,0.5424564410522004,1739502661.735121,22.05997896194458,0.19219183717616228,1739502661.7351227,22.05997896194458,1.6198370844490884,1739502661.735125,22.05997896194458,0.0,1739502661.7351267,22.05997896194458,-0.2075793778191799,1739502661.7351289,22.05997896194458,0.011935142161647386,1739502661.735131,22.05997896194458,1.8274164622682683 +1739502661.7551284,22.079978942871094,45.089700668006536,1739502661.7551315,22.079978942871094,0.005333708707708773,1739502661.7551355,22.079978942871094,44.996061025612036,1739502661.7551394,22.079978942871094,50.33734518915617,1739502661.7551413,22.079978942871094,1.1375551547641336,1739502661.7551436,22.079978942871094,0.21250058563630184,1739502661.7551458,22.079978942871094,1.0344681638319468,1739502661.7551475,22.079978942871094,0.2748976386927798,1739502661.7551494,22.079978942871094,1.092770484935204,1739502661.7551515,22.079978942871094,0.0,1739502661.7551537,22.079978942871094,-0.7129823144418133,1739502661.7551556,22.079978942871094,0.018591813643428594,1739502661.7551575,22.079978942871094,1.8057527993770173 +1739502661.7751913,22.099978923797607,45.089700668006536,1739502661.7751951,22.099978923797607,0.005333708707708773,1739502661.7751994,22.099978923797607,44.996061025612036,1739502661.7752035,22.099978923797607,50.33734518915617,1739502661.7752054,22.099978923797607,1.1375551547641336,1739502661.775208,22.099978923797607,0.21250058563630184,1739502661.77521,22.099978923797607,1.0344681638319468,1739502661.775212,22.099978923797607,0.2748976386927798,1739502661.7752137,22.099978923797607,1.092770484935204,1739502661.775216,22.099978923797607,0.0,1739502661.7752182,22.099978923797607,-0.7129823144418133,1739502661.7752202,22.099978923797607,0.018591813643428594,1739502661.7752223,22.099978923797607,1.8057527993770173 +1739502661.7975023,22.11997890472412,45.089700668006536,1739502661.797507,22.11997890472412,0.005333708707708773,1739502661.7975137,22.11997890472412,44.996061025612036,1739502661.7975214,22.11997890472412,50.33734518915617,1739502661.7975261,22.11997890472412,1.1375551547641336,1739502661.7975314,22.11997890472412,0.21250058563630184,1739502661.7975366,22.11997890472412,1.0344681638319468,1739502661.7975416,22.11997890472412,0.2748976386927798,1739502661.7975464,22.11997890472412,1.092770484935204,1739502661.7975516,22.11997890472412,0.0,1739502661.7975564,22.11997890472412,-0.7129823144418133,1739502661.7975616,22.11997890472412,0.018591813643428594,1739502661.7975667,22.11997890472412,1.8057527993770173 +1739502661.8151202,22.139978885650635,45.089700668006536,1739502661.8151238,22.139978885650635,0.005333708707708773,1739502661.8151283,22.139978885650635,44.996061025612036,1739502661.8151324,22.139978885650635,50.33734518915617,1739502661.8151345,22.139978885650635,1.1375551547641336,1739502661.8151367,22.139978885650635,0.21250058563630184,1739502661.8151388,22.139978885650635,1.0344681638319468,1739502661.815141,22.139978885650635,0.2748976386927798,1739502661.8151426,22.139978885650635,1.092770484935204,1739502661.815145,22.139978885650635,0.0,1739502661.815147,22.139978885650635,-0.7129823144418133,1739502661.8151495,22.139978885650635,0.018591813643428594,1739502661.8151517,22.139978885650635,1.8057527993770173 +1739502661.835243,22.15997886657715,45.089700668006536,1739502661.8352468,22.15997886657715,0.005333708707708773,1739502661.835251,22.15997886657715,44.996061025612036,1739502661.8352551,22.15997886657715,50.33734518915617,1739502661.835257,22.15997886657715,1.1375551547641336,1739502661.8352594,22.15997886657715,0.21250058563630184,1739502661.8352613,22.15997886657715,1.0344681638319468,1739502661.8352633,22.15997886657715,0.2748976386927798,1739502661.835265,22.15997886657715,1.092770484935204,1739502661.8352673,22.15997886657715,0.0,1739502661.8352692,22.15997886657715,-0.7129823144418133,1739502661.8352711,22.15997886657715,0.018591813643428594,1739502661.8352733,22.15997886657715,1.8057527993770173 +1739502661.855594,22.179978847503662,45.284881159392306,1739502661.8555973,22.179978847503662,0.00956748587000611,1739502661.8556013,22.179978847503662,45.03120621539297,1739502661.8556056,22.179978847503662,50.249917405419794,1739502661.8556075,22.179978847503662,1.0692227850817486,1739502661.8556101,22.179978847503662,0.21026880481745802,1739502661.8556118,22.179978847503662,0.9320084668004515,1739502661.855614,22.179978847503662,0.2769208534947852,1739502661.8556159,22.179978847503662,1.1861158278755555,1739502661.8556178,22.179978847503662,0.0,1739502661.85562,22.179978847503662,-0.4709328847101557,1739502661.8556218,22.179978847503662,0.025641794650124266,1739502661.8556237,22.179978847503662,1.7326892089706283 +1739502661.8750696,22.199978828430176,45.284881159392306,1739502661.8750734,22.199978828430176,0.00956748587000611,1739502661.875078,22.199978828430176,45.03120621539297,1739502661.875082,22.199978828430176,50.249917405419794,1739502661.8750844,22.199978828430176,1.0692227850817486,1739502661.8750868,22.199978828430176,0.21026880481745802,1739502661.875089,22.199978828430176,0.9320084668004515,1739502661.8750908,22.199978828430176,0.2769208534947852,1739502661.8750927,22.199978828430176,1.1861158278755555,1739502661.8750954,22.199978828430176,0.0,1739502661.8750973,22.199978828430176,-0.5465733810950728,1739502661.8750994,22.199978828430176,0.025641794650124266,1739502661.875101,22.199978828430176,1.7326892089706283 +1739502661.8952472,22.21997880935669,45.284881159392306,1739502661.89525,22.21997880935669,0.00956748587000611,1739502661.8952546,22.21997880935669,45.03120621539297,1739502661.8952584,22.21997880935669,50.249917405419794,1739502661.8952603,22.21997880935669,1.0692227850817486,1739502661.8952627,22.21997880935669,0.21026880481745802,1739502661.8952649,22.21997880935669,0.9320084668004515,1739502661.8952668,22.21997880935669,0.2769208534947852,1739502661.8952687,22.21997880935669,1.1861158278755555,1739502661.8952708,22.21997880935669,0.0,1739502661.8952727,22.21997880935669,-0.5465733810950728,1739502661.8952746,22.21997880935669,0.025641794650124266,1739502661.895277,22.21997880935669,1.7326892089706283 +1739502661.9150841,22.239978790283203,45.284881159392306,1739502661.9150884,22.239978790283203,0.00956748587000611,1739502661.915093,22.239978790283203,45.03120621539297,1739502661.9150968,22.239978790283203,50.249917405419794,1739502661.915099,22.239978790283203,1.0692227850817486,1739502661.9151013,22.239978790283203,0.21026880481745802,1739502661.9151034,22.239978790283203,0.9320084668004515,1739502661.9151056,22.239978790283203,0.2769208534947852,1739502661.9151073,22.239978790283203,1.1861158278755555,1739502661.9151099,22.239978790283203,0.0,1739502661.915112,22.239978790283203,-0.5465733810950728,1739502661.9151137,22.239978790283203,0.025641794650124266,1739502661.915116,22.239978790283203,1.7326892089706283 +1739502661.9352405,22.259978771209717,45.284881159392306,1739502661.9352443,22.259978771209717,0.00956748587000611,1739502661.9352486,22.259978771209717,45.03120621539297,1739502661.9352527,22.259978771209717,50.249917405419794,1739502661.9352546,22.259978771209717,1.0692227850817486,1739502661.9352572,22.259978771209717,0.21026880481745802,1739502661.935259,22.259978771209717,0.9320084668004515,1739502661.9352612,22.259978771209717,0.2769208534947852,1739502661.935263,22.259978771209717,1.1861158278755555,1739502661.9352653,22.259978771209717,0.0,1739502661.9352672,22.259978771209717,-0.5465733810950728,1739502661.9352694,22.259978771209717,0.025641794650124266,1739502661.9352713,22.259978771209717,1.7326892089706283 +1739502661.9552712,22.27997875213623,45.284881159392306,1739502661.9552748,22.27997875213623,0.00956748587000611,1739502661.9552789,22.27997875213623,45.03120621539297,1739502661.9552827,22.27997875213623,50.249917405419794,1739502661.9552848,22.27997875213623,1.0692227850817486,1739502661.955287,22.27997875213623,0.21026880481745802,1739502661.955289,22.27997875213623,0.9320084668004515,1739502661.9552908,22.27997875213623,0.2769208534947852,1739502661.9552932,22.27997875213623,1.1861158278755555,1739502661.9552956,22.27997875213623,0.0,1739502661.9552972,22.27997875213623,-0.5465733810950728,1739502661.9552994,22.27997875213623,0.025641794650124266,1739502661.9553013,22.27997875213623,1.7326892089706283 +1739502661.9751654,22.299978733062744,45.47254100391904,1739502661.9751692,22.299978733062744,0.015051414227924553,1739502661.9751742,22.299978733062744,45.276269616014545,1739502661.975178,22.299978733062744,50.35076731642279,1739502661.9751801,22.299978733062744,1.1485368952550068,1739502661.9751825,22.299978733062744,0.22830492644071762,1739502661.9751847,22.299978733062744,0.9682491651263272,1739502661.9751866,22.299978733062744,0.2955155657915696,1739502661.9751885,22.299978733062744,1.1522210179983938,1739502661.9751909,22.299978733062744,0.0,1739502661.9751925,22.299978733062744,-0.5109736734782911,1739502661.975195,22.299978733062744,0.033746324119567524,1739502661.9751966,22.299978733062744,1.6743196074009925 +1739502661.9952092,22.319978713989258,45.47254100391904,1739502661.9952126,22.319978713989258,0.015051414227924553,1739502661.9952166,22.319978713989258,45.276269616014545,1739502661.9952207,22.319978713989258,50.35076731642279,1739502661.9952228,22.319978713989258,1.1485368952550068,1739502661.9952252,22.319978713989258,0.22830492644071762,1739502661.995227,22.319978713989258,0.9682491651263272,1739502661.9952292,22.319978713989258,0.2955155657915696,1739502661.995231,22.319978713989258,1.1522210179983938,1739502661.9952333,22.319978713989258,0.0,1739502661.995235,22.319978713989258,-0.5220985894025987,1739502661.995237,22.319978713989258,0.033746324119567524,1739502661.9952393,22.319978713989258,1.6743196074009925 +1739502662.015116,22.33997869491577,45.47254100391904,1739502662.01512,22.33997869491577,0.015051414227924553,1739502662.0151246,22.33997869491577,45.276269616014545,1739502662.0151286,22.33997869491577,50.35076731642279,1739502662.0151303,22.33997869491577,1.1485368952550068,1739502662.0151331,22.33997869491577,0.22830492644071762,1739502662.0151353,22.33997869491577,0.9682491651263272,1739502662.0151372,22.33997869491577,0.2955155657915696,1739502662.015139,22.33997869491577,1.1522210179983938,1739502662.0151415,22.33997869491577,0.0,1739502662.0151434,22.33997869491577,-0.5220985894025987,1739502662.0151455,22.33997869491577,0.033746324119567524,1739502662.0151474,22.33997869491577,1.6743196074009925 +1739502662.0350666,22.359978675842285,45.47254100391904,1739502662.0350704,22.359978675842285,0.015051414227924553,1739502662.0350752,22.359978675842285,45.276269616014545,1739502662.0350792,22.359978675842285,50.35076731642279,1739502662.0350811,22.359978675842285,1.1485368952550068,1739502662.0350838,22.359978675842285,0.22830492644071762,1739502662.0350857,22.359978675842285,0.9682491651263272,1739502662.0350876,22.359978675842285,0.2955155657915696,1739502662.0350895,22.359978675842285,1.1522210179983938,1739502662.0350919,22.359978675842285,0.0,1739502662.0350938,22.359978675842285,-0.5220985894025987,1739502662.0350957,22.359978675842285,0.033746324119567524,1739502662.0350978,22.359978675842285,1.6743196074009925 +1739502662.0550206,22.3799786567688,45.47254100391904,1739502662.0550244,22.3799786567688,0.015051414227924553,1739502662.0550284,22.3799786567688,45.276269616014545,1739502662.0550323,22.3799786567688,50.35076731642279,1739502662.0550344,22.3799786567688,1.1485368952550068,1739502662.0550368,22.3799786567688,0.22830492644071762,1739502662.0550387,22.3799786567688,0.9682491651263272,1739502662.0550406,22.3799786567688,0.2955155657915696,1739502662.0550423,22.3799786567688,1.1522210179983938,1739502662.0550447,22.3799786567688,0.0,1739502662.0550466,22.3799786567688,-0.5220985894025987,1739502662.0550487,22.3799786567688,0.033746324119567524,1739502662.0550508,22.3799786567688,1.6743196074009925 +1739502662.075185,22.399978637695312,45.65372096552338,1739502662.0751894,22.399978637695312,0.021904041544273056,1739502662.0751944,22.399978637695312,45.45558614884508,1739502662.0751987,22.399978637695312,50.4010627637355,1739502662.075201,22.399978637695312,1.1896877157835926,1739502662.0752034,22.399978637695312,0.24119803268575019,1739502662.0752056,22.399978637695312,0.962968209659161,1739502662.0752077,22.399978637695312,0.3083362539433513,1739502662.0752096,22.399978637695312,1.1570991775876158,1739502662.0752118,22.399978637695312,0.0,1739502662.075214,22.399978637695312,-0.4318526942993438,1739502662.075216,22.399978637695312,0.04292973668914304,1739502662.0752184,22.399978637695312,1.6171537325973075 +1739502662.0952218,22.419978618621826,45.65372096552338,1739502662.095225,22.419978618621826,0.021904041544273056,1739502662.0952294,22.419978618621826,45.45558614884508,1739502662.0952332,22.419978618621826,50.4010627637355,1739502662.0952353,22.419978618621826,1.1896877157835926,1739502662.095238,22.419978618621826,0.24119803268575019,1739502662.0952399,22.419978618621826,0.962968209659161,1739502662.0952423,22.419978618621826,0.3083362539433513,1739502662.0952442,22.419978618621826,1.1570991775876158,1739502662.0952463,22.419978618621826,0.0,1739502662.0952482,22.419978618621826,-0.4600545550096917,1739502662.0952504,22.419978618621826,0.04292973668914304,1739502662.0952525,22.419978618621826,1.6171537325973075 +1739502662.1151288,22.43997859954834,45.65372096552338,1739502662.1151326,22.43997859954834,0.021904041544273056,1739502662.1151369,22.43997859954834,45.45558614884508,1739502662.1151407,22.43997859954834,50.4010627637355,1739502662.1151426,22.43997859954834,1.1896877157835926,1739502662.1151454,22.43997859954834,0.24119803268575019,1739502662.1151476,22.43997859954834,0.962968209659161,1739502662.1151493,22.43997859954834,0.3083362539433513,1739502662.1151514,22.43997859954834,1.1570991775876158,1739502662.1151536,22.43997859954834,0.0,1739502662.1151557,22.43997859954834,-0.4600545550096917,1739502662.1151578,22.43997859954834,0.04292973668914304,1739502662.1151597,22.43997859954834,1.6171537325973075 +1739502662.135073,22.459978580474854,45.65372096552338,1739502662.1350765,22.459978580474854,0.021904041544273056,1739502662.1350813,22.459978580474854,45.45558614884508,1739502662.1350853,22.459978580474854,50.4010627637355,1739502662.1350873,22.459978580474854,1.1896877157835926,1739502662.1350899,22.459978580474854,0.24119803268575019,1739502662.135092,22.459978580474854,0.962968209659161,1739502662.135094,22.459978580474854,0.3083362539433513,1739502662.1350958,22.459978580474854,1.1570991775876158,1739502662.1350982,22.459978580474854,0.0,1739502662.1351001,22.459978580474854,-0.4600545550096917,1739502662.1351025,22.459978580474854,0.04292973668914304,1739502662.1351042,22.459978580474854,1.6171537325973075 +1739502662.1552455,22.479978561401367,45.65372096552338,1739502662.155249,22.479978561401367,0.021904041544273056,1739502662.1552534,22.479978561401367,45.45558614884508,1739502662.1552577,22.479978561401367,50.4010627637355,1739502662.1552596,22.479978561401367,1.1896877157835926,1739502662.155262,22.479978561401367,0.24119803268575019,1739502662.155264,22.479978561401367,0.962968209659161,1739502662.155266,22.479978561401367,0.3083362539433513,1739502662.155268,22.479978561401367,1.1570991775876158,1739502662.1552699,22.479978561401367,0.0,1739502662.1552718,22.479978561401367,-0.4600545550096917,1739502662.1552737,22.479978561401367,0.04292973668914304,1739502662.1552758,22.479978561401367,1.6171537325973075 +1739502662.1749668,22.49997854232788,45.65372096552338,1739502662.1749709,22.49997854232788,0.021904041544273056,1739502662.1749756,22.49997854232788,45.45558614884508,1739502662.1749797,22.49997854232788,50.4010627637355,1739502662.1749814,22.49997854232788,1.1896877157835926,1739502662.174984,22.49997854232788,0.24119803268575019,1739502662.174986,22.49997854232788,0.962968209659161,1739502662.174988,22.49997854232788,0.3083362539433513,1739502662.17499,22.49997854232788,1.1570991775876158,1739502662.174992,22.49997854232788,0.0,1739502662.1749942,22.49997854232788,-0.4600545550096917,1739502662.1749964,22.49997854232788,0.04292973668914304,1739502662.1749988,22.49997854232788,1.6171537325973075 +1739502662.1955833,22.519978523254395,45.82893869301794,1739502662.1955864,22.519978523254395,0.030230827506923852,1739502662.1955907,22.519978523254395,45.45892361245344,1739502662.1955948,22.519978523254395,50.32649883352763,1739502662.1955965,22.519978523254395,1.1286808637953332,1739502662.195599,22.519978523254395,0.23954303762279347,1739502662.1956012,22.519978523254395,0.8576643354783533,1739502662.1956031,22.519978523254395,0.30623180147540446,1739502662.195605,22.519978523254395,1.2588004749243802,1739502662.1956072,22.519978523254395,0.0,1739502662.1956093,22.519978523254395,-0.2396317980697083,1739502662.1956115,22.519978523254395,0.05321632636998234,1739502662.1956134,22.519978523254395,1.5673144297004946 +1739502662.2151048,22.539978504180908,45.82893869301794,1739502662.2151089,22.539978504180908,0.030230827506923852,1739502662.2151132,22.539978504180908,45.45892361245344,1739502662.215117,22.539978504180908,50.32649883352763,1739502662.2151191,22.539978504180908,1.1286808637953332,1739502662.2151217,22.539978504180908,0.23954303762279347,1739502662.2151234,22.539978504180908,0.8576643354783533,1739502662.2151256,22.539978504180908,0.30623180147540446,1739502662.2151275,22.539978504180908,1.2588004749243802,1739502662.2151296,22.539978504180908,0.0,1739502662.215132,22.539978504180908,-0.30851395477611443,1739502662.215134,22.539978504180908,0.05321632636998234,1739502662.215136,22.539978504180908,1.5673144297004946 +1739502662.234951,22.559978485107422,45.82893869301794,1739502662.2349548,22.559978485107422,0.030230827506923852,1739502662.2349594,22.559978485107422,45.45892361245344,1739502662.2349632,22.559978485107422,50.32649883352763,1739502662.2349653,22.559978485107422,1.1286808637953332,1739502662.2349677,22.559978485107422,0.23954303762279347,1739502662.2349699,22.559978485107422,0.8576643354783533,1739502662.234972,22.559978485107422,0.30623180147540446,1739502662.2349737,22.559978485107422,1.2588004749243802,1739502662.234976,22.559978485107422,0.0,1739502662.2349777,22.559978485107422,-0.30851395477611443,1739502662.2349806,22.559978485107422,0.05321632636998234,1739502662.2349827,22.559978485107422,1.5673144297004946 +1739502662.2553582,22.579978466033936,45.82893869301794,1739502662.2553616,22.579978466033936,0.030230827506923852,1739502662.2553658,22.579978466033936,45.45892361245344,1739502662.2553697,22.579978466033936,50.32649883352763,1739502662.2553718,22.579978466033936,1.1286808637953332,1739502662.2553742,22.579978466033936,0.23954303762279347,1739502662.255376,22.579978466033936,0.8576643354783533,1739502662.2553782,22.579978466033936,0.30623180147540446,1739502662.25538,22.579978466033936,1.2588004749243802,1739502662.2553823,22.579978466033936,0.0,1739502662.2553842,22.579978466033936,-0.30851395477611443,1739502662.2553864,22.579978466033936,0.05321632636998234,1739502662.2553885,22.579978466033936,1.5673144297004946 +1739502662.275106,22.59997844696045,45.82893869301794,1739502662.2751095,22.59997844696045,0.030230827506923852,1739502662.275114,22.59997844696045,45.45892361245344,1739502662.2751179,22.59997844696045,50.32649883352763,1739502662.2751198,22.59997844696045,1.1286808637953332,1739502662.2751226,22.59997844696045,0.23954303762279347,1739502662.275125,22.59997844696045,0.8576643354783533,1739502662.2751267,22.59997844696045,0.30623180147540446,1739502662.2751288,22.59997844696045,1.2588004749243802,1739502662.2751312,22.59997844696045,0.0,1739502662.275133,22.59997844696045,-0.30851395477611443,1739502662.275135,22.59997844696045,0.05321632636998234,1739502662.275137,22.59997844696045,1.5673144297004946 +1739502662.29801,22.619978427886963,45.99923811296317,1739502662.298015,22.619978427886963,0.04016848539633333,1739502662.2980218,22.619978427886963,45.46216923909029,1739502662.2980297,22.619978427886963,50.274418506535156,1739502662.298034,22.619978427886963,1.0878902906934533,1739502662.2980394,22.619978427886963,0.24033404625904728,1739502662.2980444,22.619978427886963,0.7694884271930014,1739502662.2980492,22.619978427886963,0.3039724977960144,1739502662.2980545,22.619978427886963,1.3508040261876184,1739502662.2980595,22.619978427886963,0.0,1739502662.2980645,22.619978427886963,-0.1242096819881911,1739502662.2980695,22.619978427886963,0.06461462367847921,1739502662.2980752,22.619978427886963,1.5326088311843409 +1739502662.3143547,22.639978408813477,45.99923811296317,1739502662.3143573,22.639978408813477,0.04016848539633333,1739502662.314361,22.639978408813477,45.46216923909029,1739502662.314364,22.639978408813477,50.274418506535156,1739502662.3143654,22.639978408813477,1.0878902906934533,1739502662.3143675,22.639978408813477,0.24033404625904728,1739502662.3143687,22.639978408813477,0.7694884271930014,1739502662.3143702,22.639978408813477,0.3039724977960144,1739502662.3143713,22.639978408813477,1.3508040261876184,1739502662.3143735,22.639978408813477,0.0,1739502662.3143747,22.639978408813477,-0.18180480499672247,1739502662.314376,22.639978408813477,0.06461462367847921,1739502662.3143778,22.639978408813477,1.5326088311843409 +1739502662.334141,22.65997838973999,45.99923811296317,1739502662.334143,22.65997838973999,0.04016848539633333,1739502662.3341458,22.65997838973999,45.46216923909029,1739502662.3341484,22.65997838973999,50.274418506535156,1739502662.3341496,22.65997838973999,1.0878902906934533,1739502662.3341515,22.65997838973999,0.24033404625904728,1739502662.3341527,22.65997838973999,0.7694884271930014,1739502662.334154,22.65997838973999,0.3039724977960144,1739502662.3341553,22.65997838973999,1.3508040261876184,1739502662.3341568,22.65997838973999,0.0,1739502662.3341582,22.65997838973999,-0.18180480499672247,1739502662.3341594,22.65997838973999,0.06461462367847921,1739502662.3341606,22.65997838973999,1.5326088311843409 +1739502662.3543725,22.679978370666504,45.99923811296317,1739502662.3543751,22.679978370666504,0.04016848539633333,1739502662.3543785,22.679978370666504,45.46216923909029,1739502662.3543813,22.679978370666504,50.274418506535156,1739502662.3543828,22.679978370666504,1.0878902906934533,1739502662.3543844,22.679978370666504,0.24033404625904728,1739502662.3543859,22.679978370666504,0.7694884271930014,1739502662.3543878,22.679978370666504,0.3039724977960144,1739502662.3543887,22.679978370666504,1.3508040261876184,1739502662.3543904,22.679978370666504,0.0,1739502662.3543916,22.679978370666504,-0.18180480499672247,1739502662.3543928,22.679978370666504,0.06461462367847921,1739502662.3543947,22.679978370666504,1.5326088311843409 +1739502662.3741333,22.699978351593018,45.99923811296317,1739502662.3741355,22.699978351593018,0.04016848539633333,1739502662.374138,22.699978351593018,45.46216923909029,1739502662.3741407,22.699978351593018,50.274418506535156,1739502662.374142,22.699978351593018,1.0878902906934533,1739502662.3741436,22.699978351593018,0.24033404625904728,1739502662.3741448,22.699978351593018,0.7694884271930014,1739502662.374146,22.699978351593018,0.3039724977960144,1739502662.3741477,22.699978351593018,1.3508040261876184,1739502662.374149,22.699978351593018,0.0,1739502662.3741505,22.699978351593018,-0.18180480499672247,1739502662.3741517,22.699978351593018,0.06461462367847921,1739502662.374153,22.699978351593018,1.5326088311843409 +1739502662.3944144,22.71997833251953,45.99923811296317,1739502662.3944168,22.71997833251953,0.04016848539633333,1739502662.39442,22.71997833251953,45.46216923909029,1739502662.3944228,22.71997833251953,50.274418506535156,1739502662.394424,22.71997833251953,1.0878902906934533,1739502662.3944259,22.71997833251953,0.24033404625904728,1739502662.394427,22.71997833251953,0.7694884271930014,1739502662.3944287,22.71997833251953,0.3039724977960144,1739502662.39443,22.71997833251953,1.3508040261876184,1739502662.3944316,22.71997833251953,0.0,1739502662.3944333,22.71997833251953,-0.18180480499672247,1739502662.394435,22.71997833251953,0.06461462367847921,1739502662.3944361,22.71997833251953,1.5326088311843409 +1739502662.414501,22.739978313446045,46.16652527096918,1739502662.4145033,22.739978313446045,0.05189340258527064,1739502662.4145067,22.739978313446045,45.46535942000959,1739502662.41451,22.739978313446045,50.247087497011364,1739502662.4145117,22.739978313446045,1.0670666643896112,1739502662.4145136,22.739978313446045,0.2438326351916835,1739502662.4145153,22.739978313446045,0.700625379112181,1739502662.4145167,22.739978313446045,0.30327972328463926,1739502662.4145184,22.739978313446045,1.4273083938772477,1739502662.41452,22.739978313446045,0.0,1739502662.4145217,22.739978313446045,-0.043216483219311756,1739502662.4145234,22.739978313446045,0.07643251245251903,1739502662.4145253,22.739978313446045,1.5138337560475141 +1739502662.436121,22.75997829437256,46.16652527096918,1739502662.436126,22.75997829437256,0.05189340258527064,1739502662.4361308,22.75997829437256,45.46535942000959,1739502662.4361355,22.75997829437256,50.247087497011364,1739502662.436138,22.75997829437256,1.0670666643896112,1739502662.4361408,22.75997829437256,0.2438326351916835,1739502662.4361436,22.75997829437256,0.700625379112181,1739502662.436146,22.75997829437256,0.30327972328463926,1739502662.436148,22.75997829437256,1.4273083938772477,1739502662.4361513,22.75997829437256,0.0,1739502662.4361537,22.75997829437256,-0.0865253621702664,1739502662.4361567,22.75997829437256,0.07643251245251903,1739502662.436159,22.75997829437256,1.5138337560475141 +1739502662.4554622,22.779978275299072,46.16652527096918,1739502662.455469,22.779978275299072,0.05189340258527064,1739502662.455476,22.779978275299072,45.46535942000959,1739502662.4554818,22.779978275299072,50.247087497011364,1739502662.455485,22.779978275299072,1.0670666643896112,1739502662.4554896,22.779978275299072,0.2438326351916835,1739502662.4554937,22.779978275299072,0.700625379112181,1739502662.4554965,22.779978275299072,0.30327972328463926,1739502662.4555137,22.779978275299072,1.4273083938772477,1739502662.4555178,22.779978275299072,0.0,1739502662.4555213,22.779978275299072,-0.0865253621702664,1739502662.4555254,22.779978275299072,0.07643251245251903,1739502662.455528,22.779978275299072,1.5138337560475141 +1739502662.4753146,22.799978256225586,46.16652527096918,1739502662.4753182,22.799978256225586,0.05189340258527064,1739502662.4753232,22.799978256225586,45.46535942000959,1739502662.4753277,22.799978256225586,50.247087497011364,1739502662.47533,22.799978256225586,1.0670666643896112,1739502662.475333,22.799978256225586,0.2438326351916835,1739502662.475335,22.799978256225586,0.700625379112181,1739502662.4753373,22.799978256225586,0.30327972328463926,1739502662.4753392,22.799978256225586,1.4273083938772477,1739502662.475342,22.799978256225586,0.0,1739502662.4753444,22.799978256225586,-0.0865253621702664,1739502662.4753468,22.799978256225586,0.07643251245251903,1739502662.475349,22.799978256225586,1.5138337560475141 +1739502662.4956381,22.8199782371521,46.16652527096918,1739502662.4956417,22.8199782371521,0.05189340258527064,1739502662.4956467,22.8199782371521,45.46535942000959,1739502662.4956512,22.8199782371521,50.247087497011364,1739502662.4956536,22.8199782371521,1.0670666643896112,1739502662.4956565,22.8199782371521,0.2438326351916835,1739502662.4956586,22.8199782371521,0.700625379112181,1739502662.495661,22.8199782371521,0.30327972328463926,1739502662.4956632,22.8199782371521,1.4273083938772477,1739502662.4956656,22.8199782371521,0.0,1739502662.495668,22.8199782371521,-0.0865253621702664,1739502662.4956703,22.8199782371521,0.07643251245251903,1739502662.4956725,22.8199782371521,1.5138337560475141 +1739502662.51545,22.839978218078613,46.33199612346015,1739502662.5154533,22.839978218078613,0.06545892752239357,1739502662.5154576,22.839978218078613,45.468516931731855,1739502662.5154614,22.839978218078613,50.23426444606662,1739502662.515463,22.839978218078613,1.0575952832491957,1739502662.5154657,22.839978218078613,0.24897094739996908,1739502662.5154674,22.839978218078613,0.6443455068588919,1739502662.5154696,22.839978218078613,0.3041939468792044,1739502662.5154712,22.839978218078613,1.4930400246266564,1739502662.5154734,22.839978218078613,0.0,1739502662.5154753,22.839978218078613,0.022974657585347204,1739502662.515477,22.839978218078613,0.08825040122655885,1739502662.515479,22.839978218078613,1.504284145650518 +1739502662.534602,22.859978199005127,46.33199612346015,1739502662.534605,22.859978199005127,0.06545892752239357,1739502662.5346088,22.859978199005127,45.468516931731855,1739502662.534612,22.859978199005127,50.23426444606662,1739502662.5346138,22.859978199005127,1.0575952832491957,1739502662.5346158,22.859978199005127,0.24897094739996908,1739502662.5346177,22.859978199005127,0.6443455068588919,1739502662.534619,22.859978199005127,0.3041939468792044,1739502662.5346208,22.859978199005127,1.4930400246266564,1739502662.5346224,22.859978199005127,0.0,1739502662.5346243,22.859978199005127,-0.01124412102386163,1739502662.5346258,22.859978199005127,0.08825040122655885,1739502662.5346277,22.859978199005127,1.504284145650518 +1739502662.5547173,22.87997817993164,46.33199612346015,1739502662.5547202,22.87997817993164,0.06545892752239357,1739502662.5547237,22.87997817993164,45.468516931731855,1739502662.554727,22.87997817993164,50.23426444606662,1739502662.5547287,22.87997817993164,1.0575952832491957,1739502662.5547307,22.87997817993164,0.24897094739996908,1739502662.5547323,22.87997817993164,0.6443455068588919,1739502662.554734,22.87997817993164,0.3041939468792044,1739502662.5547357,22.87997817993164,1.4930400246266564,1739502662.5547373,22.87997817993164,0.0,1739502662.554739,22.87997817993164,-0.01124412102386163,1739502662.5547407,22.87997817993164,0.08825040122655885,1739502662.5547423,22.87997817993164,1.504284145650518 +1739502662.574559,22.899978160858154,46.33199612346015,1739502662.5745618,22.899978160858154,0.06545892752239357,1739502662.5745654,22.899978160858154,45.468516931731855,1739502662.5745687,22.899978160858154,50.23426444606662,1739502662.5745704,22.899978160858154,1.0575952832491957,1739502662.5745726,22.899978160858154,0.24897094739996908,1739502662.5745742,22.899978160858154,0.6443455068588919,1739502662.5745761,22.899978160858154,0.3041939468792044,1739502662.5745776,22.899978160858154,1.4930400246266564,1739502662.5745795,22.899978160858154,0.0,1739502662.574581,22.899978160858154,-0.01124412102386163,1739502662.5745828,22.899978160858154,0.08825040122655885,1739502662.5745842,22.899978160858154,1.504284145650518 +1739502662.594583,22.919978141784668,46.33199612346015,1739502662.594586,22.919978141784668,0.06545892752239357,1739502662.5945895,22.919978141784668,45.468516931731855,1739502662.594593,22.919978141784668,50.23426444606662,1739502662.5945945,22.919978141784668,1.0575952832491957,1739502662.5945966,22.919978141784668,0.24897094739996908,1739502662.5945983,22.919978141784668,0.6443455068588919,1739502662.5946,22.919978141784668,0.3041939468792044,1739502662.5946014,22.919978141784668,1.4930400246266564,1739502662.5946035,22.919978141784668,0.0,1739502662.594605,22.919978141784668,-0.01124412102386163,1739502662.5946069,22.919978141784668,0.08825040122655885,1739502662.5946085,22.919978141784668,1.504284145650518 +1739502662.6145618,22.93997812271118,46.33199612346015,1739502662.6145647,22.93997812271118,0.06545892752239357,1739502662.6145682,22.93997812271118,45.468516931731855,1739502662.6145713,22.93997812271118,50.23426444606662,1739502662.614573,22.93997812271118,1.0575952832491957,1739502662.6145751,22.93997812271118,0.24897094739996908,1739502662.6145766,22.93997812271118,0.6443455068588919,1739502662.6145785,22.93997812271118,0.3041939468792044,1739502662.61458,22.93997812271118,1.4930400246266564,1739502662.614582,22.93997812271118,0.0,1739502662.6145835,22.93997812271118,-0.01124412102386163,1739502662.6145854,22.93997812271118,0.08825040122655885,1739502662.614587,22.93997812271118,1.504284145650518 +1739502662.6347013,22.959978103637695,46.49674486524493,1739502662.6347044,22.959978103637695,0.08092820346907814,1739502662.634708,22.959978103637695,45.73343089244336,1739502662.634711,22.959978103637695,50.440281192072675,1739502662.634713,22.959978103637695,1.222281737857003,1739502662.6347148,22.959978103637695,0.2817259013725689,1739502662.6347165,22.959978103637695,0.7416790738441386,1739502662.6347182,22.959978103637695,0.3365447117089435,1739502662.6347194,22.959978103637695,1.3811927988081896,1739502662.6347215,22.959978103637695,0.0,1739502662.6347232,22.959978103637695,-0.1731270779889052,1739502662.6347249,22.959978103637695,0.10006829000059866,1739502662.6347268,22.959978103637695,1.5037314195771414 +1739502662.6550343,22.97997808456421,46.49674486524493,1739502662.6550376,22.97997808456421,0.08092820346907814,1739502662.6550424,22.97997808456421,45.73343089244336,1739502662.6550457,22.97997808456421,50.440281192072675,1739502662.6550474,22.97997808456421,1.222281737857003,1739502662.6550496,22.97997808456421,0.2817259013725689,1739502662.6550512,22.97997808456421,0.7416790738441386,1739502662.6550531,22.97997808456421,0.3365447117089435,1739502662.6550546,22.97997808456421,1.3811927988081896,1739502662.6550567,22.97997808456421,0.0,1739502662.6550581,22.97997808456421,-0.12253862076895183,1739502662.65506,22.97997808456421,0.10006829000059866,1739502662.6550615,22.97997808456421,1.5037314195771414 +1739502662.6745317,22.999978065490723,46.49674486524493,1739502662.6745343,22.999978065490723,0.08092820346907814,1739502662.674538,22.999978065490723,45.73343089244336,1739502662.6745412,22.999978065490723,50.440281192072675,1739502662.674543,22.999978065490723,1.222281737857003,1739502662.6745448,22.999978065490723,0.2817259013725689,1739502662.6745465,22.999978065490723,0.7416790738441386,1739502662.6745481,22.999978065490723,0.3365447117089435,1739502662.6745498,22.999978065490723,1.3811927988081896,1739502662.6745515,22.999978065490723,0.0,1739502662.6745534,22.999978065490723,-0.12253862076895183,1739502662.674555,22.999978065490723,0.10006829000059866,1739502662.674557,22.999978065490723,1.5037314195771414 +1739502662.694919,23.019978046417236,46.49674486524493,1739502662.6949224,23.019978046417236,0.08092820346907814,1739502662.6949265,23.019978046417236,45.73343089244336,1739502662.6949298,23.019978046417236,50.440281192072675,1739502662.6949317,23.019978046417236,1.222281737857003,1739502662.6949337,23.019978046417236,0.2817259013725689,1739502662.6949353,23.019978046417236,0.7416790738441386,1739502662.694937,23.019978046417236,0.3365447117089435,1739502662.6949387,23.019978046417236,1.3811927988081896,1739502662.6949406,23.019978046417236,0.0,1739502662.6949422,23.019978046417236,-0.12253862076895183,1739502662.694944,23.019978046417236,0.10006829000059866,1739502662.6949458,23.019978046417236,1.5037314195771414 +1739502662.7149756,23.03997802734375,46.49674486524493,1739502662.714979,23.03997802734375,0.08092820346907814,1739502662.7149825,23.03997802734375,45.73343089244336,1739502662.7149854,23.03997802734375,50.440281192072675,1739502662.7149873,23.03997802734375,1.222281737857003,1739502662.7149897,23.03997802734375,0.2817259013725689,1739502662.714991,23.03997802734375,0.7416790738441386,1739502662.714993,23.03997802734375,0.3365447117089435,1739502662.7149944,23.03997802734375,1.3811927988081896,1739502662.7149966,23.03997802734375,0.0,1739502662.714998,23.03997802734375,-0.12253862076895183,1739502662.715,23.03997802734375,0.10006829000059866,1739502662.7150016,23.03997802734375,1.5037314195771414 +1739502662.734599,23.059978008270264,46.66059047426573,1739502662.734602,23.059978008270264,0.09828417760622976,1739502662.7346053,23.059978008270264,45.926574578027136,1739502662.7346087,23.059978008270264,50.56399651153039,1739502662.73461,23.059978008270264,1.3336876743281814,1739502662.7346122,23.059978008270264,0.3065191268704497,1739502662.7346137,23.059978008270264,0.7901171296422699,1739502662.7346156,23.059978008270264,0.36025621886615283,1739502662.734617,23.059978008270264,1.3286946952359155,1739502662.734619,23.059978008270264,0.0,1739502662.7346203,23.059978008270264,-0.17951643885724497,1739502662.7346222,23.059978008270264,0.11231812695984851,1739502662.734624,23.059978008270264,1.490405554266321 +1739502662.7547662,23.079977989196777,46.66059047426573,1739502662.7547703,23.079977989196777,0.09828417760622976,1739502662.7547739,23.079977989196777,45.926574578027136,1739502662.7547774,23.079977989196777,50.56399651153039,1739502662.754779,23.079977989196777,1.3336876743281814,1739502662.7547812,23.079977989196777,0.3065191268704497,1739502662.7547834,23.079977989196777,0.7901171296422699,1739502662.754785,23.079977989196777,0.36025621886615283,1739502662.7547865,23.079977989196777,1.3286946952359155,1739502662.7547886,23.079977989196777,0.0,1739502662.75479,23.079977989196777,-0.1617108590304055,1739502662.7547922,23.079977989196777,0.11231812695984851,1739502662.754794,23.079977989196777,1.490405554266321 +1739502662.7746923,23.09997797012329,46.66059047426573,1739502662.7746956,23.09997797012329,0.09828417760622976,1739502662.7746992,23.09997797012329,45.926574578027136,1739502662.7747025,23.09997797012329,50.56399651153039,1739502662.7747042,23.09997797012329,1.3336876743281814,1739502662.7747064,23.09997797012329,0.3065191268704497,1739502662.7747083,23.09997797012329,0.7901171296422699,1739502662.7747097,23.09997797012329,0.36025621886615283,1739502662.7747116,23.09997797012329,1.3286946952359155,1739502662.7747133,23.09997797012329,0.0,1739502662.7747152,23.09997797012329,-0.1617108590304055,1739502662.7747169,23.09997797012329,0.11231812695984851,1739502662.7747185,23.09997797012329,1.490405554266321 +1739502662.7945166,23.119977951049805,46.66059047426573,1739502662.794519,23.119977951049805,0.09828417760622976,1739502662.7945223,23.119977951049805,45.926574578027136,1739502662.7945256,23.119977951049805,50.56399651153039,1739502662.7945275,23.119977951049805,1.3336876743281814,1739502662.7945292,23.119977951049805,0.3065191268704497,1739502662.7945309,23.119977951049805,0.7901171296422699,1739502662.7945323,23.119977951049805,0.36025621886615283,1739502662.794534,23.119977951049805,1.3286946952359155,1739502662.7945359,23.119977951049805,0.0,1739502662.7945375,23.119977951049805,-0.1617108590304055,1739502662.794539,23.119977951049805,0.11231812695984851,1739502662.794541,23.119977951049805,1.490405554266321 +1739502662.8145611,23.13997793197632,46.66059047426573,1739502662.814564,23.13997793197632,0.09828417760622976,1739502662.8145676,23.13997793197632,45.926574578027136,1739502662.814571,23.13997793197632,50.56399651153039,1739502662.8145726,23.13997793197632,1.3336876743281814,1739502662.8145745,23.13997793197632,0.3065191268704497,1739502662.8145764,23.13997793197632,0.7901171296422699,1739502662.8145778,23.13997793197632,0.36025621886615283,1739502662.8145795,23.13997793197632,1.3286946952359155,1739502662.8145814,23.13997793197632,0.0,1739502662.814583,23.13997793197632,-0.1617108590304055,1739502662.8145847,23.13997793197632,0.11231812695984851,1739502662.8145866,23.13997793197632,1.490405554266321 +1739502662.8345685,23.159977912902832,46.66059047426573,1739502662.8345714,23.159977912902832,0.09828417760622976,1739502662.834575,23.159977912902832,45.926574578027136,1739502662.834578,23.159977912902832,50.56399651153039,1739502662.8345797,23.159977912902832,1.3336876743281814,1739502662.8345819,23.159977912902832,0.3065191268704497,1739502662.8345833,23.159977912902832,0.7901171296422699,1739502662.8345847,23.159977912902832,0.36025621886615283,1739502662.8345864,23.159977912902832,1.3286946952359155,1739502662.834588,23.159977912902832,0.0,1739502662.8345897,23.159977912902832,-0.1617108590304055,1739502662.8345912,23.159977912902832,0.11231812695984851,1739502662.834593,23.159977912902832,1.490405554266321 +1739502662.8549535,23.179977893829346,46.82247335614242,1739502662.8549569,23.179977893829346,0.11752572921932991,1739502662.8549604,23.179977893829346,46.828169778250434,1739502662.854964,23.179977893829346,51.126614119125215,1739502662.8549657,23.179977893829346,1.9883207864899046,1739502662.8549678,23.179977893829346,0.4100158625708444,1739502662.8549695,23.179977893829346,1.3162525316660152,1739502662.8549714,23.179977893829346,0.4554285996082476,1739502662.8549728,23.179977893829346,0.8722220059837461,1739502662.854975,23.179977893829346,0.0,1739502662.8549764,23.179977893829346,-0.7993863655654471,1739502662.8549783,23.179977893829346,0.1257389312373576,1739502662.8549798,23.179977893829346,1.4723346451029562 +1739502662.874565,23.19997787475586,46.82247335614242,1739502662.8745677,23.19997787475586,0.11752572921932991,1739502662.874571,23.19997787475586,46.828169778250434,1739502662.8745744,23.19997787475586,51.126614119125215,1739502662.8745759,23.19997787475586,1.9883207864899046,1739502662.874578,23.19997787475586,0.4100158625708444,1739502662.8745797,23.19997787475586,1.3162525316660152,1739502662.8745813,23.19997787475586,0.4554285996082476,1739502662.874583,23.19997787475586,0.8722220059837461,1739502662.874585,23.19997787475586,0.0,1739502662.8745863,23.19997787475586,-0.6001126391192101,1739502662.8745883,23.19997787475586,0.1257389312373576,1739502662.87459,23.19997787475586,1.4723346451029562 +1739502662.8949766,23.219977855682373,46.82247335614242,1739502662.8949795,23.219977855682373,0.11752572921932991,1739502662.8949835,23.219977855682373,46.828169778250434,1739502662.894987,23.219977855682373,51.126614119125215,1739502662.8949885,23.219977855682373,1.9883207864899046,1739502662.8949912,23.219977855682373,0.4100158625708444,1739502662.8949926,23.219977855682373,1.3162525316660152,1739502662.8949945,23.219977855682373,0.4554285996082476,1739502662.894996,23.219977855682373,0.8722220059837461,1739502662.894998,23.219977855682373,0.0,1739502662.8949997,23.219977855682373,-0.6001126391192101,1739502662.8950016,23.219977855682373,0.1257389312373576,1739502662.8950036,23.219977855682373,1.4723346451029562 +1739502662.9146614,23.239977836608887,46.82247335614242,1739502662.9146645,23.239977836608887,0.11752572921932991,1739502662.914668,23.239977836608887,46.828169778250434,1739502662.9146714,23.239977836608887,51.126614119125215,1739502662.914673,23.239977836608887,1.9883207864899046,1739502662.9146752,23.239977836608887,0.4100158625708444,1739502662.914677,23.239977836608887,1.3162525316660152,1739502662.9146786,23.239977836608887,0.4554285996082476,1739502662.91468,23.239977836608887,0.8722220059837461,1739502662.9146821,23.239977836608887,0.0,1739502662.9146836,23.239977836608887,-0.6001126391192101,1739502662.9146855,23.239977836608887,0.1257389312373576,1739502662.9146872,23.239977836608887,1.4723346451029562 +1739502662.9351103,23.2599778175354,46.82247335614242,1739502662.9351134,23.2599778175354,0.11752572921932991,1739502662.935117,23.2599778175354,46.828169778250434,1739502662.9351203,23.2599778175354,51.126614119125215,1739502662.935122,23.2599778175354,1.9883207864899046,1739502662.935124,23.2599778175354,0.4100158625708444,1739502662.9351256,23.2599778175354,1.3162525316660152,1739502662.935127,23.2599778175354,0.4554285996082476,1739502662.9351287,23.2599778175354,0.8722220059837461,1739502662.9351306,23.2599778175354,0.0,1739502662.9351323,23.2599778175354,-0.6001126391192101,1739502662.9351337,23.2599778175354,0.1257389312373576,1739502662.9351356,23.2599778175354,1.4723346451029562 +1739502662.9548073,23.279977798461914,46.979850334782334,1739502662.9548109,23.279977798461914,0.13845943442215436,1739502662.9548142,23.279977798461914,46.92416596208705,1739502662.9548175,23.279977798461914,51.10711779446093,1739502662.9548194,23.279977798461914,1.9596178640674853,1739502662.9548216,23.279977798461914,0.4155539811479867,1739502662.9548233,23.279977798461914,1.2256561290723575,1739502662.954825,23.279977798461914,0.4589219248958546,1739502662.9548268,23.279977798461914,0.9377853713183676,1739502662.9548285,23.279977798461914,0.0,1739502662.9548302,23.279977798461914,-0.409697233202136,1739502662.9548318,23.279977798461914,0.14040364357366894,1739502662.954834,23.279977798461914,1.4069874578840114 +1739502662.9745932,23.299977779388428,46.979850334782334,1739502662.9745965,23.299977779388428,0.13845943442215436,1739502662.9745998,23.299977779388428,46.92416596208705,1739502662.9746032,23.299977779388428,51.10711779446093,1739502662.974605,23.299977779388428,1.9596178640674853,1739502662.9746068,23.299977779388428,0.4155539811479867,1739502662.9746087,23.299977779388428,1.2256561290723575,1739502662.97461,23.299977779388428,0.4589219248958546,1739502662.974612,23.299977779388428,0.9377853713183676,1739502662.9746137,23.299977779388428,0.0,1739502662.9746156,23.299977779388428,-0.4692020865656438,1739502662.9746172,23.299977779388428,0.14040364357366894,1739502662.974619,23.299977779388428,1.4069874578840114 +1739502662.9948182,23.31997776031494,46.979850334782334,1739502662.9948218,23.31997776031494,0.13845943442215436,1739502662.9948258,23.31997776031494,46.92416596208705,1739502662.994829,23.31997776031494,51.10711779446093,1739502662.9948308,23.31997776031494,1.9596178640674853,1739502662.994833,23.31997776031494,0.4155539811479867,1739502662.9948347,23.31997776031494,1.2256561290723575,1739502662.9948363,23.31997776031494,0.4589219248958546,1739502662.9948378,23.31997776031494,0.9377853713183676,1739502662.99484,23.31997776031494,0.0,1739502662.9948413,23.31997776031494,-0.4692020865656438,1739502662.9948432,23.31997776031494,0.14040364357366894,1739502662.994845,23.31997776031494,1.4069874578840114 +1739502663.0146058,23.339977741241455,46.979850334782334,1739502663.0146086,23.339977741241455,0.13845943442215436,1739502663.0146122,23.339977741241455,46.92416596208705,1739502663.0146155,23.339977741241455,51.10711779446093,1739502663.0146172,23.339977741241455,1.9596178640674853,1739502663.014619,23.339977741241455,0.4155539811479867,1739502663.014621,23.339977741241455,1.2256561290723575,1739502663.0146224,23.339977741241455,0.4589219248958546,1739502663.014624,23.339977741241455,0.9377853713183676,1739502663.014626,23.339977741241455,0.0,1739502663.0146277,23.339977741241455,-0.4692020865656438,1739502663.0146294,23.339977741241455,0.14040364357366894,1739502663.0146308,23.339977741241455,1.4069874578840114 +1739502663.0346398,23.35997772216797,46.979850334782334,1739502663.034643,23.35997772216797,0.13845943442215436,1739502663.0346463,23.35997772216797,46.92416596208705,1739502663.0346496,23.35997772216797,51.10711779446093,1739502663.034651,23.35997772216797,1.9596178640674853,1739502663.0346532,23.35997772216797,0.4155539811479867,1739502663.034655,23.35997772216797,1.2256561290723575,1739502663.0346565,23.35997772216797,0.4589219248958546,1739502663.034658,23.35997772216797,0.9377853713183676,1739502663.0346599,23.35997772216797,0.0,1739502663.0346615,23.35997772216797,-0.4692020865656438,1739502663.0346632,23.35997772216797,0.14040364357366894,1739502663.0346649,23.35997772216797,1.4069874578840114 +1739502663.0547597,23.379977703094482,46.979850334782334,1739502663.0547628,23.379977703094482,0.13845943442215436,1739502663.0547667,23.379977703094482,46.92416596208705,1739502663.0547702,23.379977703094482,51.10711779446093,1739502663.054772,23.379977703094482,1.9596178640674853,1739502663.054774,23.379977703094482,0.4155539811479867,1739502663.054776,23.379977703094482,1.2256561290723575,1739502663.0547776,23.379977703094482,0.4589219248958546,1739502663.0547793,23.379977703094482,0.9377853713183676,1739502663.0547812,23.379977703094482,0.0,1739502663.0547829,23.379977703094482,-0.4692020865656438,1739502663.0547848,23.379977703094482,0.14040364357366894,1739502663.0547864,23.379977703094482,1.4069874578840114 +1739502663.075104,23.399977684020996,47.1305013800405,1739502663.0751076,23.399977684020996,0.16084496671536552,1739502663.0751114,23.399977684020996,46.927073103011544,1739502663.0751152,23.399977684020996,51.051200296895956,1739502663.075117,23.399977684020996,1.8796869037456703,1739502663.0751197,23.399977684020996,0.4131672130753632,1739502663.0751216,23.399977684020996,1.087191383672408,1739502663.0751235,23.399977684020996,0.4521541046243205,1739502663.075125,23.399977684020996,1.0476374956209697,1739502663.0751276,23.399977684020996,0.0,1739502663.0751293,23.399977684020996,-0.2363544999826731,1739502663.0751314,23.399977684020996,0.1563929095303462,1739502663.075133,23.399977684020996,1.3567569141192195 +1739502663.095045,23.41997766494751,47.1305013800405,1739502663.09505,23.41997766494751,0.16084496671536552,1739502663.0950563,23.41997766494751,46.927073103011544,1739502663.0950634,23.41997766494751,51.051200296895956,1739502663.0950677,23.41997766494751,1.8796869037456703,1739502663.0950735,23.41997766494751,0.4131672130753632,1739502663.0950797,23.41997766494751,1.087191383672408,1739502663.0950854,23.41997766494751,0.4521541046243205,1739502663.0950885,23.41997766494751,1.0476374956209697,1739502663.095091,23.41997766494751,0.0,1739502663.0950944,23.41997766494751,-0.30911941849824975,1739502663.0951006,23.41997766494751,0.1563929095303462,1739502663.095105,23.41997766494751,1.3567569141192195 +1739502663.1150393,23.439977645874023,47.1305013800405,1739502663.115043,23.439977645874023,0.16084496671536552,1739502663.1150467,23.439977645874023,46.927073103011544,1739502663.1150506,23.439977645874023,51.051200296895956,1739502663.1150522,23.439977645874023,1.8796869037456703,1739502663.1150546,23.439977645874023,0.4131672130753632,1739502663.1150568,23.439977645874023,1.087191383672408,1739502663.1150582,23.439977645874023,0.4521541046243205,1739502663.1150599,23.439977645874023,1.0476374956209697,1739502663.1150622,23.439977645874023,0.0,1739502663.1150641,23.439977645874023,-0.30911941849824975,1739502663.1150658,23.439977645874023,0.1563929095303462,1739502663.115068,23.439977645874023,1.3567569141192195 +1739502663.135069,23.459977626800537,47.1305013800405,1739502663.1350722,23.459977626800537,0.16084496671536552,1739502663.1350763,23.459977626800537,46.927073103011544,1739502663.1350799,23.459977626800537,51.051200296895956,1739502663.1350818,23.459977626800537,1.8796869037456703,1739502663.135084,23.459977626800537,0.4131672130753632,1739502663.1350858,23.459977626800537,1.087191383672408,1739502663.135088,23.459977626800537,0.4521541046243205,1739502663.1350896,23.459977626800537,1.0476374956209697,1739502663.135092,23.459977626800537,0.0,1739502663.1350937,23.459977626800537,-0.30911941849824975,1739502663.1350956,23.459977626800537,0.1563929095303462,1739502663.1350973,23.459977626800537,1.3567569141192195 +1739502663.1549098,23.47997760772705,47.1305013800405,1739502663.154913,23.47997760772705,0.16084496671536552,1739502663.1549168,23.47997760772705,46.927073103011544,1739502663.1549208,23.47997760772705,51.051200296895956,1739502663.1549225,23.47997760772705,1.8796869037456703,1739502663.1549249,23.47997760772705,0.4131672130753632,1739502663.1549268,23.47997760772705,1.087191383672408,1739502663.1549287,23.47997760772705,0.4521541046243205,1739502663.15493,23.47997760772705,1.0476374956209697,1739502663.1549323,23.47997760772705,0.0,1739502663.154934,23.47997760772705,-0.30911941849824975,1739502663.154936,23.47997760772705,0.1563929095303462,1739502663.1549377,23.47997760772705,1.3567569141192195 +1739502663.1750658,23.499977588653564,47.27601153586769,1739502663.175069,23.499977588653564,0.1849440898256045,1739502663.1750734,23.499977588653564,46.92988599421848,1739502663.1750772,23.499977588653564,51.013771297667326,1739502663.1750789,23.499977588653564,1.8284238810184406,1739502663.1750813,23.499977588653564,0.4142525522963405,1739502663.175083,23.499977588653564,0.9726246705170164,1739502663.1750848,23.499977588653564,0.4447581342962402,1739502663.1750865,23.499977588653564,1.14819482933308,1739502663.1750886,23.499977588653564,0.0,1739502663.1750908,23.499977588653564,-0.11464607746113609,1739502663.1750925,23.499977588653564,0.17373407954622683,1739502663.1750946,23.499977588653564,1.323613865714171 +1739502663.194936,23.519977569580078,47.27601153586769,1739502663.1949391,23.519977569580078,0.1849440898256045,1739502663.1949427,23.519977569580078,46.92988599421848,1739502663.1949463,23.519977569580078,51.013771297667326,1739502663.1949482,23.519977569580078,1.8284238810184406,1739502663.19495,23.519977569580078,0.4142525522963405,1739502663.1949522,23.519977569580078,0.9726246705170164,1739502663.194954,23.519977569580078,0.4447581342962402,1739502663.1949558,23.519977569580078,1.14819482933308,1739502663.1949577,23.519977569580078,0.0,1739502663.1949596,23.519977569580078,-0.17541903638109102,1739502663.1949613,23.519977569580078,0.17373407954622683,1739502663.1949632,23.519977569580078,1.323613865714171 +1739502663.215046,23.539977550506592,47.27601153586769,1739502663.2150495,23.539977550506592,0.1849440898256045,1739502663.2150536,23.539977550506592,46.92988599421848,1739502663.2150571,23.539977550506592,51.013771297667326,1739502663.215059,23.539977550506592,1.8284238810184406,1739502663.2150612,23.539977550506592,0.4142525522963405,1739502663.215063,23.539977550506592,0.9726246705170164,1739502663.2150648,23.539977550506592,0.4447581342962402,1739502663.2150667,23.539977550506592,1.14819482933308,1739502663.2150686,23.539977550506592,0.0,1739502663.2150707,23.539977550506592,-0.17541903638109102,1739502663.2150724,23.539977550506592,0.17373407954622683,1739502663.2150743,23.539977550506592,1.323613865714171 +1739502663.2350025,23.559977531433105,47.27601153586769,1739502663.2350059,23.559977531433105,0.1849440898256045,1739502663.2350104,23.559977531433105,46.92988599421848,1739502663.2350142,23.559977531433105,51.013771297667326,1739502663.2350159,23.559977531433105,1.8284238810184406,1739502663.2350183,23.559977531433105,0.4142525522963405,1739502663.2350204,23.559977531433105,0.9726246705170164,1739502663.2350218,23.559977531433105,0.4447581342962402,1739502663.2350235,23.559977531433105,1.14819482933308,1739502663.235026,23.559977531433105,0.0,1739502663.2350278,23.559977531433105,-0.17541903638109102,1739502663.2350295,23.559977531433105,0.17373407954622683,1739502663.2350316,23.559977531433105,1.323613865714171 +1739502663.2548413,23.57997751235962,47.27601153586769,1739502663.2548444,23.57997751235962,0.1849440898256045,1739502663.2548482,23.57997751235962,46.92988599421848,1739502663.2548518,23.57997751235962,51.013771297667326,1739502663.254854,23.57997751235962,1.8284238810184406,1739502663.254856,23.57997751235962,0.4142525522963405,1739502663.254858,23.57997751235962,0.9726246705170164,1739502663.2548597,23.57997751235962,0.4447581342962402,1739502663.2548614,23.57997751235962,1.14819482933308,1739502663.2548633,23.57997751235962,0.0,1739502663.2548652,23.57997751235962,-0.17541903638109102,1739502663.2548673,23.57997751235962,0.17373407954622683,1739502663.254869,23.57997751235962,1.323613865714171 +1739502663.2750723,23.599977493286133,47.27601153586769,1739502663.275076,23.599977493286133,0.1849440898256045,1739502663.27508,23.599977493286133,46.92988599421848,1739502663.275084,23.599977493286133,51.013771297667326,1739502663.275086,23.599977493286133,1.8284238810184406,1739502663.275088,23.599977493286133,0.4142525522963405,1739502663.2750902,23.599977493286133,0.9726246705170164,1739502663.2750916,23.599977493286133,0.4447581342962402,1739502663.2750938,23.599977493286133,1.14819482933308,1739502663.2750957,23.599977493286133,0.0,1739502663.2750976,23.599977493286133,-0.17541903638109102,1739502663.2750993,23.599977493286133,0.17373407954622683,1739502663.2751014,23.599977493286133,1.323613865714171 +1739502663.2949448,23.619977474212646,47.41836759433695,1739502663.2949479,23.619977474212646,0.21114970938960376,1739502663.2949517,23.619977474212646,47.3172589008869,1739502663.2949555,23.619977474212646,51.2109649118825,1739502663.2949572,23.619977474212646,2.119060886868755,1739502663.2949595,23.619977474212646,0.46609412034641834,1739502663.2949615,23.619977474212646,1.148615208424179,1739502663.2949631,23.619977474212646,0.4851514315788401,1739502663.294965,23.619977474212646,0.9974019459342122,1739502663.294967,23.619977474212646,0.0,1739502663.2949688,23.619977474212646,-0.36854922192115647,1739502663.2949712,23.619977474212646,0.19212827218315282,1739502663.294973,23.619977474212646,1.3055979453034419 +1739502663.3150597,23.63997745513916,47.41836759433695,1739502663.3150635,23.63997745513916,0.21114970938960376,1739502663.315067,23.63997745513916,47.3172589008869,1739502663.3150709,23.63997745513916,51.2109649118825,1739502663.3150728,23.63997745513916,2.119060886868755,1739502663.3150752,23.63997745513916,0.46609412034641834,1739502663.315077,23.63997745513916,1.148615208424179,1739502663.3150792,23.63997745513916,0.4851514315788401,1739502663.3150806,23.63997745513916,0.9974019459342122,1739502663.315083,23.63997745513916,0.0,1739502663.3150845,23.63997745513916,-0.3081959993692297,1739502663.3150866,23.63997745513916,0.19212827218315282,1739502663.3150883,23.63997745513916,1.3055979453034419 +1739502663.335034,23.659977436065674,47.41836759433695,1739502663.3350377,23.659977436065674,0.21114970938960376,1739502663.3350415,23.659977436065674,47.3172589008869,1739502663.335045,23.659977436065674,51.2109649118825,1739502663.335047,23.659977436065674,2.119060886868755,1739502663.3350492,23.659977436065674,0.46609412034641834,1739502663.3350513,23.659977436065674,1.148615208424179,1739502663.335053,23.659977436065674,0.4851514315788401,1739502663.3350546,23.659977436065674,0.9974019459342122,1739502663.3350568,23.659977436065674,0.0,1739502663.3350587,23.659977436065674,-0.3081959993692297,1739502663.3350606,23.659977436065674,0.19212827218315282,1739502663.3350625,23.659977436065674,1.3055979453034419 +1739502663.3551178,23.679977416992188,47.41836759433695,1739502663.355121,23.679977416992188,0.21114970938960376,1739502663.3551247,23.679977416992188,47.3172589008869,1739502663.3551283,23.679977416992188,51.2109649118825,1739502663.3551302,23.679977416992188,2.119060886868755,1739502663.3551323,23.679977416992188,0.46609412034641834,1739502663.3551342,23.679977416992188,1.148615208424179,1739502663.355136,23.679977416992188,0.4851514315788401,1739502663.3551376,23.679977416992188,0.9974019459342122,1739502663.3551395,23.679977416992188,0.0,1739502663.3551414,23.679977416992188,-0.3081959993692297,1739502663.355143,23.679977416992188,0.19212827218315282,1739502663.3551452,23.679977416992188,1.3055979453034419 +1739502663.3750486,23.6999773979187,47.41836759433695,1739502663.375052,23.6999773979187,0.21114970938960376,1739502663.375056,23.6999773979187,47.3172589008869,1739502663.3750596,23.6999773979187,51.2109649118825,1739502663.3750615,23.6999773979187,2.119060886868755,1739502663.375064,23.6999773979187,0.46609412034641834,1739502663.3750656,23.6999773979187,1.148615208424179,1739502663.3750675,23.6999773979187,0.4851514315788401,1739502663.3750691,23.6999773979187,0.9974019459342122,1739502663.3750713,23.6999773979187,0.0,1739502663.375073,23.6999773979187,-0.3081959993692297,1739502663.375075,23.6999773979187,0.19212827218315282,1739502663.3750768,23.6999773979187,1.3055979453034419 +1739502663.3950627,23.719977378845215,47.55768861257462,1739502663.3950658,23.719977378845215,0.23948032396789998,1739502663.3950696,23.719977378845215,47.325426843843076,1739502663.395073,23.719977378845215,51.18373232147841,1739502663.3950748,23.719977378845215,2.0752807458774707,1739502663.3950772,23.719977378845215,0.4686605178430561,1739502663.395079,23.719977378845215,1.0351684233839915,1739502663.3950808,23.719977378845215,0.47722195915101673,1739502663.3950822,23.719977378845215,1.0921584780004758,1739502663.3950846,23.719977378845215,0.0,1739502663.395086,23.719977378845215,-0.12693031217748754,1739502663.3950882,23.719977378845215,0.21112387268005653,1739502663.3950899,23.719977378845215,1.275734354565109 +1739502663.4150298,23.73997735977173,47.55768861257462,1739502663.415033,23.73997735977173,0.23948032396789998,1739502663.4150376,23.73997735977173,47.325426843843076,1739502663.4150414,23.73997735977173,51.18373232147841,1739502663.4150434,23.73997735977173,2.0752807458774707,1739502663.4150457,23.73997735977173,0.4686605178430561,1739502663.4150476,23.73997735977173,1.0351684233839915,1739502663.4150496,23.73997735977173,0.47722195915101673,1739502663.4150512,23.73997735977173,1.0921584780004758,1739502663.4150536,23.73997735977173,0.0,1739502663.4150553,23.73997735977173,-0.18357587656463314,1739502663.4150572,23.73997735977173,0.21112387268005653,1739502663.415059,23.73997735977173,1.275734354565109 +1739502663.4351387,23.759977340698242,47.55768861257462,1739502663.4351425,23.759977340698242,0.23948032396789998,1739502663.4351463,23.759977340698242,47.325426843843076,1739502663.4351501,23.759977340698242,51.18373232147841,1739502663.435152,23.759977340698242,2.0752807458774707,1739502663.4351544,23.759977340698242,0.4686605178430561,1739502663.435156,23.759977340698242,1.0351684233839915,1739502663.4351578,23.759977340698242,0.47722195915101673,1739502663.4351594,23.759977340698242,1.0921584780004758,1739502663.4351618,23.759977340698242,0.0,1739502663.4351637,23.759977340698242,-0.18357587656463314,1739502663.4351656,23.759977340698242,0.21112387268005653,1739502663.4351678,23.759977340698242,1.275734354565109 +1739502663.4550052,23.779977321624756,47.55768861257462,1739502663.4550085,23.779977321624756,0.23948032396789998,1739502663.4550123,23.779977321624756,47.325426843843076,1739502663.455016,23.779977321624756,51.18373232147841,1739502663.4550178,23.779977321624756,2.0752807458774707,1739502663.4550197,23.779977321624756,0.4686605178430561,1739502663.4550219,23.779977321624756,1.0351684233839915,1739502663.4550235,23.779977321624756,0.47722195915101673,1739502663.4550252,23.779977321624756,1.0921584780004758,1739502663.455027,23.779977321624756,0.0,1739502663.455029,23.779977321624756,-0.18357587656463314,1739502663.4550312,23.779977321624756,0.21112387268005653,1739502663.4550328,23.779977321624756,1.275734354565109 +1739502663.4750721,23.79997730255127,47.55768861257462,1739502663.4750764,23.79997730255127,0.23948032396789998,1739502663.4750807,23.79997730255127,47.325426843843076,1739502663.475085,23.79997730255127,51.18373232147841,1739502663.4750872,23.79997730255127,2.0752807458774707,1739502663.4750896,23.79997730255127,0.4686605178430561,1739502663.4750922,23.79997730255127,1.0351684233839915,1739502663.4750946,23.79997730255127,0.47722195915101673,1739502663.4750965,23.79997730255127,1.0921584780004758,1739502663.4750986,23.79997730255127,0.0,1739502663.4751008,23.79997730255127,-0.18357587656463314,1739502663.475103,23.79997730255127,0.21112387268005653,1739502663.4751055,23.79997730255127,1.275734354565109 +1739502663.4948285,23.819977283477783,47.55768861257462,1739502663.4948316,23.819977283477783,0.23948032396789998,1739502663.4948354,23.819977283477783,47.325426843843076,1739502663.494839,23.819977283477783,51.18373232147841,1739502663.4948409,23.819977283477783,2.0752807458774707,1739502663.4948432,23.819977283477783,0.4686605178430561,1739502663.494845,23.819977283477783,1.0351684233839915,1739502663.4948468,23.819977283477783,0.47722195915101673,1739502663.4948483,23.819977283477783,1.0921584780004758,1739502663.4948504,23.819977283477783,0.0,1739502663.494852,23.819977283477783,-0.18357587656463314,1739502663.494854,23.819977283477783,0.21112387268005653,1739502663.4948556,23.819977283477783,1.275734354565109 +1739502663.5151598,23.839977264404297,47.6934121698956,1739502663.5151632,23.839977264404297,0.26985811887787925,1739502663.5151672,23.839977264404297,47.69496520498757,1739502663.515171,23.839977264404297,51.34150907232136,1739502663.515173,23.839977264404297,2.34692484565306,1739502663.515175,23.839977264404297,0.5175824987997248,1739502663.515177,23.839977264404297,1.1857778895240498,1739502663.5151787,23.839977264404297,0.5117385347023096,1739502663.5151806,23.839977264404297,0.9681854981490045,1739502663.5151825,23.839977264404297,0.0,1739502663.5151844,23.839977264404297,-0.3236817504625001,1739502663.5151865,23.839977264404297,0.23121901277838186,1739502663.5151885,23.839977264404297,1.2480841343119744 +1739502663.5350847,23.85997724533081,47.6934121698956,1739502663.535088,23.85997724533081,0.26985811887787925,1739502663.535092,23.85997724533081,47.69496520498757,1739502663.5350957,23.85997724533081,51.34150907232136,1739502663.5350978,23.85997724533081,2.34692484565306,1739502663.5351005,23.85997724533081,0.5175824987997248,1739502663.5351021,23.85997724533081,1.1857778895240498,1739502663.535104,23.85997724533081,0.5117385347023096,1739502663.5351055,23.85997724533081,0.9681854981490045,1739502663.5351079,23.85997724533081,0.0,1739502663.5351095,23.85997724533081,-0.27989863616296995,1739502663.5351114,23.85997724533081,0.23121901277838186,1739502663.5351133,23.85997724533081,1.2480841343119744 +1739502663.5551045,23.879977226257324,47.6934121698956,1739502663.5551076,23.879977226257324,0.26985811887787925,1739502663.5551114,23.879977226257324,47.69496520498757,1739502663.5551152,23.879977226257324,51.34150907232136,1739502663.555117,23.879977226257324,2.34692484565306,1739502663.555119,23.879977226257324,0.5175824987997248,1739502663.555121,23.879977226257324,1.1857778895240498,1739502663.5551229,23.879977226257324,0.5117385347023096,1739502663.5551248,23.879977226257324,0.9681854981490045,1739502663.5551267,23.879977226257324,0.0,1739502663.5551283,23.879977226257324,-0.27989863616296995,1739502663.5551305,23.879977226257324,0.23121901277838186,1739502663.5551324,23.879977226257324,1.2480841343119744 +1739502663.57515,23.899977207183838,47.6934121698956,1739502663.5751536,23.899977207183838,0.26985811887787925,1739502663.5751576,23.899977207183838,47.69496520498757,1739502663.5751615,23.899977207183838,51.34150907232136,1739502663.5751634,23.899977207183838,2.34692484565306,1739502663.5751657,23.899977207183838,0.5175824987997248,1739502663.5751674,23.899977207183838,1.1857778895240498,1739502663.5751693,23.899977207183838,0.5117385347023096,1739502663.575171,23.899977207183838,0.9681854981490045,1739502663.5751731,23.899977207183838,0.0,1739502663.5751748,23.899977207183838,-0.27989863616296995,1739502663.575177,23.899977207183838,0.23121901277838186,1739502663.5751789,23.899977207183838,1.2480841343119744 +1739502663.5942655,23.91997718811035,47.6934121698956,1739502663.5942674,23.91997718811035,0.26985811887787925,1739502663.5942702,23.91997718811035,47.69496520498757,1739502663.5942726,23.91997718811035,51.34150907232136,1739502663.594274,23.91997718811035,2.34692484565306,1739502663.5942755,23.91997718811035,0.5175824987997248,1739502663.5942771,23.91997718811035,1.1857778895240498,1739502663.5942783,23.91997718811035,0.5117385347023096,1739502663.5942795,23.91997718811035,0.9681854981490045,1739502663.594281,23.91997718811035,0.0,1739502663.594282,23.91997718811035,-0.27989863616296995,1739502663.5942833,23.91997718811035,0.23121901277838186,1739502663.5942845,23.91997718811035,1.2480841343119744 +1739502663.6146216,23.939977169036865,47.825266873290325,1739502663.6146245,23.939977169036865,0.3021921965171783,1739502663.6146278,23.939977169036865,47.88031752955088,1739502663.614631,23.939977169036865,51.39891792892731,1739502663.6146324,23.939977169036865,2.4572824940000784,1739502663.6146345,23.939977169036865,0.5426591357841861,1739502663.614636,23.939977169036865,1.1961736330598323,1739502663.6146376,23.939977169036865,0.5221619271405198,1739502663.614639,23.939977169036865,0.9601668816519424,1739502663.614641,23.939977169036865,0.0,1739502663.6146421,23.939977169036865,-0.2472509525649595,1739502663.614644,23.939977169036865,0.2519476846163402,1739502663.6146457,23.939977169036865,1.2176202420305 +1739502663.6356237,23.95997714996338,47.825266873290325,1739502663.635628,23.95997714996338,0.3021921965171783,1739502663.6356332,23.95997714996338,47.88031752955088,1739502663.635638,23.95997714996338,51.39891792892731,1739502663.6356409,23.95997714996338,2.4572824940000784,1739502663.6356437,23.95997714996338,0.5426591357841861,1739502663.6356468,23.95997714996338,1.1961736330598323,1739502663.6356492,23.95997714996338,0.5221619271405198,1739502663.6356516,23.95997714996338,0.9601668816519424,1739502663.6356542,23.95997714996338,0.0,1739502663.635656,23.95997714996338,-0.2574533603785576,1739502663.6356587,23.95997714996338,0.2519476846163402,1739502663.6356611,23.95997714996338,1.2176202420305 +1739502663.6558459,23.979977130889893,47.825266873290325,1739502663.6558495,23.979977130889893,0.3021921965171783,1739502663.655854,23.979977130889893,47.88031752955088,1739502663.6558585,23.979977130889893,51.39891792892731,1739502663.6558604,23.979977130889893,2.4572824940000784,1739502663.6558633,23.979977130889893,0.5426591357841861,1739502663.6558654,23.979977130889893,1.1961736330598323,1739502663.6558676,23.979977130889893,0.5221619271405198,1739502663.6558697,23.979977130889893,0.9601668816519424,1739502663.655872,23.979977130889893,0.0,1739502663.655874,23.979977130889893,-0.2574533603785576,1739502663.6558764,23.979977130889893,0.2519476846163402,1739502663.6558785,23.979977130889893,1.2176202420305 +1739502663.6759622,23.999977111816406,47.825266873290325,1739502663.6759667,23.999977111816406,0.3021921965171783,1739502663.6759717,23.999977111816406,47.88031752955088,1739502663.6759765,23.999977111816406,51.39891792892731,1739502663.675979,23.999977111816406,2.4572824940000784,1739502663.6759818,23.999977111816406,0.5426591357841861,1739502663.675984,23.999977111816406,1.1961736330598323,1739502663.675987,23.999977111816406,0.5221619271405198,1739502663.675989,23.999977111816406,0.9601668816519424,1739502663.6759915,23.999977111816406,0.0,1739502663.675994,23.999977111816406,-0.2574533603785576,1739502663.675996,23.999977111816406,0.2519476846163402,1739502663.6759984,23.999977111816406,1.2176202420305 +1739502663.696369,24.01997709274292,47.825266873290325,1739502663.6963725,24.01997709274292,0.3021921965171783,1739502663.6963768,24.01997709274292,47.88031752955088,1739502663.6963813,24.01997709274292,51.39891792892731,1739502663.6963835,24.01997709274292,2.4572824940000784,1739502663.696386,24.01997709274292,0.5426591357841861,1739502663.696388,24.01997709274292,1.1961736330598323,1739502663.6963902,24.01997709274292,0.5221619271405198,1739502663.6963923,24.01997709274292,0.9601668816519424,1739502663.6963944,24.01997709274292,0.0,1739502663.6963968,24.01997709274292,-0.2574533603785576,1739502663.6963987,24.01997709274292,0.2519476846163402,1739502663.6964011,24.01997709274292,1.2176202420305 +1739502663.71532,24.039977073669434,47.825266873290325,1739502663.7153237,24.039977073669434,0.3021921965171783,1739502663.7153282,24.039977073669434,47.88031752955088,1739502663.715332,24.039977073669434,51.39891792892731,1739502663.715334,24.039977073669434,2.4572824940000784,1739502663.715336,24.039977073669434,0.5426591357841861,1739502663.7153382,24.039977073669434,1.1961736330598323,1739502663.7153404,24.039977073669434,0.5221619271405198,1739502663.7153418,24.039977073669434,0.9601668816519424,1739502663.7153442,24.039977073669434,0.0,1739502663.7153456,24.039977073669434,-0.2574533603785576,1739502663.7153478,24.039977073669434,0.2519476846163402,1739502663.7153494,24.039977073669434,1.2176202420305 +1739502663.7351084,24.059977054595947,47.95317430929381,1739502663.735112,24.059977054595947,0.33647648215371184,1739502663.7351158,24.059977054595947,47.88288490797749,1739502663.7351196,24.059977054595947,51.37224964280906,1739502663.7351215,24.059977054595947,2.4059576308578183,1739502663.7351236,24.059977054595947,0.5442892217323383,1739502663.7351258,24.059977054595947,1.0666480596636716,1739502663.7351272,24.059977054595947,0.5079516679823235,1739502663.735129,24.059977054595947,1.0649973215090163,1739502663.735131,24.059977054595947,0.0,1739502663.735133,24.059977054595947,-0.06102274934571208,1739502663.7351346,24.059977054595947,0.27412601182778307,1739502663.7351365,24.059977054595947,1.1874046770493767 +1739502663.7552357,24.07997703552246,47.95317430929381,1739502663.7552388,24.07997703552246,0.33647648215371184,1739502663.7552426,24.07997703552246,47.88288490797749,1739502663.7552462,24.07997703552246,51.37224964280906,1739502663.7552478,24.07997703552246,2.4059576308578183,1739502663.7552502,24.07997703552246,0.5442892217323383,1739502663.755252,24.07997703552246,1.0666480596636716,1739502663.7552538,24.07997703552246,0.5079516679823235,1739502663.7552555,24.07997703552246,1.0649973215090163,1739502663.7552576,24.07997703552246,0.0,1739502663.7552593,24.07997703552246,-0.12240735554036042,1739502663.7552612,24.07997703552246,0.27412601182778307,1739502663.755263,24.07997703552246,1.1874046770493767 +1739502663.7750835,24.099977016448975,47.95317430929381,1739502663.7750869,24.099977016448975,0.33647648215371184,1739502663.7750907,24.099977016448975,47.88288490797749,1739502663.7750943,24.099977016448975,51.37224964280906,1739502663.7750962,24.099977016448975,2.4059576308578183,1739502663.7750983,24.099977016448975,0.5442892217323383,1739502663.7751005,24.099977016448975,1.0666480596636716,1739502663.7751021,24.099977016448975,0.5079516679823235,1739502663.7751038,24.099977016448975,1.0649973215090163,1739502663.775106,24.099977016448975,0.0,1739502663.775108,24.099977016448975,-0.12240735554036042,1739502663.7751102,24.099977016448975,0.27412601182778307,1739502663.775112,24.099977016448975,1.1874046770493767 +1739502663.7954862,24.11997699737549,47.95317430929381,1739502663.795489,24.11997699737549,0.33647648215371184,1739502663.7954931,24.11997699737549,47.88288490797749,1739502663.795497,24.11997699737549,51.37224964280906,1739502663.7954988,24.11997699737549,2.4059576308578183,1739502663.795501,24.11997699737549,0.5442892217323383,1739502663.795503,24.11997699737549,1.0666480596636716,1739502663.7955046,24.11997699737549,0.5079516679823235,1739502663.7955065,24.11997699737549,1.0649973215090163,1739502663.7955084,24.11997699737549,0.0,1739502663.79551,24.11997699737549,-0.12240735554036042,1739502663.7955117,24.11997699737549,0.27412601182778307,1739502663.7955136,24.11997699737549,1.1874046770493767 +1739502663.8149703,24.139976978302002,47.95317430929381,1739502663.8149734,24.139976978302002,0.33647648215371184,1739502663.8149772,24.139976978302002,47.88288490797749,1739502663.8149807,24.139976978302002,51.37224964280906,1739502663.8149827,24.139976978302002,2.4059576308578183,1739502663.814985,24.139976978302002,0.5442892217323383,1739502663.8149867,24.139976978302002,1.0666480596636716,1739502663.8149886,24.139976978302002,0.5079516679823235,1739502663.8149903,24.139976978302002,1.0649973215090163,1739502663.8149924,24.139976978302002,0.0,1739502663.814994,24.139976978302002,-0.12240735554036042,1739502663.814996,24.139976978302002,0.27412601182778307,1739502663.8149977,24.139976978302002,1.1874046770493767 +1739502663.8351114,24.159976959228516,48.07785180542216,1739502663.8351145,24.159976959228516,0.37291619269550846,1739502663.8351185,24.159976959228516,47.8853995392461,1739502663.8351223,24.159976959228516,51.36097511763568,1739502663.8351243,24.159976959228516,2.3837843980168345,1739502663.8351266,24.159976959228516,0.5495500853773714,1739502663.8351283,24.159976959228516,0.963255121714345,1739502663.8351302,24.159976959228516,0.4945634054653278,1739502663.835132,24.159976959228516,1.1568336195030333,1739502663.835134,24.159976959228516,0.0,1739502663.8351357,24.159976959228516,0.031092514469664385,1739502663.8351376,24.159976959228516,0.29666716659062037,1739502663.8351395,24.159976959228516,1.173709845862259 +1739502663.8551116,24.17997694015503,48.07785180542216,1739502663.8551147,24.17997694015503,0.37291619269550846,1739502663.8551183,24.17997694015503,47.8853995392461,1739502663.855122,24.17997694015503,51.36097511763568,1739502663.855124,24.17997694015503,2.3837843980168345,1739502663.8551264,24.17997694015503,0.5495500853773714,1739502663.855128,24.17997694015503,0.963255121714345,1739502663.85513,24.17997694015503,0.4945634054653278,1739502663.8551314,24.17997694015503,1.1568336195030333,1739502663.8551338,24.17997694015503,0.0,1739502663.8551352,24.17997694015503,-0.0168762263592257,1739502663.8551373,24.17997694015503,0.29666716659062037,1739502663.855139,24.17997694015503,1.173709845862259 +1739502663.875011,24.199976921081543,48.07785180542216,1739502663.875014,24.199976921081543,0.37291619269550846,1739502663.8750184,24.199976921081543,47.8853995392461,1739502663.8750224,24.199976921081543,51.36097511763568,1739502663.875024,24.199976921081543,2.3837843980168345,1739502663.8750267,24.199976921081543,0.5495500853773714,1739502663.8750284,24.199976921081543,0.963255121714345,1739502663.8750303,24.199976921081543,0.4945634054653278,1739502663.875032,24.199976921081543,1.1568336195030333,1739502663.8750346,24.199976921081543,0.0,1739502663.8750365,24.199976921081543,-0.0168762263592257,1739502663.8750381,24.199976921081543,0.29666716659062037,1739502663.87504,24.199976921081543,1.173709845862259 +1739502663.895628,24.219976902008057,48.07785180542216,1739502663.8956313,24.219976902008057,0.37291619269550846,1739502663.8956363,24.219976902008057,47.8853995392461,1739502663.8956406,24.219976902008057,51.36097511763568,1739502663.8956425,24.219976902008057,2.3837843980168345,1739502663.895645,24.219976902008057,0.5495500853773714,1739502663.895647,24.219976902008057,0.963255121714345,1739502663.895649,24.219976902008057,0.4945634054653278,1739502663.8956509,24.219976902008057,1.1568336195030333,1739502663.8956535,24.219976902008057,0.0,1739502663.8956552,24.219976902008057,-0.0168762263592257,1739502663.8956573,24.219976902008057,0.29666716659062037,1739502663.8956592,24.219976902008057,1.173709845862259 +1739502663.9170456,24.23997688293457,48.07785180542216,1739502663.9170501,24.23997688293457,0.37291619269550846,1739502663.917056,24.23997688293457,47.8853995392461,1739502663.9170618,24.23997688293457,51.36097511763568,1739502663.9170647,24.23997688293457,2.3837843980168345,1739502663.917068,24.23997688293457,0.5495500853773714,1739502663.9170709,24.23997688293457,0.963255121714345,1739502663.9170735,24.23997688293457,0.4945634054653278,1739502663.917076,24.23997688293457,1.1568336195030333,1739502663.9170792,24.23997688293457,0.0,1739502663.917082,24.23997688293457,-0.0168762263592257,1739502663.917085,24.23997688293457,0.29666716659062037,1739502663.9170878,24.23997688293457,1.173709845862259 +1739502663.9373379,24.259976863861084,48.07785180542216,1739502663.9373426,24.259976863861084,0.37291619269550846,1739502663.9373488,24.259976863861084,47.8853995392461,1739502663.9373548,24.259976863861084,51.36097511763568,1739502663.9373577,24.259976863861084,2.3837843980168345,1739502663.937361,24.259976863861084,0.5495500853773714,1739502663.9373636,24.259976863861084,0.963255121714345,1739502663.9373665,24.259976863861084,0.4945634054653278,1739502663.937369,24.259976863861084,1.1568336195030333,1739502663.9373727,24.259976863861084,0.0,1739502663.9373755,24.259976863861084,-0.0168762263592257,1739502663.9373784,24.259976863861084,0.29666716659062037,1739502663.937381,24.259976863861084,1.173709845862259 +1739502663.956653,24.279976844787598,48.20092257108941,1739502663.9566576,24.279976844787598,0.4119204185088634,1739502663.9566643,24.279976844787598,47.88789390069703,1739502663.95667,24.279976844787598,51.36129266200581,1739502663.956697,24.279976844787598,2.3844089019447603,1739502663.956708,24.279976844787598,0.5579749780965672,1739502663.9567144,24.279976844787598,0.8810751095213984,1739502663.9567227,24.279976844787598,0.48333292601534944,1739502663.9567292,24.279976844787598,1.235444277501496,1739502663.956736,24.279976844787598,0.0,1739502663.9567423,24.279976844787598,0.09877113756267496,1739502663.9567492,24.279976844787598,0.31920832135345767,1739502663.9567566,24.279976844787598,1.1728129648595307 +1739502663.9758399,24.29997682571411,48.20092257108941,1739502663.9758441,24.29997682571411,0.4119204185088634,1739502663.9758494,24.29997682571411,47.88789390069703,1739502663.9758542,24.29997682571411,51.36129266200581,1739502663.9758563,24.29997682571411,2.3844089019447603,1739502663.9758599,24.29997682571411,0.5579749780965672,1739502663.9758625,24.29997682571411,0.8810751095213984,1739502663.975865,24.29997682571411,0.48333292601534944,1739502663.975867,24.29997682571411,1.235444277501496,1739502663.9758697,24.29997682571411,0.0,1739502663.9758723,24.29997682571411,0.06263131264196531,1739502663.9758747,24.29997682571411,0.31920832135345767,1739502663.9758768,24.29997682571411,1.1728129648595307 +1739502663.995405,24.319976806640625,48.20092257108941,1739502663.995409,24.319976806640625,0.4119204185088634,1739502663.9954138,24.319976806640625,47.88789390069703,1739502663.9954176,24.319976806640625,51.36129266200581,1739502663.9954195,24.319976806640625,2.3844089019447603,1739502663.995422,24.319976806640625,0.5579749780965672,1739502663.995424,24.319976806640625,0.8810751095213984,1739502663.9954264,24.319976806640625,0.48333292601534944,1739502663.9954278,24.319976806640625,1.235444277501496,1739502663.9954302,24.319976806640625,0.0,1739502663.9954321,24.319976806640625,0.06263131264196531,1739502663.9954343,24.319976806640625,0.31920832135345767,1739502663.995436,24.319976806640625,1.1728129648595307 +1739502664.0145047,24.33997678756714,48.20092257108941,1739502664.0145068,24.33997678756714,0.4119204185088634,1739502664.0145102,24.33997678756714,47.88789390069703,1739502664.0145128,24.33997678756714,51.36129266200581,1739502664.0145144,24.33997678756714,2.3844089019447603,1739502664.0145166,24.33997678756714,0.5579749780965672,1739502664.0145178,24.33997678756714,0.8810751095213984,1739502664.0145192,24.33997678756714,0.48333292601534944,1739502664.0145206,24.33997678756714,1.235444277501496,1739502664.0145223,24.33997678756714,0.0,1739502664.0145237,24.33997678756714,0.06263131264196531,1739502664.0145254,24.33997678756714,0.31920832135345767,1739502664.014527,24.33997678756714,1.1728129648595307 +1739502664.0344872,24.359976768493652,48.20092257108941,1739502664.0344896,24.359976768493652,0.4119204185088634,1739502664.0344927,24.359976768493652,47.88789390069703,1739502664.0344956,24.359976768493652,51.36129266200581,1739502664.0344968,24.359976768493652,2.3844089019447603,1739502664.0344985,24.359976768493652,0.5579749780965672,1739502664.0345001,24.359976768493652,0.8810751095213984,1739502664.0345016,24.359976768493652,0.48333292601534944,1739502664.034503,24.359976768493652,1.235444277501496,1739502664.0345044,24.359976768493652,0.0,1739502664.034506,24.359976768493652,0.06263131264196531,1739502664.0345075,24.359976768493652,0.31920832135345767,1739502664.0345087,24.359976768493652,1.1728129648595307 +1739502664.0550213,24.379976749420166,48.3232989772473,1739502664.0550246,24.379976749420166,0.4537643448223836,1739502664.0550287,24.379976749420166,47.890386428119285,1739502664.0550318,24.379976749420166,51.36858099676866,1739502664.0550337,24.379976749420166,2.398742626978359,1739502664.0550354,24.379976749420166,0.5683802900220298,1739502664.0550373,24.379976749420166,0.8119164362578698,1739502664.055039,24.379976749420166,0.47359898757400654,1739502664.0550408,24.379976749420166,1.3057238781235236,1739502664.0550425,24.379976749420166,0.0,1739502664.0550442,24.379976749420166,0.15497420983744292,1739502664.0550456,24.379976749420166,0.34174947611629497,1739502664.0550473,24.379976749420166,1.1796068425799053 +1739502664.0744526,24.39997673034668,48.3232989772473,1739502664.0744557,24.39997673034668,0.4537643448223836,1739502664.0744588,24.39997673034668,47.890386428119285,1739502664.074462,24.39997673034668,51.36858099676866,1739502664.0744636,24.39997673034668,2.398742626978359,1739502664.0744653,24.39997673034668,0.5683802900220298,1739502664.0744667,24.39997673034668,0.8119164362578698,1739502664.0744684,24.39997673034668,0.47359898757400654,1739502664.0744698,24.39997673034668,1.3057238781235236,1739502664.0744717,24.39997673034668,0.0,1739502664.074473,24.39997673034668,0.1261170355436183,1739502664.0744748,24.39997673034668,0.34174947611629497,1739502664.0744765,24.39997673034668,1.1796068425799053 +1739502664.0945575,24.419976711273193,48.3232989772473,1739502664.0945606,24.419976711273193,0.4537643448223836,1739502664.094565,24.419976711273193,47.890386428119285,1739502664.094568,24.419976711273193,51.36858099676866,1739502664.0945697,24.419976711273193,2.398742626978359,1739502664.0945716,24.419976711273193,0.5683802900220298,1739502664.094573,24.419976711273193,0.8119164362578698,1739502664.0945747,24.419976711273193,0.47359898757400654,1739502664.0945761,24.419976711273193,1.3057238781235236,1739502664.094578,24.419976711273193,0.0,1739502664.0945795,24.419976711273193,0.1261170355436183,1739502664.094581,24.419976711273193,0.34174947611629497,1739502664.0945828,24.419976711273193,1.1796068425799053 +1739502664.1145866,24.439976692199707,48.3232989772473,1739502664.1145897,24.439976692199707,0.4537643448223836,1739502664.1145928,24.439976692199707,47.890386428119285,1739502664.114596,24.439976692199707,51.36858099676866,1739502664.1145973,24.439976692199707,2.398742626978359,1739502664.1145992,24.439976692199707,0.5683802900220298,1739502664.1146007,24.439976692199707,0.8119164362578698,1739502664.1146023,24.439976692199707,0.47359898757400654,1739502664.114604,24.439976692199707,1.3057238781235236,1739502664.114606,24.439976692199707,0.0,1739502664.114607,24.439976692199707,0.1261170355436183,1739502664.1146085,24.439976692199707,0.34174947611629497,1739502664.1146102,24.439976692199707,1.1796068425799053 +1739502664.1347709,24.45997667312622,48.3232989772473,1739502664.1347744,24.45997667312622,0.4537643448223836,1739502664.1347783,24.45997667312622,47.890386428119285,1739502664.1347818,24.45997667312622,51.36858099676866,1739502664.1347837,24.45997667312622,2.398742626978359,1739502664.1347861,24.45997667312622,0.5683802900220298,1739502664.1347878,24.45997667312622,0.8119164362578698,1739502664.1347895,24.45997667312622,0.47359898757400654,1739502664.1347911,24.45997667312622,1.3057238781235236,1739502664.1347933,24.45997667312622,0.0,1739502664.134795,24.45997667312622,0.1261170355436183,1739502664.1347969,24.45997667312622,0.34174947611629497,1739502664.1347988,24.45997667312622,1.1796068425799053 +1739502664.1591508,24.479976654052734,48.3232989772473,1739502664.1591568,24.479976654052734,0.4537643448223836,1739502664.1591644,24.479976654052734,47.890386428119285,1739502664.1591735,24.479976654052734,51.36858099676866,1739502664.1591783,24.479976654052734,2.398742626978359,1739502664.1591847,24.479976654052734,0.5683802900220298,1739502664.1591902,24.479976654052734,0.8119164362578698,1739502664.159196,24.479976654052734,0.47359898757400654,1739502664.1592019,24.479976654052734,1.3057238781235236,1739502664.1592073,24.479976654052734,0.0,1739502664.159213,24.479976654052734,0.1261170355436183,1739502664.159219,24.479976654052734,0.34174947611629497,1739502664.1592247,24.479976654052734,1.1796068425799053 +1739502664.1779037,24.499976634979248,48.44579730899187,1739502664.1779077,24.499976634979248,0.4987600450601759,1739502664.1779134,24.499976634979248,48.55867616354688,1739502664.1779196,24.499976634979248,51.633217345677686,1739502664.1779234,24.499976634979248,3.0424594708949324,1739502664.177928,24.499976634979248,0.6735467355488397,1739502664.177932,24.499976634979248,1.241138624318388,1739502664.177936,24.499976634979248,0.5663504238480399,1739502664.1779401,24.499976634979248,0.9262416033884863,1739502664.1779444,24.499976634979248,0.0,1739502664.1779485,24.499976634979248,-0.4467955230060776,1739502664.1779528,24.499976634979248,0.36429063087913227,1739502664.177957,24.499976634979248,1.1940018344630992 +1739502664.1965106,24.51997661590576,48.44579730899187,1739502664.1965137,24.51997661590576,0.4987600450601759,1739502664.1965177,24.51997661590576,48.55867616354688,1739502664.1965222,24.51997661590576,51.633217345677686,1739502664.1965249,24.51997661590576,3.0424594708949324,1739502664.1965284,24.51997661590576,0.6735467355488397,1739502664.1965315,24.51997661590576,1.241138624318388,1739502664.1965346,24.51997661590576,0.5663504238480399,1739502664.1965375,24.51997661590576,0.9262416033884863,1739502664.1965406,24.51997661590576,0.0,1739502664.1965437,24.51997661590576,-0.2677602310746129,1739502664.1965468,24.51997661590576,0.36429063087913227,1739502664.1965501,24.51997661590576,1.1940018344630992 +1739502664.2162185,24.539976596832275,48.44579730899187,1739502664.2162213,24.539976596832275,0.4987600450601759,1739502664.2162256,24.539976596832275,48.55867616354688,1739502664.2162304,24.539976596832275,51.633217345677686,1739502664.216233,24.539976596832275,3.0424594708949324,1739502664.2162364,24.539976596832275,0.6735467355488397,1739502664.2162395,24.539976596832275,1.241138624318388,1739502664.2162423,24.539976596832275,0.5663504238480399,1739502664.2162454,24.539976596832275,0.9262416033884863,1739502664.2162485,24.539976596832275,0.0,1739502664.2162516,24.539976596832275,-0.2677602310746129,1739502664.2162547,24.539976596832275,0.36429063087913227,1739502664.2162578,24.539976596832275,1.1940018344630992 +1739502664.2366223,24.55997657775879,48.44579730899187,1739502664.2366257,24.55997657775879,0.4987600450601759,1739502664.23663,24.55997657775879,48.55867616354688,1739502664.2366352,24.55997657775879,51.633217345677686,1739502664.2366376,24.55997657775879,3.0424594708949324,1739502664.2366416,24.55997657775879,0.6735467355488397,1739502664.2366447,24.55997657775879,1.241138624318388,1739502664.2366478,24.55997657775879,0.5663504238480399,1739502664.2366512,24.55997657775879,0.9262416033884863,1739502664.2366545,24.55997657775879,0.0,1739502664.2366579,24.55997657775879,-0.2677602310746129,1739502664.2366612,24.55997657775879,0.36429063087913227,1739502664.2366645,24.55997657775879,1.1940018344630992 +1739502664.2573059,24.579976558685303,48.44579730899187,1739502664.2573092,24.579976558685303,0.4987600450601759,1739502664.2573135,24.579976558685303,48.55867616354688,1739502664.2573185,24.579976558685303,51.633217345677686,1739502664.2573211,24.579976558685303,3.0424594708949324,1739502664.2573247,24.579976558685303,0.6735467355488397,1739502664.257328,24.579976558685303,1.241138624318388,1739502664.2573311,24.579976558685303,0.5663504238480399,1739502664.2573345,24.579976558685303,0.9262416033884863,1739502664.2573378,24.579976558685303,0.0,1739502664.257341,24.579976558685303,-0.2677602310746129,1739502664.2573442,24.579976558685303,0.36429063087913227,1739502664.2573476,24.579976558685303,1.1940018344630992 +1739502664.2745605,24.599976539611816,48.566723563991665,1739502664.274563,24.599976539611816,0.546308734635975,1739502664.2745662,24.599976539611816,48.657183595905714,1739502664.274569,24.599976539611816,51.64428009636474,1739502664.2745702,24.599976539611816,3.0803889018219714,1739502664.2745721,24.599976539611816,0.6888511657268808,1739502664.2745733,24.599976539611816,1.1834674553019429,1739502664.2745745,24.599976539611816,0.5651116005608319,1739502664.274576,24.599976539611816,0.9699766961437273,1739502664.2745774,24.599976539611816,0.0,1739502664.274579,24.599976539611816,-0.16123816733800725,1739502664.2745805,24.599976539611816,0.38744640035374084,1739502664.2745817,24.599976539611816,1.1645030302248467 +1739502664.2944322,24.61997652053833,48.566723563991665,1739502664.294435,24.61997652053833,0.546308734635975,1739502664.2944381,24.61997652053833,48.657183595905714,1739502664.2944407,24.61997652053833,51.64428009636474,1739502664.294443,24.61997652053833,3.0803889018219714,1739502664.2944448,24.61997652053833,0.6888511657268808,1739502664.294446,24.61997652053833,1.1834674553019429,1739502664.294448,24.61997652053833,0.5651116005608319,1739502664.2944489,24.61997652053833,0.9699766961437273,1739502664.2944508,24.61997652053833,0.0,1739502664.2944517,24.61997652053833,-0.1945263340811194,1739502664.2944531,24.61997652053833,0.38744640035374084,1739502664.294455,24.61997652053833,1.1645030302248467 +1739502664.3142893,24.639976501464844,48.566723563991665,1739502664.3142917,24.639976501464844,0.546308734635975,1739502664.3142946,24.639976501464844,48.657183595905714,1739502664.3142972,24.639976501464844,51.64428009636474,1739502664.3142986,24.639976501464844,3.0803889018219714,1739502664.3143,24.639976501464844,0.6888511657268808,1739502664.3143015,24.639976501464844,1.1834674553019429,1739502664.3143027,24.639976501464844,0.5651116005608319,1739502664.314304,24.639976501464844,0.9699766961437273,1739502664.3143055,24.639976501464844,0.0,1739502664.3143065,24.639976501464844,-0.1945263340811194,1739502664.3143082,24.639976501464844,0.38744640035374084,1739502664.3143094,24.639976501464844,1.1645030302248467 +1739502664.3343737,24.659976482391357,48.566723563991665,1739502664.3343759,24.659976482391357,0.546308734635975,1739502664.3343787,24.659976482391357,48.657183595905714,1739502664.3343813,24.659976482391357,51.64428009636474,1739502664.3343825,24.659976482391357,3.0803889018219714,1739502664.3343842,24.659976482391357,0.6888511657268808,1739502664.3343856,24.659976482391357,1.1834674553019429,1739502664.3343868,24.659976482391357,0.5651116005608319,1739502664.334388,24.659976482391357,0.9699766961437273,1739502664.3343894,24.659976482391357,0.0,1739502664.3343909,24.659976482391357,-0.1945263340811194,1739502664.334392,24.659976482391357,0.38744640035374084,1739502664.3343933,24.659976482391357,1.1645030302248467 +1739502664.3543823,24.67997646331787,48.566723563991665,1739502664.3543854,24.67997646331787,0.546308734635975,1739502664.3543882,24.67997646331787,48.657183595905714,1739502664.354391,24.67997646331787,51.64428009636474,1739502664.3543923,24.67997646331787,3.0803889018219714,1739502664.3543942,24.67997646331787,0.6888511657268808,1739502664.3543956,24.67997646331787,1.1834674553019429,1739502664.3543973,24.67997646331787,0.5651116005608319,1739502664.3543985,24.67997646331787,0.9699766961437273,1739502664.3544004,24.67997646331787,0.0,1739502664.3544016,24.67997646331787,-0.1945263340811194,1739502664.354403,24.67997646331787,0.38744640035374084,1739502664.3544047,24.67997646331787,1.1645030302248467 +1739502664.374576,24.699976444244385,48.566723563991665,1739502664.374579,24.699976444244385,0.546308734635975,1739502664.3745825,24.699976444244385,48.657183595905714,1739502664.3745856,24.699976444244385,51.64428009636474,1739502664.3745875,24.699976444244385,3.0803889018219714,1739502664.3745894,24.699976444244385,0.6888511657268808,1739502664.3745914,24.699976444244385,1.1834674553019429,1739502664.3745928,24.699976444244385,0.5651116005608319,1739502664.3745942,24.699976444244385,0.9699766961437273,1739502664.374596,24.699976444244385,0.0,1739502664.3745975,24.699976444244385,-0.1945263340811194,1739502664.3745995,24.699976444244385,0.38744640035374084,1739502664.374601,24.699976444244385,1.1645030302248467 +1739502664.3955963,24.7199764251709,48.683595931475715,1739502664.3956,24.7199764251709,0.5955187081804221,1739502664.395605,24.7199764251709,48.755716481012385,1739502664.3956094,24.7199764251709,51.65609540563555,1739502664.3956113,24.7199764251709,3.1220958454288774,1739502664.3956141,24.7199764251709,0.7044848035091011,1739502664.3956165,24.7199764251709,1.1243571893332187,1739502664.3956187,24.7199764251709,0.5607510859519873,1739502664.3956206,24.7199764251709,1.0169469784001532,1739502664.3956234,24.7199764251709,0.0,1739502664.3956254,24.7199764251709,-0.08607245059535884,1739502664.3956277,24.7199764251709,0.41212970365060864,1739502664.3956301,24.7199764251709,1.1369112898060478 +1739502664.4162767,24.739976406097412,48.683595931475715,1739502664.4162803,24.739976406097412,0.5955187081804221,1739502664.416285,24.739976406097412,48.755716481012385,1739502664.4162896,24.739976406097412,51.65609540563555,1739502664.416292,24.739976406097412,3.1220958454288774,1739502664.4162946,24.739976406097412,0.7044848035091011,1739502664.416297,24.739976406097412,1.1243571893332187,1739502664.4162993,24.739976406097412,0.5607510859519873,1739502664.4163013,24.739976406097412,1.0169469784001532,1739502664.4163036,24.739976406097412,0.0,1739502664.416306,24.739976406097412,-0.11996431140589459,1739502664.4163082,24.739976406097412,0.41212970365060864,1739502664.4163105,24.739976406097412,1.1369112898060478 +1739502664.4361613,24.759976387023926,48.683595931475715,1739502664.436165,24.759976387023926,0.5955187081804221,1739502664.43617,24.759976387023926,48.755716481012385,1739502664.4361746,24.759976387023926,51.65609540563555,1739502664.4361765,24.759976387023926,3.1220958454288774,1739502664.4361792,24.759976387023926,0.7044848035091011,1739502664.4361815,24.759976387023926,1.1243571893332187,1739502664.4361837,24.759976387023926,0.5607510859519873,1739502664.4361858,24.759976387023926,1.0169469784001532,1739502664.4361882,24.759976387023926,0.0,1739502664.4361904,24.759976387023926,-0.11996431140589459,1739502664.4361928,24.759976387023926,0.41212970365060864,1739502664.4361951,24.759976387023926,1.1369112898060478 +1739502664.4558392,24.77997636795044,48.683595931475715,1739502664.4558427,24.77997636795044,0.5955187081804221,1739502664.4558477,24.77997636795044,48.755716481012385,1739502664.455852,24.77997636795044,51.65609540563555,1739502664.4558544,24.77997636795044,3.1220958454288774,1739502664.455857,24.77997636795044,0.7044848035091011,1739502664.4558594,24.77997636795044,1.1243571893332187,1739502664.4558618,24.77997636795044,0.5607510859519873,1739502664.4558637,24.77997636795044,1.0169469784001532,1739502664.455866,24.77997636795044,0.0,1739502664.4558685,24.77997636795044,-0.11996431140589459,1739502664.4558706,24.77997636795044,0.41212970365060864,1739502664.455873,24.77997636795044,1.1369112898060478 +1739502664.4754665,24.799976348876953,48.683595931475715,1739502664.4754698,24.799976348876953,0.5955187081804221,1739502664.4754739,24.799976348876953,48.755716481012385,1739502664.4754777,24.799976348876953,51.65609540563555,1739502664.4754796,24.799976348876953,3.1220958454288774,1739502664.4754817,24.799976348876953,0.7044848035091011,1739502664.4754837,24.799976348876953,1.1243571893332187,1739502664.4754858,24.799976348876953,0.5607510859519873,1739502664.4754872,24.799976348876953,1.0169469784001532,1739502664.4754894,24.799976348876953,0.0,1739502664.4754913,24.799976348876953,-0.11996431140589459,1739502664.4754932,24.799976348876953,0.41212970365060864,1739502664.475495,24.799976348876953,1.1369112898060478 +1739502664.4952419,24.819976329803467,48.79692305836316,1739502664.4952447,24.819976329803467,0.6465985020879206,1739502664.495248,24.819976329803467,48.875778852142396,1739502664.4952512,24.819976329803467,51.68044343684398,1739502664.4952528,24.819976329803467,3.2109592684279256,1739502664.4952548,24.819976329803467,0.726880874946547,1739502664.4952564,24.819976329803467,1.1026004156299587,1739502664.4952579,24.819976329803467,0.5620094181472438,1739502664.4952593,24.819976329803467,1.0348023055788271,1739502664.4952614,24.819976329803467,0.0,1739502664.4952629,24.819976329803467,-0.0736848351770936,1739502664.4952648,24.819976329803467,0.43710887044253477,1739502664.4952662,24.819976329803467,1.1229494865596739 +1739502664.5147557,24.83997631072998,48.79692305836316,1739502664.514759,24.83997631072998,0.6465985020879206,1739502664.5147626,24.83997631072998,48.875778852142396,1739502664.5147665,24.83997631072998,51.68044343684398,1739502664.514768,24.83997631072998,3.2109592684279256,1739502664.5147703,24.83997631072998,0.726880874946547,1739502664.5147717,24.83997631072998,1.1026004156299587,1739502664.5147731,24.83997631072998,0.5620094181472438,1739502664.5147748,24.83997631072998,1.0348023055788271,1739502664.5147765,24.83997631072998,0.0,1739502664.5147784,24.83997631072998,-0.08814718098084673,1739502664.5147798,24.83997631072998,0.43710887044253477,1739502664.5147817,24.83997631072998,1.1229494865596739 +1739502664.5347238,24.859976291656494,48.79692305836316,1739502664.5347269,24.859976291656494,0.6465985020879206,1739502664.534731,24.859976291656494,48.875778852142396,1739502664.5347342,24.859976291656494,51.68044343684398,1739502664.534736,24.859976291656494,3.2109592684279256,1739502664.5347385,24.859976291656494,0.726880874946547,1739502664.53474,24.859976291656494,1.1026004156299587,1739502664.5347419,24.859976291656494,0.5620094181472438,1739502664.5347433,24.859976291656494,1.0348023055788271,1739502664.534745,24.859976291656494,0.0,1739502664.5347466,24.859976291656494,-0.08814718098084673,1739502664.5347483,24.859976291656494,0.43710887044253477,1739502664.5347502,24.859976291656494,1.1229494865596739 +1739502664.5550058,24.879976272583008,48.79692305836316,1739502664.5550084,24.879976272583008,0.6465985020879206,1739502664.555012,24.879976272583008,48.875778852142396,1739502664.5550156,24.879976272583008,51.68044343684398,1739502664.5550172,24.879976272583008,3.2109592684279256,1739502664.5550194,24.879976272583008,0.726880874946547,1739502664.5550208,24.879976272583008,1.1026004156299587,1739502664.5550225,24.879976272583008,0.5620094181472438,1739502664.5550241,24.879976272583008,1.0348023055788271,1739502664.5550258,24.879976272583008,0.0,1739502664.5550275,24.879976272583008,-0.08814718098084673,1739502664.5550292,24.879976272583008,0.43710887044253477,1739502664.555031,24.879976272583008,1.1229494865596739 +1739502664.5749385,24.89997625350952,48.79692305836316,1739502664.5749419,24.89997625350952,0.6465985020879206,1739502664.5749454,24.89997625350952,48.875778852142396,1739502664.5749497,24.89997625350952,51.68044343684398,1739502664.5749512,24.89997625350952,3.2109592684279256,1739502664.5749533,24.89997625350952,0.726880874946547,1739502664.5749552,24.89997625350952,1.1026004156299587,1739502664.5749571,24.89997625350952,0.5620094181472438,1739502664.5749586,24.89997625350952,1.0348023055788271,1739502664.5749605,24.89997625350952,0.0,1739502664.5749621,24.89997625350952,-0.08814718098084673,1739502664.574964,24.89997625350952,0.43710887044253477,1739502664.5749655,24.89997625350952,1.1229494865596739 +1739502664.5949109,24.919976234436035,48.79692305836316,1739502664.5949137,24.919976234436035,0.6465985020879206,1739502664.5949173,24.919976234436035,48.875778852142396,1739502664.5949209,24.919976234436035,51.68044343684398,1739502664.5949225,24.919976234436035,3.2109592684279256,1739502664.5949242,24.919976234436035,0.726880874946547,1739502664.594926,24.919976234436035,1.1026004156299587,1739502664.5949275,24.919976234436035,0.5620094181472438,1739502664.5949292,24.919976234436035,1.0348023055788271,1739502664.594931,24.919976234436035,0.0,1739502664.5949326,24.919976234436035,-0.08814718098084673,1739502664.594934,24.919976234436035,0.43710887044253477,1739502664.594936,24.919976234436035,1.1229494865596739 +1739502664.6148605,24.93997621536255,48.907819569870256,1739502664.614864,24.93997621536255,0.6999551789829823,1739502664.6148677,24.93997621536255,49.01794893409945,1739502664.614871,24.93997621536255,51.70941343662869,1739502664.6148727,24.93997621536255,3.330906287368168,1739502664.6148746,24.93997621536255,0.7539972877438939,1739502664.6148765,24.93997621536255,1.106024999280327,1739502664.614878,24.93997621536255,0.568178301156633,1739502664.6148794,24.93997621536255,1.0319711718856721,1739502664.6148813,24.93997621536255,0.0,1739502664.6148827,24.93997621536255,-0.07863042366268114,1739502664.6148849,24.93997621536255,0.4620880372344609,1739502664.6148868,24.93997621536255,1.1135755841601789 +1739502664.6346693,24.959976196289062,48.907819569870256,1739502664.6346726,24.959976196289062,0.6999551789829823,1739502664.6346762,24.959976196289062,49.01794893409945,1739502664.6346798,24.959976196289062,51.70941343662869,1739502664.6346817,24.959976196289062,3.330906287368168,1739502664.6346834,24.959976196289062,0.7539972877438939,1739502664.6346853,24.959976196289062,1.106024999280327,1739502664.6346867,24.959976196289062,0.568178301156633,1739502664.6346881,24.959976196289062,1.0319711718856721,1739502664.63469,24.959976196289062,0.0,1739502664.6346915,24.959976196289062,-0.08160441227450677,1739502664.6346934,24.959976196289062,0.4620880372344609,1739502664.6346948,24.959976196289062,1.1135755841601789 +1739502664.6550086,24.979976177215576,48.907819569870256,1739502664.6550114,24.979976177215576,0.6999551789829823,1739502664.655015,24.979976177215576,49.01794893409945,1739502664.6550183,24.979976177215576,51.70941343662869,1739502664.6550198,24.979976177215576,3.330906287368168,1739502664.655022,24.979976177215576,0.7539972877438939,1739502664.6550236,24.979976177215576,1.106024999280327,1739502664.6550252,24.979976177215576,0.568178301156633,1739502664.6550267,24.979976177215576,1.0319711718856721,1739502664.6550286,24.979976177215576,0.0,1739502664.65503,24.979976177215576,-0.08160441227450677,1739502664.6550314,24.979976177215576,0.4620880372344609,1739502664.6550333,24.979976177215576,1.1135755841601789 +1739502664.6747694,24.99997615814209,48.907819569870256,1739502664.6747725,24.99997615814209,0.6999551789829823,1739502664.674776,24.99997615814209,49.01794893409945,1739502664.6747794,24.99997615814209,51.70941343662869,1739502664.6747808,24.99997615814209,3.330906287368168,1739502664.674783,24.99997615814209,0.7539972877438939,1739502664.6747847,24.99997615814209,1.106024999280327,1739502664.6747866,24.99997615814209,0.568178301156633,1739502664.674788,24.99997615814209,1.0319711718856721,1739502664.67479,24.99997615814209,0.0,1739502664.6747916,24.99997615814209,-0.08160441227450677,1739502664.6747935,24.99997615814209,0.4620880372344609,1739502664.674795,24.99997615814209,1.1135755841601789 +1739502664.695547,25.019976139068604,48.907819569870256,1739502664.6955504,25.019976139068604,0.6999551789829823,1739502664.6955545,25.019976139068604,49.01794893409945,1739502664.6955578,25.019976139068604,51.70941343662869,1739502664.6955597,25.019976139068604,3.330906287368168,1739502664.695562,25.019976139068604,0.7539972877438939,1739502664.6955638,25.019976139068604,1.106024999280327,1739502664.6955655,25.019976139068604,0.568178301156633,1739502664.6955671,25.019976139068604,1.0319711718856721,1739502664.6955688,25.019976139068604,0.0,1739502664.6955707,25.019976139068604,-0.08160441227450677,1739502664.6955724,25.019976139068604,0.4620880372344609,1739502664.6955743,25.019976139068604,1.1135755841601789 +1739502664.7148635,25.039976119995117,49.01643531628282,1739502664.7148666,25.039976119995117,0.7556035539725539,1739502664.7148702,25.039976119995117,49.19358522900819,1739502664.7148738,25.039976119995117,51.73976105396167,1739502664.7148757,25.039976119995117,3.4857046972176455,1739502664.7148778,25.039976119995117,0.7866405752291352,1739502664.7148795,25.039976119995117,1.1375285422339911,1739502664.7148812,25.039976119995117,0.5801656757992953,1739502664.7148826,25.039976119995117,1.0062875824652449,1739502664.7148845,25.039976119995117,0.0,1739502664.7148862,25.039976119995117,-0.10595400376330989,1739502664.7148879,25.039976119995117,0.48719539662995837,1739502664.7148898,25.039976119995117,1.1046323338992892 +1739502664.7347727,25.05997610092163,49.01643531628282,1739502664.7347755,25.05997610092163,0.7556035539725539,1739502664.734779,25.05997610092163,49.19358522900819,1739502664.7347822,25.05997610092163,51.73976105396167,1739502664.734784,25.05997610092163,3.4857046972176455,1739502664.734786,25.05997610092163,0.7866405752291352,1739502664.7347877,25.05997610092163,1.1375285422339911,1739502664.7347894,25.05997610092163,0.5801656757992953,1739502664.7347906,25.05997610092163,1.0062875824652449,1739502664.7347927,25.05997610092163,0.0,1739502664.7347941,25.05997610092163,-0.09834475143404431,1739502664.7347958,25.05997610092163,0.48719539662995837,1739502664.7347977,25.05997610092163,1.1046323338992892 +1739502664.75507,25.079976081848145,49.01643531628282,1739502664.7550728,25.079976081848145,0.7556035539725539,1739502664.7550762,25.079976081848145,49.19358522900819,1739502664.7550797,25.079976081848145,51.73976105396167,1739502664.7550812,25.079976081848145,3.4857046972176455,1739502664.755083,25.079976081848145,0.7866405752291352,1739502664.7550848,25.079976081848145,1.1375285422339911,1739502664.7550867,25.079976081848145,0.5801656757992953,1739502664.755088,25.079976081848145,1.0062875824652449,1739502664.75509,25.079976081848145,0.0,1739502664.7550914,25.079976081848145,-0.09834475143404431,1739502664.7550933,25.079976081848145,0.48719539662995837,1739502664.7550948,25.079976081848145,1.1046323338992892 +1739502664.7748847,25.099976062774658,49.01643531628282,1739502664.7748876,25.099976062774658,0.7556035539725539,1739502664.7748914,25.099976062774658,49.19358522900819,1739502664.7748945,25.099976062774658,51.73976105396167,1739502664.7748964,25.099976062774658,3.4857046972176455,1739502664.7748985,25.099976062774658,0.7866405752291352,1739502664.7749002,25.099976062774658,1.1375285422339911,1739502664.7749019,25.099976062774658,0.5801656757992953,1739502664.7749033,25.099976062774658,1.0062875824652449,1739502664.7749054,25.099976062774658,0.0,1739502664.7749069,25.099976062774658,-0.09834475143404431,1739502664.7749088,25.099976062774658,0.48719539662995837,1739502664.7749104,25.099976062774658,1.1046323338992892 +1739502664.7951875,25.119976043701172,49.01643531628282,1739502664.7951903,25.119976043701172,0.7556035539725539,1739502664.795194,25.119976043701172,49.19358522900819,1739502664.795197,25.119976043701172,51.73976105396167,1739502664.7951987,25.119976043701172,3.4857046972176455,1739502664.7952006,25.119976043701172,0.7866405752291352,1739502664.7952023,25.119976043701172,1.1375285422339911,1739502664.795204,25.119976043701172,0.5801656757992953,1739502664.7952054,25.119976043701172,1.0062875824652449,1739502664.7952073,25.119976043701172,0.0,1739502664.7952087,25.119976043701172,-0.09834475143404431,1739502664.7952106,25.119976043701172,0.48719539662995837,1739502664.7952123,25.119976043701172,1.1046323338992892 +1739502664.8148427,25.139976024627686,49.01643531628282,1739502664.814846,25.139976024627686,0.7556035539725539,1739502664.8148499,25.139976024627686,49.19358522900819,1739502664.8148532,25.139976024627686,51.73976105396167,1739502664.8148546,25.139976024627686,3.4857046972176455,1739502664.8148568,25.139976024627686,0.7866405752291352,1739502664.8148587,25.139976024627686,1.1375285422339911,1739502664.8148606,25.139976024627686,0.5801656757992953,1739502664.814862,25.139976024627686,1.0062875824652449,1739502664.814864,25.139976024627686,0.0,1739502664.8148656,25.139976024627686,-0.09834475143404431,1739502664.8148673,25.139976024627686,0.48719539662995837,1739502664.8148687,25.139976024627686,1.1046323338992892 +1739502664.834837,25.1599760055542,49.12265197621588,1739502664.83484,25.1599760055542,0.8134606016487069,1739502664.8348439,25.1599760055542,49.30238197771366,1739502664.8348472,25.1599760055542,51.75364381999208,1739502664.834849,25.1599760055542,3.571525432678283,1739502664.8348508,25.1599760055542,0.8089736148313283,1739502664.8348527,25.1599760055542,1.1124035818708469,1739502664.8348544,25.1599760055542,0.580651599409126,1739502664.8348558,25.1599760055542,1.0267185742538691,1739502664.8348577,25.1599760055542,0.0,1739502664.8348594,25.1599760055542,-0.052728463481064594,1739502664.834861,25.1599760055542,0.5128242215510951,1739502664.8348627,25.1599760055542,1.0937021370666113 +1739502664.8550792,25.179975986480713,49.12265197621588,1739502664.855082,25.179975986480713,0.8134606016487069,1739502664.8550854,25.179975986480713,49.30238197771366,1739502664.8550887,25.179975986480713,51.75364381999208,1739502664.8550901,25.179975986480713,3.571525432678283,1739502664.8550923,25.179975986480713,0.8089736148313283,1739502664.855094,25.179975986480713,1.1124035818708469,1739502664.8550956,25.179975986480713,0.580651599409126,1739502664.855097,25.179975986480713,1.0267185742538691,1739502664.855099,25.179975986480713,0.0,1739502664.8551004,25.179975986480713,-0.0669835628127422,1739502664.8551023,25.179975986480713,0.5128242215510951,1739502664.8551037,25.179975986480713,1.0937021370666113 +1739502664.874848,25.199975967407227,49.12265197621588,1739502664.874851,25.199975967407227,0.8134606016487069,1739502664.8748546,25.199975967407227,49.30238197771366,1739502664.8748577,25.199975967407227,51.75364381999208,1739502664.8748596,25.199975967407227,3.571525432678283,1739502664.8748617,25.199975967407227,0.8089736148313283,1739502664.8748634,25.199975967407227,1.1124035818708469,1739502664.874865,25.199975967407227,0.580651599409126,1739502664.8748667,25.199975967407227,1.0267185742538691,1739502664.8748684,25.199975967407227,0.0,1739502664.8748703,25.199975967407227,-0.0669835628127422,1739502664.8748717,25.199975967407227,0.5128242215510951,1739502664.8748736,25.199975967407227,1.0937021370666113 +1739502664.8950999,25.21997594833374,49.12265197621588,1739502664.8951027,25.21997594833374,0.8134606016487069,1739502664.8951066,25.21997594833374,49.30238197771366,1739502664.8951097,25.21997594833374,51.75364381999208,1739502664.895111,25.21997594833374,3.571525432678283,1739502664.8951132,25.21997594833374,0.8089736148313283,1739502664.895115,25.21997594833374,1.1124035818708469,1739502664.8951168,25.21997594833374,0.580651599409126,1739502664.8951182,25.21997594833374,1.0267185742538691,1739502664.8951201,25.21997594833374,0.0,1739502664.8951218,25.21997594833374,-0.0669835628127422,1739502664.8951237,25.21997594833374,0.5128242215510951,1739502664.8951252,25.21997594833374,1.0937021370666113 +1739502664.9148085,25.239975929260254,49.12265197621588,1739502664.9148118,25.239975929260254,0.8134606016487069,1739502664.9148154,25.239975929260254,49.30238197771366,1739502664.9148185,25.239975929260254,51.75364381999208,1739502664.9148204,25.239975929260254,3.571525432678283,1739502664.9148223,25.239975929260254,0.8089736148313283,1739502664.914824,25.239975929260254,1.1124035818708469,1739502664.9148254,25.239975929260254,0.580651599409126,1739502664.914827,25.239975929260254,1.0267185742538691,1739502664.9148288,25.239975929260254,0.0,1739502664.9148304,25.239975929260254,-0.0669835628127422,1739502664.914832,25.239975929260254,0.5128242215510951,1739502664.914834,25.239975929260254,1.0937021370666113 +1739502664.934942,25.259975910186768,49.22645589044781,1739502664.9349453,25.259975910186768,0.8735267995967755,1739502664.9349487,25.259975910186768,49.4770610227397,1739502664.934952,25.259975910186768,51.777948850596,1739502664.9349535,25.259975910186768,3.7296112645295554,1739502664.9349556,25.259975910186768,0.8416655019986481,1739502664.9349573,25.259975910186768,1.1425172503771983,1739502664.934959,25.259975910186768,0.5904906477313316,1739502664.9349604,25.259975910186768,1.0022795257496366,1739502664.9349625,25.259975910186768,0.0,1739502664.9349637,25.259975910186768,-0.09182294859592002,1739502664.9349656,25.259975910186768,0.5387300305509897,1739502664.9349673,25.259975910186768,1.0863401611989445 +1739502664.9550962,25.27997589111328,49.22645589044781,1739502664.955099,25.27997589111328,0.8735267995967755,1739502664.9551024,25.27997589111328,49.4770610227397,1739502664.955106,25.27997589111328,51.777948850596,1739502664.955108,25.27997589111328,3.7296112645295554,1739502664.9551096,25.27997589111328,0.8416655019986481,1739502664.9551113,25.27997589111328,1.1425172503771983,1739502664.955113,25.27997589111328,0.5904906477313316,1739502664.9551146,25.27997589111328,1.0022795257496366,1739502664.9551163,25.27997589111328,0.0,1739502664.9551182,25.27997589111328,-0.08406063544930786,1739502664.9551198,25.27997589111328,0.5387300305509897,1739502664.9551215,25.27997589111328,1.0863401611989445 +1739502664.9747791,25.299975872039795,49.22645589044781,1739502664.974782,25.299975872039795,0.8735267995967755,1739502664.9747856,25.299975872039795,49.4770610227397,1739502664.974789,25.299975872039795,51.777948850596,1739502664.9747906,25.299975872039795,3.7296112645295554,1739502664.9747927,25.299975872039795,0.8416655019986481,1739502664.9747944,25.299975872039795,1.1425172503771983,1739502664.974796,25.299975872039795,0.5904906477313316,1739502664.9747975,25.299975872039795,1.0022795257496366,1739502664.9747996,25.299975872039795,0.0,1739502664.974801,25.299975872039795,-0.08406063544930786,1739502664.974803,25.299975872039795,0.5387300305509897,1739502664.9748044,25.299975872039795,1.0863401611989445 +1739502664.9951544,25.31997585296631,49.22645589044781,1739502664.995157,25.31997585296631,0.8735267995967755,1739502664.9951603,25.31997585296631,49.4770610227397,1739502664.9951637,25.31997585296631,51.777948850596,1739502664.995165,25.31997585296631,3.7296112645295554,1739502664.995167,25.31997585296631,0.8416655019986481,1739502664.9951684,25.31997585296631,1.1425172503771983,1739502664.9951704,25.31997585296631,0.5904906477313316,1739502664.9951718,25.31997585296631,1.0022795257496366,1739502664.9951737,25.31997585296631,0.0,1739502664.9951751,25.31997585296631,-0.08406063544930786,1739502664.995177,25.31997585296631,0.5387300305509897,1739502664.9951785,25.31997585296631,1.0863401611989445 +1739502665.014897,25.339975833892822,49.22645589044781,1739502665.0149004,25.339975833892822,0.8735267995967755,1739502665.0149038,25.339975833892822,49.4770610227397,1739502665.0149074,25.339975833892822,51.777948850596,1739502665.014909,25.339975833892822,3.7296112645295554,1739502665.0149107,25.339975833892822,0.8416655019986481,1739502665.0149126,25.339975833892822,1.1425172503771983,1739502665.014914,25.339975833892822,0.5904906477313316,1739502665.0149155,25.339975833892822,1.0022795257496366,1739502665.0149176,25.339975833892822,0.0,1739502665.0149195,25.339975833892822,-0.08406063544930786,1739502665.014921,25.339975833892822,0.5387300305509897,1739502665.0149229,25.339975833892822,1.0863401611989445 +1739502665.0347545,25.359975814819336,49.22645589044781,1739502665.034758,25.359975814819336,0.8735267995967755,1739502665.0347614,25.359975814819336,49.4770610227397,1739502665.0347648,25.359975814819336,51.777948850596,1739502665.0347664,25.359975814819336,3.7296112645295554,1739502665.0347683,25.359975814819336,0.8416655019986481,1739502665.03477,25.359975814819336,1.1425172503771983,1739502665.0347714,25.359975814819336,0.5904906477313316,1739502665.0347729,25.359975814819336,1.0022795257496366,1739502665.034775,25.359975814819336,0.0,1739502665.0347767,25.359975814819336,-0.08406063544930786,1739502665.0347786,25.359975814819336,0.5387300305509897,1739502665.0347805,25.359975814819336,1.0863401611989445 +1739502665.0551012,25.37997579574585,49.327881343302934,1739502665.055104,25.37997579574585,0.9358016060050476,1739502665.0551076,25.37997579574585,49.569256887526045,1739502665.055111,25.37997579574585,51.786836462308294,1739502665.0551126,25.37997579574585,3.802528160774692,1739502665.0551145,25.37997579574585,0.861816056538829,1739502665.0551162,25.37997579574585,1.1044024000763257,1739502665.0551178,25.37997579574585,0.5869986716544966,1739502665.0551193,25.37997579574585,1.0333116221845278,1739502665.0551212,25.37997579574585,0.0,1739502665.0551226,25.37997579574585,-0.025297132866957773,1739502665.0551245,25.37997579574585,0.5650660921102498,1739502665.0551262,25.37997579574585,1.0769723616485887 +1739502665.0748136,25.399975776672363,49.327881343302934,1739502665.0748167,25.399975776672363,0.9358016060050476,1739502665.0748203,25.399975776672363,49.569256887526045,1739502665.0748236,25.399975776672363,51.786836462308294,1739502665.0748253,25.399975776672363,3.802528160774692,1739502665.0748274,25.399975776672363,0.861816056538829,1739502665.0748293,25.399975776672363,1.1044024000763257,1739502665.0748308,25.399975776672363,0.5869986716544966,1739502665.0748324,25.399975776672363,1.0333116221845278,1739502665.0748343,25.399975776672363,0.0,1739502665.074836,25.399975776672363,-0.043660739464060905,1739502665.0748374,25.399975776672363,0.5650660921102498,1739502665.0748394,25.399975776672363,1.0769723616485887 +1739502665.0951684,25.419975757598877,49.327881343302934,1739502665.095171,25.419975757598877,0.9358016060050476,1739502665.0951743,25.419975757598877,49.569256887526045,1739502665.0951777,25.419975757598877,51.786836462308294,1739502665.0951793,25.419975757598877,3.802528160774692,1739502665.095181,25.419975757598877,0.861816056538829,1739502665.095183,25.419975757598877,1.1044024000763257,1739502665.0951846,25.419975757598877,0.5869986716544966,1739502665.0951865,25.419975757598877,1.0333116221845278,1739502665.0951881,25.419975757598877,0.0,1739502665.0951898,25.419975757598877,-0.043660739464060905,1739502665.0951915,25.419975757598877,0.5650660921102498,1739502665.0951931,25.419975757598877,1.0769723616485887 +1739502665.1148171,25.43997573852539,49.327881343302934,1739502665.11482,25.43997573852539,0.9358016060050476,1739502665.1148236,25.43997573852539,49.569256887526045,1739502665.1148267,25.43997573852539,51.786836462308294,1739502665.1148286,25.43997573852539,3.802528160774692,1739502665.1148305,25.43997573852539,0.861816056538829,1739502665.1148324,25.43997573852539,1.1044024000763257,1739502665.114834,25.43997573852539,0.5869986716544966,1739502665.1148355,25.43997573852539,1.0333116221845278,1739502665.1148374,25.43997573852539,0.0,1739502665.114839,25.43997573852539,-0.043660739464060905,1739502665.1148407,25.43997573852539,0.5650660921102498,1739502665.1148427,25.43997573852539,1.0769723616485887 +1739502665.1348033,25.459975719451904,49.327881343302934,1739502665.1348062,25.459975719451904,0.9358016060050476,1739502665.13481,25.459975719451904,49.569256887526045,1739502665.134813,25.459975719451904,51.786836462308294,1739502665.1348152,25.459975719451904,3.802528160774692,1739502665.1348176,25.459975719451904,0.861816056538829,1739502665.1348193,25.459975719451904,1.1044024000763257,1739502665.134821,25.459975719451904,0.5869986716544966,1739502665.1348228,25.459975719451904,1.0333116221845278,1739502665.1348248,25.459975719451904,0.0,1739502665.1348262,25.459975719451904,-0.043660739464060905,1739502665.134828,25.459975719451904,0.5650660921102498,1739502665.1348295,25.459975719451904,1.0769723616485887 +1739502665.1552668,25.479975700378418,49.426953670347736,1739502665.1552696,25.479975700378418,1.0002963303879087,1739502665.1552732,25.479975700378418,49.659721030065214,1739502665.1552765,25.479975700378418,51.795256104163116,1739502665.1552784,25.479975700378418,3.8829224582991335,1739502665.1552804,25.479975700378418,0.8830358060405308,1739502665.155282,25.479975700378418,1.072332171463286,1739502665.1552837,25.479975700378418,0.5842016686667225,1739502665.1552854,25.479975700378418,1.0601654646873961,1739502665.155287,25.479975700378418,0.0,1739502665.1552885,25.479975700378418,0.0024029830275208615,1739502665.1552904,25.479975700378418,0.5914913851163595,1739502665.1552918,25.479975700378418,1.0721574043765414 +1739502665.1747944,25.49997568130493,49.426953670347736,1739502665.1747973,25.49997568130493,1.0002963303879087,1739502665.1748009,25.49997568130493,49.659721030065214,1739502665.174804,25.49997568130493,51.795256104163116,1739502665.1748056,25.49997568130493,3.8829224582991335,1739502665.1748078,25.49997568130493,0.8830358060405308,1739502665.1748095,25.49997568130493,1.072332171463286,1739502665.1748111,25.49997568130493,0.5842016686667225,1739502665.1748126,25.49997568130493,1.0601654646873961,1739502665.1748147,25.49997568130493,0.0,1739502665.1748164,25.49997568130493,-0.011991939689145248,1739502665.1748178,25.49997568130493,0.5914913851163595,1739502665.1748195,25.49997568130493,1.0721574043765414 +1739502665.195262,25.519975662231445,49.426953670347736,1739502665.1952648,25.519975662231445,1.0002963303879087,1739502665.1952682,25.519975662231445,49.659721030065214,1739502665.1952717,25.519975662231445,51.795256104163116,1739502665.1952732,25.519975662231445,3.8829224582991335,1739502665.1952753,25.519975662231445,0.8830358060405308,1739502665.1952767,25.519975662231445,1.072332171463286,1739502665.1952784,25.519975662231445,0.5842016686667225,1739502665.1952798,25.519975662231445,1.0601654646873961,1739502665.1952817,25.519975662231445,0.0,1739502665.1952832,25.519975662231445,-0.011991939689145248,1739502665.195285,25.519975662231445,0.5914913851163595,1739502665.1952865,25.519975662231445,1.0721574043765414 +1739502665.2149124,25.53997564315796,49.426953670347736,1739502665.2149155,25.53997564315796,1.0002963303879087,1739502665.2149193,25.53997564315796,49.659721030065214,1739502665.2149227,25.53997564315796,51.795256104163116,1739502665.2149246,25.53997564315796,3.8829224582991335,1739502665.214927,25.53997564315796,0.8830358060405308,1739502665.2149284,25.53997564315796,1.072332171463286,1739502665.21493,25.53997564315796,0.5842016686667225,1739502665.2149317,25.53997564315796,1.0601654646873961,1739502665.2149334,25.53997564315796,0.0,1739502665.214935,25.53997564315796,-0.011991939689145248,1739502665.2149367,25.53997564315796,0.5914913851163595,1739502665.2149386,25.53997564315796,1.0721574043765414 +1739502665.2348151,25.559975624084473,49.426953670347736,1739502665.2348182,25.559975624084473,1.0002963303879087,1739502665.2348218,25.559975624084473,49.659721030065214,1739502665.2348251,25.559975624084473,51.795256104163116,1739502665.234827,25.559975624084473,3.8829224582991335,1739502665.234829,25.559975624084473,0.8830358060405308,1739502665.2348306,25.559975624084473,1.072332171463286,1739502665.2348323,25.559975624084473,0.5842016686667225,1739502665.2348337,25.559975624084473,1.0601654646873961,1739502665.2348354,25.559975624084473,0.0,1739502665.234837,25.559975624084473,-0.011991939689145248,1739502665.2348385,25.559975624084473,0.5914913851163595,1739502665.2348404,25.559975624084473,1.0721574043765414 +1739502665.2549858,25.579975605010986,49.426953670347736,1739502665.2549884,25.579975605010986,1.0002963303879087,1739502665.2549918,25.579975605010986,49.659721030065214,1739502665.254995,25.579975605010986,51.795256104163116,1739502665.2549968,25.579975605010986,3.8829224582991335,1739502665.2549987,25.579975605010986,0.8830358060405308,1739502665.2550004,25.579975605010986,1.072332171463286,1739502665.2550018,25.579975605010986,0.5842016686667225,1739502665.2550035,25.579975605010986,1.0601654646873961,1739502665.2550054,25.579975605010986,0.0,1739502665.2550068,25.579975605010986,-0.011991939689145248,1739502665.2550085,25.579975605010986,0.5914913851163595,1739502665.2550101,25.579975605010986,1.0721574043765414 +1739502665.2750514,25.5999755859375,49.524023287387024,1739502665.275054,25.5999755859375,1.0672052731387556,1739502665.2750583,25.5999755859375,49.772459251743186,1739502665.2750616,25.5999755859375,51.803949680835466,1739502665.275063,25.5999755859375,3.9932452125319795,1739502665.2750654,25.5999755859375,0.9088769558279619,1739502665.2750669,25.5999755859375,1.0641288723820141,1739502665.2750688,25.5999755859375,0.5863595637869147,1739502665.2750702,25.5999755859375,1.0671458279437223,1739502665.275072,25.5999755859375,0.0,1739502665.2750735,25.5999755859375,-0.0003427369742076414,1739502665.2750754,25.5999755859375,0.6179166781224691,1739502665.2750769,25.5999755859375,1.0711289431531659 +1739502665.2956662,25.619975566864014,49.524023287387024,1739502665.29567,25.619975566864014,1.0672052731387556,1739502665.2956738,25.619975566864014,49.772459251743186,1739502665.2956774,25.619975566864014,51.803949680835466,1739502665.2956796,25.619975566864014,3.9932452125319795,1739502665.2956815,25.619975566864014,0.9088769558279619,1739502665.2956834,25.619975566864014,1.0641288723820141,1739502665.2956848,25.619975566864014,0.5863595637869147,1739502665.2956865,25.619975566864014,1.0671458279437223,1739502665.2956884,25.619975566864014,0.0,1739502665.29569,25.619975566864014,-0.003983115209443611,1739502665.295692,25.619975566864014,0.6179166781224691,1739502665.2956939,25.619975566864014,1.0711289431531659 +1739502665.3148263,25.639975547790527,49.524023287387024,1739502665.3148293,25.639975547790527,1.0672052731387556,1739502665.314833,25.639975547790527,49.772459251743186,1739502665.3148363,25.639975547790527,51.803949680835466,1739502665.314838,25.639975547790527,3.9932452125319795,1739502665.31484,25.639975547790527,0.9088769558279619,1739502665.3148417,25.639975547790527,1.0641288723820141,1739502665.3148434,25.639975547790527,0.5863595637869147,1739502665.3148448,25.639975547790527,1.0671458279437223,1739502665.3148468,25.639975547790527,0.0,1739502665.3148482,25.639975547790527,-0.003983115209443611,1739502665.31485,25.639975547790527,0.6179166781224691,1739502665.3148518,25.639975547790527,1.0711289431531659 +1739502665.3348012,25.65997552871704,49.524023287387024,1739502665.3348045,25.65997552871704,1.0672052731387556,1739502665.334808,25.65997552871704,49.772459251743186,1739502665.3348112,25.65997552871704,51.803949680835466,1739502665.3348126,25.65997552871704,3.9932452125319795,1739502665.3348148,25.65997552871704,0.9088769558279619,1739502665.3348165,25.65997552871704,1.0641288723820141,1739502665.3348184,25.65997552871704,0.5863595637869147,1739502665.3348198,25.65997552871704,1.0671458279437223,1739502665.3348217,25.65997552871704,0.0,1739502665.3348231,25.65997552871704,-0.003983115209443611,1739502665.3348248,25.65997552871704,0.6179166781224691,1739502665.3348265,25.65997552871704,1.0711289431531659 +1739502665.3547945,25.679975509643555,49.524023287387024,1739502665.3547971,25.679975509643555,1.0672052731387556,1739502665.3548002,25.679975509643555,49.772459251743186,1739502665.354803,25.679975509643555,51.803949680835466,1739502665.3548045,25.679975509643555,3.9932452125319795,1739502665.3548064,25.679975509643555,0.9088769558279619,1739502665.354808,25.679975509643555,1.0641288723820141,1739502665.3548095,25.679975509643555,0.5863595637869147,1739502665.3548107,25.679975509643555,1.0671458279437223,1739502665.3548124,25.679975509643555,0.0,1739502665.3548138,25.679975509643555,-0.003983115209443611,1739502665.3548152,25.679975509643555,0.6179166781224691,1739502665.3548164,25.679975509643555,1.0711289431531659 +1739502665.3750687,25.69997549057007,49.61921169543759,1739502665.375072,25.69997549057007,1.136597953711866,1739502665.3750758,25.69997549057007,49.91880703843801,1739502665.3750794,25.69997549057007,51.810741812497874,1739502665.3750813,25.69997549057007,4.138545312446753,1739502665.3750834,25.69997549057007,0.9401949818480234,1739502665.3750854,25.69997549057007,1.0836506781643336,1739502665.375087,25.69997549057007,0.594534868544838,1739502665.3750887,25.69997549057007,1.0506092030914038,1739502665.3750906,25.69997549057007,0.0,1739502665.3750925,25.69997549057007,-0.02739202623331777,1739502665.3750944,25.69997549057007,0.6443419711285787,1739502665.375096,25.69997549057007,1.0706859398334834 +1739502665.3965468,25.719975471496582,49.61921169543759,1739502665.3965545,25.719975471496582,1.136597953711866,1739502665.3965616,25.719975471496582,49.91880703843801,1739502665.396582,25.719975471496582,51.810741812497874,1739502665.3965847,25.719975471496582,4.138545312446753,1739502665.396589,25.719975471496582,0.9401949818480234,1739502665.3966,25.719975471496582,1.0836506781643336,1739502665.3966026,25.719975471496582,0.594534868544838,1739502665.3966062,25.719975471496582,1.0506092030914038,1739502665.3966093,25.719975471496582,0.0,1739502665.396613,25.719975471496582,-0.02007673674207955,1739502665.3966155,25.719975471496582,0.6443419711285787,1739502665.3966193,25.719975471496582,1.0706859398334834 +1739502665.4155843,25.739975452423096,49.61921169543759,1739502665.4155881,25.739975452423096,1.136597953711866,1739502665.4155927,25.739975452423096,49.91880703843801,1739502665.415597,25.739975452423096,51.810741812497874,1739502665.4155993,25.739975452423096,4.138545312446753,1739502665.415602,25.739975452423096,0.9401949818480234,1739502665.415604,25.739975452423096,1.0836506781643336,1739502665.4156065,25.739975452423096,0.594534868544838,1739502665.4156084,25.739975452423096,1.0506092030914038,1739502665.4156108,25.739975452423096,0.0,1739502665.4156132,25.739975452423096,-0.02007673674207955,1739502665.4156156,25.739975452423096,0.6443419711285787,1739502665.4156175,25.739975452423096,1.0706859398334834 +1739502665.4359295,25.75997543334961,49.61921169543759,1739502665.4359334,25.75997543334961,1.136597953711866,1739502665.4359381,25.75997543334961,49.91880703843801,1739502665.4359426,25.75997543334961,51.810741812497874,1739502665.435945,25.75997543334961,4.138545312446753,1739502665.4359474,25.75997543334961,0.9401949818480234,1739502665.4359496,25.75997543334961,1.0836506781643336,1739502665.435952,25.75997543334961,0.594534868544838,1739502665.4359539,25.75997543334961,1.0506092030914038,1739502665.4359565,25.75997543334961,0.0,1739502665.4359586,25.75997543334961,-0.02007673674207955,1739502665.4359608,25.75997543334961,0.6443419711285787,1739502665.4359632,25.75997543334961,1.0706859398334834 +1739502665.456201,25.779975414276123,49.61921169543759,1739502665.4562051,25.779975414276123,1.136597953711866,1739502665.4562097,25.779975414276123,49.91880703843801,1739502665.456214,25.779975414276123,51.810741812497874,1739502665.456216,25.779975414276123,4.138545312446753,1739502665.456219,25.779975414276123,0.9401949818480234,1739502665.456221,25.779975414276123,1.0836506781643336,1739502665.4562235,25.779975414276123,0.594534868544838,1739502665.4562254,25.779975414276123,1.0506092030914038,1739502665.456228,25.779975414276123,0.0,1739502665.4562302,25.779975414276123,-0.02007673674207955,1739502665.456233,25.779975414276123,0.6443419711285787,1739502665.4562352,25.779975414276123,1.0706859398334834 +1739502665.4756951,25.799975395202637,49.61921169543759,1739502665.4756982,25.799975395202637,1.136597953711866,1739502665.4757023,25.799975395202637,49.91880703843801,1739502665.4757059,25.799975395202637,51.810741812497874,1739502665.4757075,25.799975395202637,4.138545312446753,1739502665.47571,25.799975395202637,0.9401949818480234,1739502665.4757118,25.799975395202637,1.0836506781643336,1739502665.4757135,25.799975395202637,0.594534868544838,1739502665.4757156,25.799975395202637,1.0506092030914038,1739502665.4757178,25.799975395202637,0.0,1739502665.4757197,25.799975395202637,-0.02007673674207955,1739502665.4757214,25.799975395202637,0.6443419711285787,1739502665.4757235,25.799975395202637,1.0706859398334834 +1739502665.495275,25.81997537612915,49.71240745943211,1739502665.4952776,25.81997537612915,1.2084003688693334,1739502665.4952812,25.81997537612915,50.04159590211148,1739502665.4952846,25.81997537612915,51.81285789312185,1739502665.495286,25.81997537612915,4.256610749184268,1739502665.4952881,25.81997537612915,0.9674391884763198,1739502665.4952896,25.81997537612915,1.0811759575496105,1739502665.4952915,25.81997537612915,0.5978922203941561,1739502665.495293,25.81997537612915,1.0526912347923925,1739502665.4952948,25.81997537612915,0.0,1739502665.4952962,25.81997537612915,-0.01363612090851837,1739502665.4952981,25.81997537612915,0.6710528977786145,1739502665.4952998,25.81997537612915,1.0683400494685236 +1739502665.5148978,25.839975357055664,49.71240745943211,1739502665.5149012,25.839975357055664,1.2084003688693334,1739502665.5149047,25.839975357055664,50.04159590211148,1739502665.514908,25.839975357055664,51.81285789312185,1739502665.5149097,25.839975357055664,4.256610749184268,1739502665.5149117,25.839975357055664,0.9674391884763198,1739502665.5149136,25.839975357055664,1.0811759575496105,1739502665.514915,25.839975357055664,0.5978922203941561,1739502665.5149167,25.839975357055664,1.0526912347923925,1739502665.5149186,25.839975357055664,0.0,1739502665.5149202,25.839975357055664,-0.015648814676131106,1739502665.514922,25.839975357055664,0.6710528977786145,1739502665.5149238,25.839975357055664,1.0683400494685236 +1739502665.5348423,25.859975337982178,49.71240745943211,1739502665.5348456,25.859975337982178,1.2084003688693334,1739502665.5348492,25.859975337982178,50.04159590211148,1739502665.534853,25.859975337982178,51.81285789312185,1739502665.5348544,25.859975337982178,4.256610749184268,1739502665.5348566,25.859975337982178,0.9674391884763198,1739502665.5348582,25.859975337982178,1.0811759575496105,1739502665.5348597,25.859975337982178,0.5978922203941561,1739502665.5348613,25.859975337982178,1.0526912347923925,1739502665.534863,25.859975337982178,0.0,1739502665.534865,25.859975337982178,-0.015648814676131106,1739502665.5348666,25.859975337982178,0.6710528977786145,1739502665.5348682,25.859975337982178,1.0683400494685236 +1739502665.554776,25.87997531890869,49.71240745943211,1739502665.5547788,25.87997531890869,1.2084003688693334,1739502665.5547822,25.87997531890869,50.04159590211148,1739502665.5547855,25.87997531890869,51.81285789312185,1739502665.5547872,25.87997531890869,4.256610749184268,1739502665.554789,25.87997531890869,0.9674391884763198,1739502665.5547907,25.87997531890869,1.0811759575496105,1739502665.5547924,25.87997531890869,0.5978922203941561,1739502665.554794,25.87997531890869,1.0526912347923925,1739502665.5547957,25.87997531890869,0.0,1739502665.5547974,25.87997531890869,-0.015648814676131106,1739502665.554799,25.87997531890869,0.6710528977786145,1739502665.5548007,25.87997531890869,1.0683400494685236 +1739502665.5748277,25.899975299835205,49.71240745943211,1739502665.5748308,25.899975299835205,1.2084003688693334,1739502665.574834,25.899975299835205,50.04159590211148,1739502665.5748374,25.899975299835205,51.81285789312185,1739502665.5748394,25.899975299835205,4.256610749184268,1739502665.574841,25.899975299835205,0.9674391884763198,1739502665.574843,25.899975299835205,1.0811759575496105,1739502665.5748444,25.899975299835205,0.5978922203941561,1739502665.574846,25.899975299835205,1.0526912347923925,1739502665.5748477,25.899975299835205,0.0,1739502665.5748496,25.899975299835205,-0.015648814676131106,1739502665.5748513,25.899975299835205,0.6710528977786145,1739502665.574853,25.899975299835205,1.0683400494685236 +1739502665.5953119,25.91997528076172,49.803474371849575,1739502665.5953145,25.91997528076172,1.2825351033675005,1739502665.595318,25.91997528076172,50.158141787231315,1739502665.5953214,25.91997528076172,51.812038271014046,1739502665.595323,25.91997528076172,4.369718600061429,1739502665.5953252,25.91997528076172,0.9939897986668627,1739502665.5953267,25.91997528076172,1.0744962181625957,1739502665.5953286,25.91997528076172,0.6002001951720689,1739502665.59533,25.91997528076172,1.0583316544661376,1739502665.5953324,25.91997528076172,0.0,1739502665.5953338,25.91997528076172,-0.004946335861940527,1739502665.5953355,25.91997528076172,0.6979453675196218,1739502665.5953372,25.91997528076172,1.0666225171503554 +1739502665.6149616,25.939975261688232,49.803474371849575,1739502665.6149645,25.939975261688232,1.2825351033675005,1739502665.6149683,25.939975261688232,50.158141787231315,1739502665.6149716,25.939975261688232,51.812038271014046,1739502665.614973,25.939975261688232,4.369718600061429,1739502665.6149752,25.939975261688232,0.9939897986668627,1739502665.6149771,25.939975261688232,1.0744962181625957,1739502665.6149786,25.939975261688232,0.6002001951720689,1739502665.6149797,25.939975261688232,1.0583316544661376,1739502665.614982,25.939975261688232,0.0,1739502665.6149833,25.939975261688232,-0.008290862684217748,1739502665.6149852,25.939975261688232,0.6979453675196218,1739502665.614987,25.939975261688232,1.0666225171503554 +1739502665.6348126,25.959975242614746,49.803474371849575,1739502665.634816,25.959975242614746,1.2825351033675005,1739502665.6348195,25.959975242614746,50.158141787231315,1739502665.6348228,25.959975242614746,51.812038271014046,1739502665.6348248,25.959975242614746,4.369718600061429,1739502665.6348267,25.959975242614746,0.9939897986668627,1739502665.6348283,25.959975242614746,1.0744962181625957,1739502665.63483,25.959975242614746,0.6002001951720689,1739502665.6348317,25.959975242614746,1.0583316544661376,1739502665.6348333,25.959975242614746,0.0,1739502665.634835,25.959975242614746,-0.008290862684217748,1739502665.6348367,25.959975242614746,0.6979453675196218,1739502665.6348386,25.959975242614746,1.0666225171503554 +1739502665.6553488,25.97997522354126,49.803474371849575,1739502665.6553516,25.97997522354126,1.2825351033675005,1739502665.6553552,25.97997522354126,50.158141787231315,1739502665.6553586,25.97997522354126,51.812038271014046,1739502665.6553602,25.97997522354126,4.369718600061429,1739502665.6553621,25.97997522354126,0.9939897986668627,1739502665.6553636,25.97997522354126,1.0744962181625957,1739502665.6553655,25.97997522354126,0.6002001951720689,1739502665.655367,25.97997522354126,1.0583316544661376,1739502665.6553688,25.97997522354126,0.0,1739502665.6553702,25.97997522354126,-0.008290862684217748,1739502665.6553721,25.97997522354126,0.6979453675196218,1739502665.6553736,25.97997522354126,1.0666225171503554 +1739502665.6751676,25.999975204467773,49.803474371849575,1739502665.675171,25.999975204467773,1.2825351033675005,1739502665.6751747,25.999975204467773,50.158141787231315,1739502665.6751778,25.999975204467773,51.812038271014046,1739502665.6751795,25.999975204467773,4.369718600061429,1739502665.6751816,25.999975204467773,0.9939897986668627,1739502665.6751838,25.999975204467773,1.0744962181625957,1739502665.6751857,25.999975204467773,0.6002001951720689,1739502665.675187,25.999975204467773,1.0583316544661376,1739502665.6751893,25.999975204467773,0.0,1739502665.6751907,25.999975204467773,-0.008290862684217748,1739502665.6751926,25.999975204467773,0.6979453675196218,1739502665.6751943,25.999975204467773,1.0666225171503554 +1739502665.6952834,26.019975185394287,49.803474371849575,1739502665.695286,26.019975185394287,1.2825351033675005,1739502665.6952896,26.019975185394287,50.158141787231315,1739502665.695293,26.019975185394287,51.812038271014046,1739502665.6952944,26.019975185394287,4.369718600061429,1739502665.6952963,26.019975185394287,0.9939897986668627,1739502665.6952977,26.019975185394287,1.0744962181625957,1739502665.6952996,26.019975185394287,0.6002001951720689,1739502665.6953008,26.019975185394287,1.0583316544661376,1739502665.6953027,26.019975185394287,0.0,1739502665.6953042,26.019975185394287,-0.008290862684217748,1739502665.695306,26.019975185394287,0.6979453675196218,1739502665.6953075,26.019975185394287,1.0666225171503554 +1739502665.7149563,26.0399751663208,49.89240079607856,1739502665.7149596,26.0399751663208,1.359007578204368,1739502665.7149634,26.0399751663208,50.33452182613426,1739502665.7149668,26.0399751663208,51.80616847827058,1739502665.7149682,26.0399751663208,4.5443043476707565,1739502665.7149706,26.0399751663208,1.0297792527580998,1739502665.7149723,26.0399751663208,1.115032737925314,1739502665.714974,26.0399751663208,0.6108,1739502665.7149756,26.0399751663208,1.0245613210666966,1739502665.7149773,26.0399751663208,0.0,1739502665.714979,26.0399751663208,-0.05618618271948797,1739502665.7149806,26.0399751663208,0.7250205582208973,1739502665.7149825,26.0399751663208,1.0657802064618378 +1739502665.73489,26.059975147247314,49.89240079607856,1739502665.734893,26.059975147247314,1.359007578204368,1739502665.7348967,26.059975147247314,50.33452182613426,1739502665.7349,26.059975147247314,51.80616847827058,1739502665.7349017,26.059975147247314,4.5443043476707565,1739502665.7349038,26.059975147247314,1.0297792527580998,1739502665.7349055,26.059975147247314,1.115032737925314,1739502665.7349072,26.059975147247314,0.6108,1739502665.7349086,26.059975147247314,1.0245613210666966,1739502665.7349105,26.059975147247314,0.0,1739502665.734912,26.059975147247314,-0.04121888539514118,1739502665.7349138,26.059975147247314,0.7250205582208973,1739502665.7349153,26.059975147247314,1.0657802064618378 +1739502665.7553399,26.079975128173828,49.89240079607856,1739502665.7553422,26.079975128173828,1.359007578204368,1739502665.7553458,26.079975128173828,50.33452182613426,1739502665.7553492,26.079975128173828,51.80616847827058,1739502665.7553508,26.079975128173828,4.5443043476707565,1739502665.7553525,26.079975128173828,1.0297792527580998,1739502665.7553546,26.079975128173828,1.115032737925314,1739502665.755356,26.079975128173828,0.6108,1739502665.7553577,26.079975128173828,1.0245613210666966,1739502665.7553596,26.079975128173828,0.0,1739502665.7553613,26.079975128173828,-0.04121888539514118,1739502665.7553627,26.079975128173828,0.7250205582208973,1739502665.7553644,26.079975128173828,1.0657802064618378 +1739502665.7749338,26.099975109100342,49.89240079607856,1739502665.7749374,26.099975109100342,1.359007578204368,1739502665.7749407,26.099975109100342,50.33452182613426,1739502665.774944,26.099975109100342,51.80616847827058,1739502665.7749457,26.099975109100342,4.5443043476707565,1739502665.774948,26.099975109100342,1.0297792527580998,1739502665.7749496,26.099975109100342,1.115032737925314,1739502665.7749512,26.099975109100342,0.6108,1739502665.7749527,26.099975109100342,1.0245613210666966,1739502665.7749548,26.099975109100342,0.0,1739502665.7749562,26.099975109100342,-0.04121888539514118,1739502665.7749581,26.099975109100342,0.7250205582208973,1739502665.7749596,26.099975109100342,1.0657802064618378 +1739502665.795177,26.119975090026855,49.89240079607856,1739502665.7951796,26.119975090026855,1.359007578204368,1739502665.795183,26.119975090026855,50.33452182613426,1739502665.7951858,26.119975090026855,51.80616847827058,1739502665.7951875,26.119975090026855,4.5443043476707565,1739502665.7951896,26.119975090026855,1.0297792527580998,1739502665.7951913,26.119975090026855,1.115032737925314,1739502665.7951932,26.119975090026855,0.6108,1739502665.7951946,26.119975090026855,1.0245613210666966,1739502665.7951965,26.119975090026855,0.0,1739502665.7951982,26.119975090026855,-0.04121888539514118,1739502665.7951996,26.119975090026855,0.7250205582208973,1739502665.7952015,26.119975090026855,1.0657802064618378 +1739502665.8149822,26.13997507095337,49.97901293903882,1739502665.8149855,26.13997507095337,1.4376872207119424,1739502665.8149893,26.13997507095337,50.49382673445897,1739502665.8149927,26.13997507095337,51.79464253062789,1739502665.814994,26.13997507095337,4.694177505529902,1739502665.8149965,26.13997507095337,1.0621812797691028,1739502665.8149984,26.13997507095337,1.136321481832651,1739502665.815,26.13997507095337,0.6108,1739502665.8150015,26.13997507095337,1.0072597717006744,1739502665.8150036,26.13997507095337,0.0,1739502665.8150053,26.13997507095337,-0.059856852207762754,1739502665.815007,26.13997507095337,0.7524827019597181,1739502665.8150084,26.13997507095337,1.0612922554607394 +1739502665.8348618,26.159975051879883,49.97901293903882,1739502665.8348653,26.159975051879883,1.4376872207119424,1739502665.8348696,26.159975051879883,50.49382673445897,1739502665.8348727,26.159975051879883,51.79464253062789,1739502665.8348746,26.159975051879883,4.694177505529902,1739502665.8348768,26.159975051879883,1.0621812797691028,1739502665.8348782,26.159975051879883,1.136321481832651,1739502665.83488,26.159975051879883,0.6108,1739502665.8348815,26.159975051879883,1.0072597717006744,1739502665.8348832,26.159975051879883,0.0,1739502665.834885,26.159975051879883,-0.054032483760064975,1739502665.8348866,26.159975051879883,0.7524827019597181,1739502665.8348882,26.159975051879883,1.0612922554607394 +1739502665.8549662,26.179975032806396,49.97901293903882,1739502665.8549688,26.179975032806396,1.4376872207119424,1739502665.8549724,26.179975032806396,50.49382673445897,1739502665.8549757,26.179975032806396,51.79464253062789,1739502665.8549774,26.179975032806396,4.694177505529902,1739502665.8549793,26.179975032806396,1.0621812797691028,1739502665.8549812,26.179975032806396,1.136321481832651,1739502665.8549829,26.179975032806396,0.6108,1739502665.8549845,26.179975032806396,1.0072597717006744,1739502665.854986,26.179975032806396,0.0,1739502665.8549876,26.179975032806396,-0.054032483760064975,1739502665.8549893,26.179975032806396,0.7524827019597181,1739502665.854991,26.179975032806396,1.0612922554607394 +1739502665.8749177,26.19997501373291,49.97901293903882,1739502665.8749208,26.19997501373291,1.4376872207119424,1739502665.874925,26.19997501373291,50.49382673445897,1739502665.8749285,26.19997501373291,51.79464253062789,1739502665.8749301,26.19997501373291,4.694177505529902,1739502665.8749323,26.19997501373291,1.0621812797691028,1739502665.874934,26.19997501373291,1.136321481832651,1739502665.8749359,26.19997501373291,0.6108,1739502665.8749373,26.19997501373291,1.0072597717006744,1739502665.8749392,26.19997501373291,0.0,1739502665.8749406,26.19997501373291,-0.054032483760064975,1739502665.8749428,26.19997501373291,0.7524827019597181,1739502665.8749442,26.19997501373291,1.0612922554607394 +1739502665.8953657,26.219974994659424,49.97901293903882,1739502665.895368,26.219974994659424,1.4376872207119424,1739502665.895372,26.219974994659424,50.49382673445897,1739502665.8953753,26.219974994659424,51.79464253062789,1739502665.8953772,26.219974994659424,4.694177505529902,1739502665.8953793,26.219974994659424,1.0621812797691028,1739502665.895381,26.219974994659424,1.136321481832651,1739502665.8953826,26.219974994659424,0.6108,1739502665.895384,26.219974994659424,1.0072597717006744,1739502665.8953857,26.219974994659424,0.0,1739502665.8953876,26.219974994659424,-0.054032483760064975,1739502665.895389,26.219974994659424,0.7524827019597181,1739502665.895391,26.219974994659424,1.0612922554607394 +1739502665.914877,26.239974975585938,49.97901293903882,1739502665.9148805,26.239974975585938,1.4376872207119424,1739502665.914884,26.239974975585938,50.49382673445897,1739502665.9148872,26.239974975585938,51.79464253062789,1739502665.9148889,26.239974975585938,4.694177505529902,1739502665.9148912,26.239974975585938,1.0621812797691028,1739502665.9148932,26.239974975585938,1.136321481832651,1739502665.9148948,26.239974975585938,0.6108,1739502665.9148965,26.239974975585938,1.0072597717006744,1739502665.9148982,26.239974975585938,0.0,1739502665.9148998,26.239974975585938,-0.054032483760064975,1739502665.9149015,26.239974975585938,0.7524827019597181,1739502665.914903,26.239974975585938,1.0612922554607394 +1739502665.935042,26.25997495651245,50.063002851029964,1739502665.9350445,26.25997495651245,1.5183212725293256,1739502665.9350483,26.25997495651245,50.57318845233767,1739502665.9350517,26.25997495651245,51.787120375956825,1739502665.9350536,26.25997495651245,4.761041102606041,1739502665.9350557,26.25997495651245,1.082120290528676,1739502665.9350572,26.25997495651245,1.0924611572568017,1739502665.9350588,26.25997495651245,0.6108,1739502665.9350605,26.25997495651245,1.043230142529477,1739502665.9350626,26.25997495651245,0.0,1739502665.935064,26.25997495651245,0.007070859276556929,1739502665.9350657,26.25997495651245,0.7800843909022661,1739502665.9350674,26.25997495651245,1.0552540904713956 +1739502665.954709,26.279974937438965,50.063002851029964,1739502665.954712,26.279974937438965,1.5183212725293256,1739502665.9547155,26.279974937438965,50.57318845233767,1739502665.954718,26.279974937438965,51.787120375956825,1739502665.9547198,26.279974937438965,4.761041102606041,1739502665.9547215,26.279974937438965,1.082120290528676,1739502665.9547231,26.279974937438965,1.0924611572568017,1739502665.9547248,26.279974937438965,0.6108,1739502665.9547265,26.279974937438965,1.043230142529477,1739502665.9547281,26.279974937438965,0.0,1739502665.9547298,26.279974937438965,-0.012023947941918633,1739502665.9547312,26.279974937438965,0.7800843909022661,1739502665.9547334,26.279974937438965,1.0552540904713956 +1739502665.974918,26.29997491836548,50.063002851029964,1739502665.974921,26.29997491836548,1.5183212725293256,1739502665.9749243,26.29997491836548,50.57318845233767,1739502665.9749277,26.29997491836548,51.787120375956825,1739502665.9749293,26.29997491836548,4.761041102606041,1739502665.9749315,26.29997491836548,1.082120290528676,1739502665.974933,26.29997491836548,1.0924611572568017,1739502665.9749348,26.29997491836548,0.6108,1739502665.9749362,26.29997491836548,1.043230142529477,1739502665.9749382,26.29997491836548,0.0,1739502665.9749396,26.29997491836548,-0.012023947941918633,1739502665.9749415,26.29997491836548,0.7800843909022661,1739502665.974943,26.29997491836548,1.0552540904713956 +1739502665.995074,26.319974899291992,50.063002851029964,1739502665.9950767,26.319974899291992,1.5183212725293256,1739502665.99508,26.319974899291992,50.57318845233767,1739502665.9950833,26.319974899291992,51.787120375956825,1739502665.9950848,26.319974899291992,4.761041102606041,1739502665.995087,26.319974899291992,1.082120290528676,1739502665.9950883,26.319974899291992,1.0924611572568017,1739502665.99509,26.319974899291992,0.6108,1739502665.9950914,26.319974899291992,1.043230142529477,1739502665.9950933,26.319974899291992,0.0,1739502665.9950948,26.319974899291992,-0.012023947941918633,1739502665.9950967,26.319974899291992,0.7800843909022661,1739502665.9950984,26.319974899291992,1.0552540904713956 +1739502666.0173705,26.339974880218506,50.063002851029964,1739502666.0173752,26.339974880218506,1.5183212725293256,1739502666.017381,26.339974880218506,50.57318845233767,1739502666.0173872,26.339974880218506,51.787120375956825,1739502666.017391,26.339974880218506,4.761041102606041,1739502666.0173955,26.339974880218506,1.082120290528676,1739502666.0173995,26.339974880218506,1.0924611572568017,1739502666.0174036,26.339974880218506,0.6108,1739502666.0174077,26.339974880218506,1.043230142529477,1739502666.0174122,26.339974880218506,0.0,1739502666.0174162,26.339974880218506,-0.012023947941918633,1739502666.0174203,26.339974880218506,0.7800843909022661,1739502666.0174243,26.339974880218506,1.0552540904713956 +1739502666.0349298,26.35997486114502,50.144431524686674,1739502666.034933,26.35997486114502,1.600936003455046,1739502666.0349367,26.35997486114502,50.574991743730806,1739502666.03494,26.35997486114502,51.78722088929976,1739502666.0349417,26.35997486114502,4.760147650668804,1739502666.0349436,26.35997486114502,1.0912772072065857,1739502666.0349452,26.35997486114502,0.9963331965920571,1739502666.0349472,26.35997486114502,0.5955388810755085,1739502666.0349486,26.35997486114502,1.1266224501193647,1739502666.0349505,26.35997486114502,0.0,1739502666.0349522,26.35997486114502,0.1112393575998272,1739502666.0349538,26.35997486114502,0.8076860798448141,1739502666.0349555,26.35997486114502,1.0539029007568874 +1739502666.0553784,26.379974842071533,50.144431524686674,1739502666.0553813,26.379974842071533,1.600936003455046,1739502666.0553846,26.379974842071533,50.574991743730806,1739502666.055388,26.379974842071533,51.78722088929976,1739502666.0553894,26.379974842071533,4.760147650668804,1739502666.0553913,26.379974842071533,1.0912772072065857,1739502666.055393,26.379974842071533,0.9963331965920571,1739502666.055395,26.379974842071533,0.5955388810755085,1739502666.0553963,26.379974842071533,1.1266224501193647,1739502666.0553982,26.379974842071533,0.0,1739502666.0553997,26.379974842071533,0.07271954936247726,1739502666.0554013,26.379974842071533,0.8076860798448141,1739502666.055403,26.379974842071533,1.0539029007568874 +1739502666.0749512,26.399974822998047,50.144431524686674,1739502666.0749543,26.399974822998047,1.600936003455046,1739502666.0749578,26.399974822998047,50.574991743730806,1739502666.0749612,26.399974822998047,51.78722088929976,1739502666.074963,26.399974822998047,4.760147650668804,1739502666.074965,26.399974822998047,1.0912772072065857,1739502666.0749664,26.399974822998047,0.9963331965920571,1739502666.0749683,26.399974822998047,0.5955388810755085,1739502666.0749698,26.399974822998047,1.1266224501193647,1739502666.0749717,26.399974822998047,0.0,1739502666.074973,26.399974822998047,0.07271954936247726,1739502666.074975,26.399974822998047,0.8076860798448141,1739502666.0749764,26.399974822998047,1.0539029007568874 +1739502666.095621,26.41997480392456,50.144431524686674,1739502666.0956242,26.41997480392456,1.600936003455046,1739502666.0956278,26.41997480392456,50.574991743730806,1739502666.0956311,26.41997480392456,51.78722088929976,1739502666.0956326,26.41997480392456,4.760147650668804,1739502666.0956347,26.41997480392456,1.0912772072065857,1739502666.0956361,26.41997480392456,0.9963331965920571,1739502666.095638,26.41997480392456,0.5955388810755085,1739502666.0956392,26.41997480392456,1.1266224501193647,1739502666.0956414,26.41997480392456,0.0,1739502666.0956428,26.41997480392456,0.07271954936247726,1739502666.0956447,26.41997480392456,0.8076860798448141,1739502666.0956461,26.41997480392456,1.0539029007568874 +1739502666.1149328,26.439974784851074,50.144431524686674,1739502666.114936,26.439974784851074,1.600936003455046,1739502666.11494,26.439974784851074,50.574991743730806,1739502666.1149435,26.439974784851074,51.78722088929976,1739502666.114945,26.439974784851074,4.760147650668804,1739502666.114947,26.439974784851074,1.0912772072065857,1739502666.1149487,26.439974784851074,0.9963331965920571,1739502666.1149507,26.439974784851074,0.5955388810755085,1739502666.114952,26.439974784851074,1.1266224501193647,1739502666.114954,26.439974784851074,0.0,1739502666.1149557,26.439974784851074,0.07271954936247726,1739502666.1149573,26.439974784851074,0.8076860798448141,1739502666.114959,26.439974784851074,1.0539029007568874 +1739502666.1348634,26.459974765777588,50.144431524686674,1739502666.1348667,26.459974765777588,1.600936003455046,1739502666.1348705,26.459974765777588,50.574991743730806,1739502666.1348739,26.459974765777588,51.78722088929976,1739502666.1348755,26.459974765777588,4.760147650668804,1739502666.1348777,26.459974765777588,1.0912772072065857,1739502666.1348794,26.459974765777588,0.9963331965920571,1739502666.1348808,26.459974765777588,0.5955388810755085,1739502666.1348822,26.459974765777588,1.1266224501193647,1739502666.1348846,26.459974765777588,0.0,1739502666.1348858,26.459974765777588,0.07271954936247726,1739502666.1348877,26.459974765777588,0.8076860798448141,1739502666.1348894,26.459974765777588,1.0539029007568874 +1739502666.1554687,26.4799747467041,50.22381918923415,1739502666.1554716,26.4799747467041,1.6860596163655002,1739502666.1554754,26.4799747467041,50.88394490356246,1739502666.1554785,26.4799747467041,51.73626100749219,1739502666.1554801,26.4799747467041,5.082479145781805,1739502666.155482,26.4799747467041,1.1518538102496951,1739502666.1554837,26.4799747467041,1.1574164470322914,1739502666.1554854,26.4799747467041,0.6108,1739502666.155487,26.4799747467041,0.9904039133753775,1739502666.1554887,26.4799747467041,0.0,1739502666.1554904,26.4799747467041,-0.13812342625485546,1739502666.1554918,26.4799747467041,0.8352877687873621,1739502666.1554937,26.4799747467041,1.062638866549967 +1739502666.1748714,26.499974727630615,50.22381918923415,1739502666.1748743,26.499974727630615,1.6860596163655002,1739502666.1748784,26.499974727630615,50.88394490356246,1739502666.1748817,26.499974727630615,51.73626100749219,1739502666.1748836,26.499974727630615,5.082479145781805,1739502666.1748857,26.499974727630615,1.1518538102496951,1739502666.1748874,26.499974727630615,1.1574164470322914,1739502666.1748888,26.499974727630615,0.6108,1739502666.1748905,26.499974727630615,0.9904039133753775,1739502666.1748924,26.499974727630615,0.0,1739502666.1748943,26.499974727630615,-0.07223495317458961,1739502666.1748962,26.499974727630615,0.8352877687873621,1739502666.1748977,26.499974727630615,1.062638866549967 +1739502666.1951578,26.51997470855713,50.22381918923415,1739502666.1951604,26.51997470855713,1.6860596163655002,1739502666.195164,26.51997470855713,50.88394490356246,1739502666.1951673,26.51997470855713,51.73626100749219,1739502666.1951687,26.51997470855713,5.082479145781805,1739502666.1951709,26.51997470855713,1.1518538102496951,1739502666.1951725,26.51997470855713,1.1574164470322914,1739502666.1951742,26.51997470855713,0.6108,1739502666.1951756,26.51997470855713,0.9904039133753775,1739502666.1951778,26.51997470855713,0.0,1739502666.1951792,26.51997470855713,-0.07223495317458961,1739502666.1951811,26.51997470855713,0.8352877687873621,1739502666.1951826,26.51997470855713,1.062638866549967 +1739502666.2148776,26.539974689483643,50.22381918923415,1739502666.214881,26.539974689483643,1.6860596163655002,1739502666.2148845,26.539974689483643,50.88394490356246,1739502666.2148879,26.539974689483643,51.73626100749219,1739502666.2148898,26.539974689483643,5.082479145781805,1739502666.2148921,26.539974689483643,1.1518538102496951,1739502666.2148936,26.539974689483643,1.1574164470322914,1739502666.2148952,26.539974689483643,0.6108,1739502666.214897,26.539974689483643,0.9904039133753775,1739502666.2148986,26.539974689483643,0.0,1739502666.2149003,26.539974689483643,-0.07223495317458961,1739502666.214902,26.539974689483643,0.8352877687873621,1739502666.2149038,26.539974689483643,1.062638866549967 +1739502666.23488,26.559974670410156,50.22381918923415,1739502666.2348833,26.559974670410156,1.6860596163655002,1739502666.234887,26.559974670410156,50.88394490356246,1739502666.2348905,26.559974670410156,51.73626100749219,1739502666.2348924,26.559974670410156,5.082479145781805,1739502666.2348943,26.559974670410156,1.1518538102496951,1739502666.234896,26.559974670410156,1.1574164470322914,1739502666.2348976,26.559974670410156,0.6108,1739502666.2348993,26.559974670410156,0.9904039133753775,1739502666.2349012,26.559974670410156,0.0,1739502666.2349029,26.559974670410156,-0.07223495317458961,1739502666.2349043,26.559974670410156,0.8352877687873621,1739502666.2349062,26.559974670410156,1.062638866549967 +1739502666.2551973,26.57997465133667,50.3009130074523,1739502666.2552,26.57997465133667,1.7734323516627946,1739502666.2552032,26.57997465133667,50.962621913420115,1739502666.2552066,26.57997465133667,51.72447647740513,1739502666.2552083,26.57997465133667,5.144457044758174,1739502666.2552102,26.57997465133667,1.1712199245122188,1739502666.2552118,26.57997465133667,1.1104757603897903,1739502666.2552135,26.57997465133667,0.6108,1739502666.2552152,26.57997465133667,1.028303260034236,1739502666.2552168,26.57997465133667,0.0,1739502666.2552185,26.57997465133667,-0.005771376147793512,1739502666.25522,26.57997465133667,0.8628894577299101,1739502666.2552218,26.57997465133667,1.0548445176206989 +1739502666.2748723,26.599974632263184,50.3009130074523,1739502666.2748756,26.599974632263184,1.7734323516627946,1739502666.2748795,26.599974632263184,50.962621913420115,1739502666.2748828,26.599974632263184,51.72447647740513,1739502666.2748847,26.599974632263184,5.144457044758174,1739502666.2748866,26.599974632263184,1.1712199245122188,1739502666.2748883,26.599974632263184,1.1104757603897903,1739502666.27489,26.599974632263184,0.6108,1739502666.2748916,26.599974632263184,1.028303260034236,1739502666.2748933,26.599974632263184,0.0,1739502666.274895,26.599974632263184,-0.026541257586462752,1739502666.2748966,26.599974632263184,0.8628894577299101,1739502666.2748983,26.599974632263184,1.0548445176206989 +1739502666.2952154,26.619974613189697,50.3009130074523,1739502666.295218,26.619974613189697,1.7734323516627946,1739502666.2952216,26.619974613189697,50.962621913420115,1739502666.295225,26.619974613189697,51.72447647740513,1739502666.2952266,26.619974613189697,5.144457044758174,1739502666.2952287,26.619974613189697,1.1712199245122188,1739502666.2952302,26.619974613189697,1.1104757603897903,1739502666.2952318,26.619974613189697,0.6108,1739502666.2952332,26.619974613189697,1.028303260034236,1739502666.2952352,26.619974613189697,0.0,1739502666.2952366,26.619974613189697,-0.026541257586462752,1739502666.2952385,26.619974613189697,0.8628894577299101,1739502666.29524,26.619974613189697,1.0548445176206989 +1739502666.3150043,26.63997459411621,50.3009130074523,1739502666.3150077,26.63997459411621,1.7734323516627946,1739502666.3150113,26.63997459411621,50.962621913420115,1739502666.3150146,26.63997459411621,51.72447647740513,1739502666.3150165,26.63997459411621,5.144457044758174,1739502666.3150182,26.63997459411621,1.1712199245122188,1739502666.31502,26.63997459411621,1.1104757603897903,1739502666.3150218,26.63997459411621,0.6108,1739502666.3150234,26.63997459411621,1.028303260034236,1739502666.315025,26.63997459411621,0.0,1739502666.3150268,26.63997459411621,-0.026541257586462752,1739502666.3150284,26.63997459411621,0.8628894577299101,1739502666.31503,26.63997459411621,1.0548445176206989 +1739502666.3348932,26.659974575042725,50.3009130074523,1739502666.3348966,26.659974575042725,1.7734323516627946,1739502666.3349004,26.659974575042725,50.962621913420115,1739502666.3349035,26.659974575042725,51.72447647740513,1739502666.3349054,26.659974575042725,5.144457044758174,1739502666.3349073,26.659974575042725,1.1712199245122188,1739502666.334909,26.659974575042725,1.1104757603897903,1739502666.3349106,26.659974575042725,0.6108,1739502666.3349123,26.659974575042725,1.028303260034236,1739502666.334914,26.659974575042725,0.0,1739502666.3349156,26.659974575042725,-0.026541257586462752,1739502666.3349173,26.659974575042725,0.8628894577299101,1739502666.334919,26.659974575042725,1.0548445176206989 +1739502666.3548656,26.67997455596924,50.3009130074523,1739502666.3548682,26.67997455596924,1.7734323516627946,1739502666.3548717,26.67997455596924,50.962621913420115,1739502666.354875,26.67997455596924,51.72447647740513,1739502666.3548768,26.67997455596924,5.144457044758174,1739502666.3548787,26.67997455596924,1.1712199245122188,1739502666.3548803,26.67997455596924,1.1104757603897903,1739502666.3548818,26.67997455596924,0.6108,1739502666.3548834,26.67997455596924,1.028303260034236,1739502666.354885,26.67997455596924,0.0,1739502666.3548868,26.67997455596924,-0.026541257586462752,1739502666.3548884,26.67997455596924,0.8628894577299101,1739502666.3548903,26.67997455596924,1.0548445176206989 +1739502666.3935175,26.70997452735901,50.375180971341145,1739502666.3935215,26.70997452735901,1.8624401832373723,1739502666.3935268,26.70997452735901,51.095716827134,1739502666.3935325,26.70997452735901,51.69656511163945,1739502666.3935354,26.70997452735901,5.269464205223597,1739502666.3935394,26.70997452735901,1.2008154537082234,1739502666.3935428,26.70997452735901,1.1159026803606162,1739502666.3935456,26.70997452735901,0.6108,1739502666.393549,26.70997452735901,1.0238485216366437,1739502666.3935523,26.70997452735901,0.0,1739502666.3935556,26.70997452735901,-0.02938948423734491,1739502666.393559,26.70997452735901,0.8904911466724581,1739502666.3935626,26.70997452735901,1.0523479344620117 +1739502666.412824,26.729974508285522,50.375180971341145,1739502666.412828,26.729974508285522,1.8624401832373723,1739502666.4128325,26.729974508285522,51.095716827134,1739502666.4128377,26.729974508285522,51.69656511163945,1739502666.4128404,26.729974508285522,5.269464205223597,1739502666.4128447,26.729974508285522,1.2008154537082234,1739502666.4128478,26.729974508285522,1.1159026803606162,1739502666.4128516,26.729974508285522,0.6108,1739502666.4128547,26.729974508285522,1.0238485216366437,1739502666.4128585,26.729974508285522,0.0,1739502666.4128616,26.729974508285522,-0.028499412825367942,1739502666.4128656,26.729974508285522,0.8904911466724581,1739502666.412869,26.729974508285522,1.0523479344620117 +1739502666.4305174,26.749974489212036,50.375180971341145,1739502666.4305198,26.749974489212036,1.8624401832373723,1739502666.4305227,26.749974489212036,51.095716827134,1739502666.4305255,26.749974489212036,51.69656511163945,1739502666.4305267,26.749974489212036,5.269464205223597,1739502666.4305282,26.749974489212036,1.2008154537082234,1739502666.4305298,26.749974489212036,1.1159026803606162,1739502666.430531,26.749974489212036,0.6108,1739502666.4305325,26.749974489212036,1.0238485216366437,1739502666.430534,26.749974489212036,0.0,1739502666.430535,26.749974489212036,-0.028499412825367942,1739502666.4305365,26.749974489212036,0.8904911466724581,1739502666.430538,26.749974489212036,1.0523479344620117 +1739502666.4505405,26.76997447013855,50.375180971341145,1739502666.4505436,26.76997447013855,1.8624401832373723,1739502666.4505467,26.76997447013855,51.095716827134,1739502666.4505494,26.76997447013855,51.69656511163945,1739502666.4505506,26.76997447013855,5.269464205223597,1739502666.4505522,26.76997447013855,1.2008154537082234,1739502666.4505537,26.76997447013855,1.1159026803606162,1739502666.450555,26.76997447013855,0.6108,1739502666.450557,26.76997447013855,1.0238485216366437,1739502666.4505584,26.76997447013855,0.0,1739502666.4505599,26.76997447013855,-0.028499412825367942,1739502666.450561,26.76997447013855,0.8904911466724581,1739502666.4505625,26.76997447013855,1.0523479344620117 +1739502666.470259,26.789974451065063,50.375180971341145,1739502666.4702613,26.789974451065063,1.8624401832373723,1739502666.470264,26.789974451065063,51.095716827134,1739502666.4702666,26.789974451065063,51.69656511163945,1739502666.470268,26.789974451065063,5.269464205223597,1739502666.4702694,26.789974451065063,1.2008154537082234,1739502666.4702709,26.789974451065063,1.1159026803606162,1739502666.4702723,26.789974451065063,0.6108,1739502666.4702737,26.789974451065063,1.0238485216366437,1739502666.4702754,26.789974451065063,0.0,1739502666.4702766,26.789974451065063,-0.028499412825367942,1739502666.4702783,26.789974451065063,0.8904911466724581,1739502666.4702795,26.789974451065063,1.0523479344620117 +1739502666.4906576,26.809974431991577,50.44676490348642,1739502666.4906602,26.809974431991577,1.9532108640644354,1739502666.490663,26.809974431991577,51.24805154149173,1739502666.490666,26.809974431991577,51.66052321709311,1739502666.4906673,26.809974431991577,5.411081537325255,1739502666.490669,26.809974431991577,1.2332191483352095,1739502666.4906704,26.809974431991577,1.1358267654969445,1739502666.4906719,26.809974431991577,0.6108,1739502666.4906733,26.809974431991577,1.0076584968885036,1739502666.490675,26.809974431991577,0.0,1739502666.4906762,26.809974431991577,-0.047540751780248115,1739502666.4906778,26.809974431991577,0.9180928356150061,1739502666.490679,26.809974431991577,1.0492488263439508 +1739502666.5114243,26.82997441291809,50.44676490348642,1739502666.5114272,26.82997441291809,1.9532108640644354,1739502666.5114305,26.82997441291809,51.24805154149173,1739502666.5114331,26.82997441291809,51.66052321709311,1739502666.5114346,26.82997441291809,5.411081537325255,1739502666.5114362,26.82997441291809,1.2332191483352095,1739502666.5114377,26.82997441291809,1.1358267654969445,1739502666.5114388,26.82997441291809,0.6108,1739502666.5114403,26.82997441291809,1.0076584968885036,1739502666.511442,26.82997441291809,0.0,1739502666.5114431,26.82997441291809,-0.04159032945544716,1739502666.5114446,26.82997441291809,0.9180928356150061,1739502666.511446,26.82997441291809,1.0492488263439508 +1739502666.5311584,26.849974393844604,50.44676490348642,1739502666.531161,26.849974393844604,1.9532108640644354,1739502666.531164,26.849974393844604,51.24805154149173,1739502666.5311668,26.849974393844604,51.66052321709311,1739502666.531168,26.849974393844604,5.411081537325255,1739502666.53117,26.849974393844604,1.2332191483352095,1739502666.5311713,26.849974393844604,1.1358267654969445,1739502666.5311725,26.849974393844604,0.6108,1739502666.531174,26.849974393844604,1.0076584968885036,1739502666.5311754,26.849974393844604,0.0,1739502666.531177,26.849974393844604,-0.04159032945544716,1739502666.5311782,26.849974393844604,0.9180928356150061,1739502666.5311797,26.849974393844604,1.0492488263439508 +1739502666.5516083,26.869974374771118,50.44676490348642,1739502666.5516112,26.869974374771118,1.9532108640644354,1739502666.5516145,26.869974374771118,51.24805154149173,1739502666.5516174,26.869974374771118,51.66052321709311,1739502666.5516188,26.869974374771118,5.411081537325255,1739502666.5516207,26.869974374771118,1.2332191483352095,1739502666.5516222,26.869974374771118,1.1358267654969445,1739502666.5516236,26.869974374771118,0.6108,1739502666.551625,26.869974374771118,1.0076584968885036,1739502666.5516264,26.869974374771118,0.0,1739502666.551628,26.869974374771118,-0.04159032945544716,1739502666.5516293,26.869974374771118,0.9180928356150061,1739502666.5516307,26.869974374771118,1.0492488263439508 +1739502666.570504,26.889974355697632,50.44676490348642,1739502666.5705085,26.889974355697632,1.9532108640644354,1739502666.5705142,26.889974355697632,51.24805154149173,1739502666.5705185,26.889974355697632,51.66052321709311,1739502666.5705209,26.889974355697632,5.411081537325255,1739502666.570524,26.889974355697632,1.2332191483352095,1739502666.570526,26.889974355697632,1.1358267654969445,1739502666.5705283,26.889974355697632,0.6108,1739502666.5705307,26.889974355697632,1.0076584968885036,1739502666.5705333,26.889974355697632,0.0,1739502666.5705354,26.889974355697632,-0.04159032945544716,1739502666.570538,26.889974355697632,0.9180928356150061,1739502666.5705402,26.889974355697632,1.0492488263439508 +1739502666.5902143,26.909974336624146,50.515570507517864,1739502666.5902164,26.909974336624146,2.045591690671431,1739502666.5902193,26.909974336624146,51.33865184766837,1739502666.5902221,26.909974336624146,51.638693556213056,1739502666.5902233,26.909974336624146,5.48960817381645,1739502666.5902252,26.909974336624146,1.255562154450074,1739502666.5902264,26.909974336624146,1.104624503938603,1739502666.5902276,26.909974336624146,0.6108,1739502666.590229,26.909974336624146,1.0331280364932687,1739502666.5902305,26.909974336624146,0.0,1739502666.590232,26.909974336624146,0.002066997683778325,1739502666.590233,26.909974336624146,0.9456945245575541,1739502666.5902345,26.909974336624146,1.0447039624854961 +1739502666.610229,26.92997431755066,50.515570507517864,1739502666.6102314,26.92997431755066,2.045591690671431,1739502666.610234,26.92997431755066,51.33865184766837,1739502666.610237,26.92997431755066,51.638693556213056,1739502666.6102383,26.92997431755066,5.48960817381645,1739502666.61024,26.92997431755066,1.255562154450074,1739502666.6102412,26.92997431755066,1.104624503938603,1739502666.6102428,26.92997431755066,0.6108,1739502666.610244,26.92997431755066,1.0331280364932687,1739502666.6102457,26.92997431755066,0.0,1739502666.610247,26.92997431755066,-0.011575925992227454,1739502666.610248,26.92997431755066,0.9456945245575541,1739502666.6102498,26.92997431755066,1.0447039624854961 +1739502666.6307843,26.949974298477173,50.515570507517864,1739502666.6307874,26.949974298477173,2.045591690671431,1739502666.630791,26.949974298477173,51.33865184766837,1739502666.6307945,26.949974298477173,51.638693556213056,1739502666.630796,26.949974298477173,5.48960817381645,1739502666.630798,26.949974298477173,1.255562154450074,1739502666.6307998,26.949974298477173,1.104624503938603,1739502666.6308017,26.949974298477173,0.6108,1739502666.630803,26.949974298477173,1.0331280364932687,1739502666.6308053,26.949974298477173,0.0,1739502666.6308067,26.949974298477173,-0.011575925992227454,1739502666.6308086,26.949974298477173,0.9456945245575541,1739502666.63081,26.949974298477173,1.0447039624854961 +1739502666.6534421,26.969974279403687,50.515570507517864,1739502666.6534457,26.969974279403687,2.045591690671431,1739502666.6534505,26.969974279403687,51.33865184766837,1739502666.6534548,26.969974279403687,51.638693556213056,1739502666.653457,26.969974279403687,5.48960817381645,1739502666.6534598,26.969974279403687,1.255562154450074,1739502666.6534617,26.969974279403687,1.104624503938603,1739502666.6534643,26.969974279403687,0.6108,1739502666.6534662,26.969974279403687,1.0331280364932687,1739502666.6534684,26.969974279403687,0.0,1739502666.6534705,26.969974279403687,-0.011575925992227454,1739502666.6534724,26.969974279403687,0.9456945245575541,1739502666.6534748,26.969974279403687,1.0447039624854961 +1739502666.6718698,26.9899742603302,50.515570507517864,1739502666.6718733,26.9899742603302,2.045591690671431,1739502666.6718779,26.9899742603302,51.33865184766837,1739502666.671882,26.9899742603302,51.638693556213056,1739502666.6718838,26.9899742603302,5.48960817381645,1739502666.6718864,26.9899742603302,1.255562154450074,1739502666.6718884,26.9899742603302,1.104624503938603,1739502666.6718905,26.9899742603302,0.6108,1739502666.6718922,26.9899742603302,1.0331280364932687,1739502666.6718946,26.9899742603302,0.0,1739502666.6718965,26.9899742603302,-0.011575925992227454,1739502666.6718986,26.9899742603302,0.9456945245575541,1739502666.671901,26.9899742603302,1.0447039624854961 +1739502666.6930604,27.009974241256714,50.515570507517864,1739502666.6930654,27.009974241256714,2.045591690671431,1739502666.6930726,27.009974241256714,51.33865184766837,1739502666.6930807,27.009974241256714,51.638693556213056,1739502666.6930852,27.009974241256714,5.48960817381645,1739502666.693091,27.009974241256714,1.255562154450074,1739502666.6930962,27.009974241256714,1.104624503938603,1739502666.6931014,27.009974241256714,0.6108,1739502666.6931067,27.009974241256714,1.0331280364932687,1739502666.6931121,27.009974241256714,0.0,1739502666.6931174,27.009974241256714,-0.011575925992227454,1739502666.6931226,27.009974241256714,0.9456945245575541,1739502666.6931279,27.009974241256714,1.0447039624854961 +1739502666.7121894,27.029974222183228,50.58161993948238,1739502666.7121928,27.029974222183228,2.1395810405074274,1739502666.7121973,27.029974222183228,51.49154892227132,1739502666.7122014,27.029974222183228,51.59300027208146,1739502666.7122037,27.029974222183228,5.633418564924786,1739502666.7122066,27.029974222183228,1.2890227924947104,1739502666.7122087,27.029974222183228,1.1294010549652358,1739502666.7122107,27.029974222183228,0.6108,1739502666.7122128,27.029974222183228,1.0128517710956586,1739502666.712215,27.029974222183228,0.0,1739502666.712217,27.029974222183228,-0.03961730700556462,1739502666.7122195,27.029974222183228,0.9732962135001021,1739502666.7122216,27.029974222183228,1.043706140789126 +1739502666.731329,27.04997420310974,50.58161993948238,1739502666.7313325,27.04997420310974,2.1395810405074274,1739502666.7313366,27.04997420310974,51.49154892227132,1739502666.7313411,27.04997420310974,51.59300027208146,1739502666.731343,27.04997420310974,5.633418564924786,1739502666.7313457,27.04997420310974,1.2890227924947104,1739502666.7313478,27.04997420310974,1.1294010549652358,1739502666.7313497,27.04997420310974,0.6108,1739502666.7313516,27.04997420310974,1.0128517710956586,1739502666.7313538,27.04997420310974,0.0,1739502666.731356,27.04997420310974,-0.03085436969346733,1739502666.731358,27.04997420310974,0.9732962135001021,1739502666.7313604,27.04997420310974,1.043706140789126 +1739502666.7515554,27.069974184036255,50.58161993948238,1739502666.751559,27.069974184036255,2.1395810405074274,1739502666.751563,27.069974184036255,51.49154892227132,1739502666.7515674,27.069974184036255,51.59300027208146,1739502666.7515695,27.069974184036255,5.633418564924786,1739502666.751572,27.069974184036255,1.2890227924947104,1739502666.751574,27.069974184036255,1.1294010549652358,1739502666.751576,27.069974184036255,0.6108,1739502666.751578,27.069974184036255,1.0128517710956586,1739502666.7515805,27.069974184036255,0.0,1739502666.7515824,27.069974184036255,-0.03085436969346733,1739502666.7515845,27.069974184036255,0.9732962135001021,1739502666.7515867,27.069974184036255,1.043706140789126 +1739502666.773944,27.08997416496277,50.58161993948238,1739502666.7739491,27.08997416496277,2.1395810405074274,1739502666.7739563,27.08997416496277,51.49154892227132,1739502666.7739644,27.08997416496277,51.59300027208146,1739502666.773969,27.08997416496277,5.633418564924786,1739502666.773975,27.08997416496277,1.2890227924947104,1739502666.77398,27.08997416496277,1.1294010549652358,1739502666.773985,27.08997416496277,0.6108,1739502666.7739904,27.08997416496277,1.0128517710956586,1739502666.7739959,27.08997416496277,0.0,1739502666.774001,27.08997416496277,-0.03085436969346733,1739502666.7740064,27.08997416496277,0.9732962135001021,1739502666.7740116,27.08997416496277,1.043706140789126 +1739502666.7911863,27.109974145889282,50.58161993948238,1739502666.79119,27.109974145889282,2.1395810405074274,1739502666.7911944,27.109974145889282,51.49154892227132,1739502666.7911985,27.109974145889282,51.59300027208146,1739502666.7912004,27.109974145889282,5.633418564924786,1739502666.7912028,27.109974145889282,1.2890227924947104,1739502666.7912052,27.109974145889282,1.1294010549652358,1739502666.791207,27.109974145889282,0.6108,1739502666.791209,27.109974145889282,1.0128517710956586,1739502666.7912114,27.109974145889282,0.0,1739502666.7912133,27.109974145889282,-0.03085436969346733,1739502666.7912154,27.109974145889282,0.9732962135001021,1739502666.7912176,27.109974145889282,1.043706140789126 +1739502666.8130856,27.129974126815796,50.64491993074157,1739502666.8130908,27.129974126815796,2.2351595298064924,1739502666.813098,27.129974126815796,51.64210091236253,1739502666.8131065,27.129974126815796,51.54426888948229,1739502666.813111,27.129974126815796,5.768717934939669,1739502666.8131168,27.129974126815796,1.3215713673638954,1739502666.813122,27.129974126815796,1.1493071157052523,1739502666.8131273,27.129974126815796,0.6108,1739502666.8131325,27.129974126815796,0.9968500109685942,1739502666.8131378,27.129974126815796,0.0,1739502666.813143,27.129974126815796,-0.04923647935475777,1739502666.8131485,27.129974126815796,1.00089790244265,1739502666.8131537,27.129974126815796,1.040342077287868 +1739502666.8318918,27.14997410774231,50.64491993074157,1739502666.831895,27.14997410774231,2.2351595298064924,1739502666.8318994,27.14997410774231,51.64210091236253,1739502666.8319037,27.14997410774231,51.54426888948229,1739502666.8319058,27.14997410774231,5.768717934939669,1739502666.8319087,27.14997410774231,1.3215713673638954,1739502666.8319106,27.14997410774231,1.1493071157052523,1739502666.8319125,27.14997410774231,0.6108,1739502666.8319144,27.14997410774231,0.9968500109685942,1739502666.8319168,27.14997410774231,0.0,1739502666.831919,27.14997410774231,-0.043492066319273825,1739502666.831921,27.14997410774231,1.00089790244265,1739502666.8319235,27.14997410774231,1.040342077287868 +1739502666.8514912,27.169974088668823,50.64491993074157,1739502666.851495,27.169974088668823,2.2351595298064924,1739502666.8514993,27.169974088668823,51.64210091236253,1739502666.8515031,27.169974088668823,51.54426888948229,1739502666.851505,27.169974088668823,5.768717934939669,1739502666.8515077,27.169974088668823,1.3215713673638954,1739502666.8515098,27.169974088668823,1.1493071157052523,1739502666.8515117,27.169974088668823,0.6108,1739502666.8515139,27.169974088668823,0.9968500109685942,1739502666.8515162,27.169974088668823,0.0,1739502666.8515184,27.169974088668823,-0.043492066319273825,1739502666.8515205,27.169974088668823,1.00089790244265,1739502666.8515224,27.169974088668823,1.040342077287868 +1739502666.8732295,27.189974069595337,50.64491993074157,1739502666.873233,27.189974069595337,2.2351595298064924,1739502666.8732376,27.189974069595337,51.64210091236253,1739502666.8732417,27.189974069595337,51.54426888948229,1739502666.8732433,27.189974069595337,5.768717934939669,1739502666.8732462,27.189974069595337,1.3215713673638954,1739502666.8732483,27.189974069595337,1.1493071157052523,1739502666.8732502,27.189974069595337,0.6108,1739502666.8732522,27.189974069595337,0.9968500109685942,1739502666.8732543,27.189974069595337,0.0,1739502666.8732564,27.189974069595337,-0.043492066319273825,1739502666.8732586,27.189974069595337,1.00089790244265,1739502666.8732605,27.189974069595337,1.040342077287868 +1739502666.8925266,27.20997405052185,50.64491993074157,1739502666.8925302,27.20997405052185,2.2351595298064924,1739502666.8925343,27.20997405052185,51.64210091236253,1739502666.8925383,27.20997405052185,51.54426888948229,1739502666.8925405,27.20997405052185,5.768717934939669,1739502666.8925428,27.20997405052185,1.3215713673638954,1739502666.8925447,27.20997405052185,1.1493071157052523,1739502666.8925474,27.20997405052185,0.6108,1739502666.892549,27.20997405052185,0.9968500109685942,1739502666.8925514,27.20997405052185,0.0,1739502666.8925536,27.20997405052185,-0.043492066319273825,1739502666.8925555,27.20997405052185,1.00089790244265,1739502666.8925576,27.20997405052185,1.040342077287868 +1739502666.9110572,27.229974031448364,50.64491993074157,1739502666.911061,27.229974031448364,2.2351595298064924,1739502666.911065,27.229974031448364,51.64210091236253,1739502666.9110687,27.229974031448364,51.54426888948229,1739502666.9110708,27.229974031448364,5.768717934939669,1739502666.911073,27.229974031448364,1.3215713673638954,1739502666.911075,27.229974031448364,1.1493071157052523,1739502666.9110768,27.229974031448364,0.6108,1739502666.9110787,27.229974031448364,0.9968500109685942,1739502666.9110806,27.229974031448364,0.0,1739502666.9110827,27.229974031448364,-0.043492066319273825,1739502666.9110851,27.229974031448364,1.00089790244265,1739502666.9110873,27.229974031448364,1.040342077287868 +1739502666.9308195,27.249974012374878,50.70531779948901,1739502666.9308224,27.249974012374878,2.332062505839323,1739502666.9308255,27.249974012374878,51.70990539250868,1739502666.9308283,27.249974012374878,51.523210577539324,1739502666.9308298,27.249974012374878,5.822803511725583,1739502666.9308317,27.249974012374878,1.340644533037631,1739502666.9308329,27.249974012374878,1.101041273253449,1739502666.9308345,27.249974012374878,0.6108,1739502666.9308357,27.249974012374878,1.0360938341829227,1739502666.930838,27.249974012374878,0.0,1739502666.9308393,27.249974012374878,0.020690024888245187,1739502666.9308405,27.249974012374878,1.0284995913851993,1739502666.9308422,27.249974012374878,1.0354607259473665 +1739502666.9507499,27.26997399330139,50.70531779948901,1739502666.950753,27.26997399330139,2.332062505839323,1739502666.950756,27.26997399330139,51.70990539250868,1739502666.950759,27.26997399330139,51.523210577539324,1739502666.9507604,27.26997399330139,5.822803511725583,1739502666.950762,27.26997399330139,1.340644533037631,1739502666.9507635,27.26997399330139,1.101041273253449,1739502666.9507651,27.26997399330139,0.6108,1739502666.9507663,27.26997399330139,1.0360938341829227,1739502666.9507678,27.26997399330139,0.0,1739502666.9507694,27.26997399330139,0.000633108235556179,1739502666.9507709,27.26997399330139,1.0284995913851993,1739502666.9507723,27.26997399330139,1.0354607259473665 +1739502666.970776,27.289973974227905,50.70531779948901,1739502666.9707787,27.289973974227905,2.332062505839323,1739502666.9707813,27.289973974227905,51.70990539250868,1739502666.9707842,27.289973974227905,51.523210577539324,1739502666.9707856,27.289973974227905,5.822803511725583,1739502666.9707873,27.289973974227905,1.340644533037631,1739502666.970789,27.289973974227905,1.101041273253449,1739502666.9707904,27.289973974227905,0.6108,1739502666.9707916,27.289973974227905,1.0360938341829227,1739502666.9707932,27.289973974227905,0.0,1739502666.9707944,27.289973974227905,0.000633108235556179,1739502666.970796,27.289973974227905,1.0284995913851993,1739502666.9707973,27.289973974227905,1.0354607259473665 +1739502666.9905775,27.30997395515442,50.70531779948901,1739502666.9905803,27.30997395515442,2.332062505839323,1739502666.9905832,27.30997395515442,51.70990539250868,1739502666.990586,27.30997395515442,51.523210577539324,1739502666.9905875,27.30997395515442,5.822803511725583,1739502666.9905891,27.30997395515442,1.340644533037631,1739502666.9905908,27.30997395515442,1.101041273253449,1739502666.990592,27.30997395515442,0.6108,1739502666.9905932,27.30997395515442,1.0360938341829227,1739502666.9905949,27.30997395515442,0.0,1739502666.990596,27.30997395515442,0.000633108235556179,1739502666.990598,27.30997395515442,1.0284995913851993,1739502666.9905992,27.30997395515442,1.0354607259473665 +1739502667.010492,27.329973936080933,50.70531779948901,1739502667.0104947,27.329973936080933,2.332062505839323,1739502667.0104978,27.329973936080933,51.70990539250868,1739502667.0105007,27.329973936080933,51.523210577539324,1739502667.0105019,27.329973936080933,5.822803511725583,1739502667.0105038,27.329973936080933,1.340644533037631,1739502667.0105052,27.329973936080933,1.101041273253449,1739502667.0105069,27.329973936080933,0.6108,1739502667.0105083,27.329973936080933,1.0360938341829227,1739502667.0105097,27.329973936080933,0.0,1739502667.010511,27.329973936080933,0.000633108235556179,1739502667.0105124,27.329973936080933,1.0284995913851993,1739502667.010514,27.329973936080933,1.0354607259473665 +1739502667.0310323,27.349973917007446,50.76286888730258,1739502667.0310352,27.349973917007446,2.4303428052262124,1739502667.031038,27.349973917007446,51.89838380774463,1739502667.0310404,27.349973917007446,51.453491024818234,1739502667.031042,27.349973917007446,5.9979733270526525,1739502667.0310438,27.349973917007446,1.379581336227799,1739502667.0310452,27.349973917007446,1.155088309988938,1739502667.0310464,27.349973917007446,0.6108,1739502667.0310478,27.349973917007446,0.9922502691001882,1739502667.0310497,27.349973917007446,0.0,1739502667.031051,27.349973917007446,-0.06318797705534847,1739502667.0310526,27.349973917007446,1.0561012803277485,1739502667.0310538,27.349973917007446,1.0354941439257566 +1739502667.051025,27.36997389793396,50.76286888730258,1739502667.0510275,27.36997389793396,2.4303428052262124,1739502667.0510302,27.36997389793396,51.89838380774463,1739502667.0510328,27.36997389793396,51.453491024818234,1739502667.0510345,27.36997389793396,5.9979733270526525,1739502667.051036,27.36997389793396,1.379581336227799,1739502667.0510375,27.36997389793396,1.155088309988938,1739502667.0510387,27.36997389793396,0.6108,1739502667.05104,27.36997389793396,0.9922502691001882,1739502667.0510418,27.36997389793396,0.0,1739502667.051043,27.36997389793396,-0.04324387482556835,1739502667.0510447,27.36997389793396,1.0561012803277485,1739502667.0510461,27.36997389793396,1.0354941439257566 +1739502667.0709527,27.389973878860474,50.76286888730258,1739502667.0709555,27.389973878860474,2.4303428052262124,1739502667.0709586,27.389973878860474,51.89838380774463,1739502667.0709615,27.389973878860474,51.453491024818234,1739502667.0709627,27.389973878860474,5.9979733270526525,1739502667.0709646,27.389973878860474,1.379581336227799,1739502667.070966,27.389973878860474,1.155088309988938,1739502667.0709674,27.389973878860474,0.6108,1739502667.070969,27.389973878860474,0.9922502691001882,1739502667.0709705,27.389973878860474,0.0,1739502667.070972,27.389973878860474,-0.04324387482556835,1739502667.0709732,27.389973878860474,1.0561012803277485,1739502667.0709748,27.389973878860474,1.0354941439257566 +1739502667.0905442,27.409973859786987,50.76286888730258,1739502667.0905466,27.409973859786987,2.4303428052262124,1739502667.0905497,27.409973859786987,51.89838380774463,1739502667.0905526,27.409973859786987,51.453491024818234,1739502667.090554,27.409973859786987,5.9979733270526525,1739502667.0905561,27.409973859786987,1.379581336227799,1739502667.0905578,27.409973859786987,1.155088309988938,1739502667.0905592,27.409973859786987,0.6108,1739502667.0905604,27.409973859786987,0.9922502691001882,1739502667.090562,27.409973859786987,0.0,1739502667.0905633,27.409973859786987,-0.04324387482556835,1739502667.090565,27.409973859786987,1.0561012803277485,1739502667.0905662,27.409973859786987,1.0354941439257566 +1739502667.1108925,27.4299738407135,50.76286888730258,1739502667.1108956,27.4299738407135,2.4303428052262124,1739502667.1108985,27.4299738407135,51.89838380774463,1739502667.1109014,27.4299738407135,51.453491024818234,1739502667.1109025,27.4299738407135,5.9979733270526525,1739502667.1109042,27.4299738407135,1.379581336227799,1739502667.110906,27.4299738407135,1.155088309988938,1739502667.110907,27.4299738407135,0.6108,1739502667.1109087,27.4299738407135,0.9922502691001882,1739502667.1109102,27.4299738407135,0.0,1739502667.1109114,27.4299738407135,-0.04324387482556835,1739502667.110913,27.4299738407135,1.0561012803277485,1739502667.1109145,27.4299738407135,1.0354941439257566 +1739502667.1304228,27.449973821640015,50.76286888730258,1739502667.1304255,27.449973821640015,2.4303428052262124,1739502667.130428,27.449973821640015,51.89838380774463,1739502667.130431,27.449973821640015,51.453491024818234,1739502667.1304324,27.449973821640015,5.9979733270526525,1739502667.1304338,27.449973821640015,1.379581336227799,1739502667.1304352,27.449973821640015,1.155088309988938,1739502667.1304367,27.449973821640015,0.6108,1739502667.1304379,27.449973821640015,0.9922502691001882,1739502667.1304398,27.449973821640015,0.0,1739502667.130441,27.449973821640015,-0.04324387482556835,1739502667.1304424,27.449973821640015,1.0561012803277485,1739502667.130444,27.449973821640015,1.0354941439257566 +1739502667.1507654,27.46997380256653,50.81755918070452,1739502667.150768,27.46997380256653,2.5299408103897436,1739502667.1507711,27.46997380256653,52.08962780718099,1739502667.150774,27.46997380256653,51.380805241440164,1739502667.150776,27.46997380256653,6.16367811481744,1739502667.1507773,27.46997380256653,1.417015517573807,1739502667.1507788,27.46997380256653,1.2030655636273369,1739502667.1507804,27.46997380256653,0.6108,1739502667.1507816,27.46997380256653,0.9548875262211166,1739502667.1507833,27.46997380256653,0.0,1739502667.1507845,27.46997380256653,-0.09011876726547859,1739502667.1507862,27.46997380256653,1.0837029692702977,1739502667.1507874,27.46997380256653,1.030357879994875 +1739502667.1711307,27.489973783493042,50.81755918070452,1739502667.1711333,27.489973783493042,2.5299408103897436,1739502667.171136,27.489973783493042,52.08962780718099,1739502667.1711385,27.489973783493042,51.380805241440164,1739502667.1711402,27.489973783493042,6.16367811481744,1739502667.1711419,27.489973783493042,1.417015517573807,1739502667.171143,27.489973783493042,1.2030655636273369,1739502667.1711447,27.489973783493042,0.6108,1739502667.171146,27.489973783493042,0.9548875262211166,1739502667.1711478,27.489973783493042,0.0,1739502667.171149,27.489973783493042,-0.07547035377375833,1739502667.1711507,27.489973783493042,1.0837029692702977,1739502667.1711519,27.489973783493042,1.030357879994875 +1739502667.1911244,27.509973764419556,50.81755918070452,1739502667.191127,27.509973764419556,2.5299408103897436,1739502667.19113,27.509973764419556,52.08962780718099,1739502667.1911328,27.509973764419556,51.380805241440164,1739502667.191134,27.509973764419556,6.16367811481744,1739502667.191136,27.509973764419556,1.417015517573807,1739502667.1911373,27.509973764419556,1.2030655636273369,1739502667.1911385,27.509973764419556,0.6108,1739502667.19114,27.509973764419556,0.9548875262211166,1739502667.1911416,27.509973764419556,0.0,1739502667.1911426,27.509973764419556,-0.07547035377375833,1739502667.1911445,27.509973764419556,1.0837029692702977,1739502667.1911457,27.509973764419556,1.030357879994875 +1739502667.2110238,27.52997374534607,50.81755918070452,1739502667.211027,27.52997374534607,2.5299408103897436,1739502667.2110298,27.52997374534607,52.08962780718099,1739502667.2110329,27.52997374534607,51.380805241440164,1739502667.211034,27.52997374534607,6.16367811481744,1739502667.2110357,27.52997374534607,1.417015517573807,1739502667.2110372,27.52997374534607,1.2030655636273369,1739502667.2110388,27.52997374534607,0.6108,1739502667.2110398,27.52997374534607,0.9548875262211166,1739502667.2110417,27.52997374534607,0.0,1739502667.2110431,27.52997374534607,-0.07547035377375833,1739502667.2110443,27.52997374534607,1.0837029692702977,1739502667.211046,27.52997374534607,1.030357879994875 +1739502667.2309139,27.549973726272583,50.81755918070452,1739502667.2309165,27.549973726272583,2.5299408103897436,1739502667.2309196,27.549973726272583,52.08962780718099,1739502667.2309227,27.549973726272583,51.380805241440164,1739502667.2309241,27.549973726272583,6.16367811481744,1739502667.2309258,27.549973726272583,1.417015517573807,1739502667.230927,27.549973726272583,1.2030655636273369,1739502667.2309287,27.549973726272583,0.6108,1739502667.2309299,27.549973726272583,0.9548875262211166,1739502667.2309315,27.549973726272583,0.0,1739502667.2309327,27.549973726272583,-0.07547035377375833,1739502667.2309344,27.549973726272583,1.0837029692702977,1739502667.2309356,27.549973726272583,1.030357879994875 +1739502667.2504683,27.569973707199097,50.86916246364028,1739502667.250471,27.569973707199097,2.6303903854838637,1739502667.250474,27.569973707199097,52.22236451519019,1739502667.2504768,27.569973707199097,51.329048441906465,1739502667.2504783,27.569973707199097,6.267770599533365,1739502667.2504802,27.569973707199097,1.4450303343649342,1739502667.2504816,27.569973707199097,1.2009653456121931,1739502667.250483,27.569973707199097,0.6108,1739502667.2504842,27.569973707199097,0.9564932523813796,1739502667.250486,27.569973707199097,0.0,1739502667.250488,27.569973707199097,-0.061149106141662524,1739502667.2504897,27.569973707199097,1.111304658212847,1739502667.2504911,27.569973707199097,1.0221177513423683 +1739502667.270781,27.58997368812561,50.86916246364028,1739502667.2707837,27.58997368812561,2.6303903854838637,1739502667.2707868,27.58997368812561,52.22236451519019,1739502667.2707896,27.58997368812561,51.329048441906465,1739502667.270791,27.58997368812561,6.267770599533365,1739502667.270793,27.58997368812561,1.4450303343649342,1739502667.2707944,27.58997368812561,1.2009653456121931,1739502667.270796,27.58997368812561,0.6108,1739502667.2707973,27.58997368812561,0.9564932523813796,1739502667.270799,27.58997368812561,0.0,1739502667.2708004,27.58997368812561,-0.06562449896098865,1739502667.2708018,27.58997368812561,1.111304658212847,1739502667.2708032,27.58997368812561,1.0221177513423683 +1739502667.2905629,27.609973669052124,50.86916246364028,1739502667.2905657,27.609973669052124,2.6303903854838637,1739502667.2905686,27.609973669052124,52.22236451519019,1739502667.2905717,27.609973669052124,51.329048441906465,1739502667.2905734,27.609973669052124,6.267770599533365,1739502667.2905748,27.609973669052124,1.4450303343649342,1739502667.2905765,27.609973669052124,1.2009653456121931,1739502667.2905777,27.609973669052124,0.6108,1739502667.2905788,27.609973669052124,0.9564932523813796,1739502667.2905805,27.609973669052124,0.0,1739502667.290582,27.609973669052124,-0.06562449896098865,1739502667.2905834,27.609973669052124,1.111304658212847,1739502667.290585,27.609973669052124,1.0221177513423683 +1739502667.3113165,27.629973649978638,50.86916246364028,1739502667.311319,27.629973649978638,2.6303903854838637,1739502667.3113222,27.629973649978638,52.22236451519019,1739502667.3113246,27.629973649978638,51.329048441906465,1739502667.3113263,27.629973649978638,6.267770599533365,1739502667.311328,27.629973649978638,1.4450303343649342,1739502667.3113296,27.629973649978638,1.2009653456121931,1739502667.3113308,27.629973649978638,0.6108,1739502667.311332,27.629973649978638,0.9564932523813796,1739502667.3113337,27.629973649978638,0.0,1739502667.311335,27.629973649978638,-0.06562449896098865,1739502667.3113365,27.629973649978638,1.111304658212847,1739502667.3113377,27.629973649978638,1.0221177513423683 +1739502667.3306623,27.64997363090515,50.86916246364028,1739502667.3306646,27.64997363090515,2.6303903854838637,1739502667.330668,27.64997363090515,52.22236451519019,1739502667.3306708,27.64997363090515,51.329048441906465,1739502667.330672,27.64997363090515,6.267770599533365,1739502667.330674,27.64997363090515,1.4450303343649342,1739502667.3306754,27.64997363090515,1.2009653456121931,1739502667.3306768,27.64997363090515,0.6108,1739502667.330678,27.64997363090515,0.9564932523813796,1739502667.33068,27.64997363090515,0.0,1739502667.330681,27.64997363090515,-0.06562449896098865,1739502667.3306823,27.64997363090515,1.111304658212847,1739502667.330684,27.64997363090515,1.0221177513423683 +1739502667.3511875,27.669973611831665,50.86916246364028,1739502667.35119,27.669973611831665,2.6303903854838637,1739502667.3511934,27.669973611831665,52.22236451519019,1739502667.351196,27.669973611831665,51.329048441906465,1739502667.3511975,27.669973611831665,6.267770599533365,1739502667.3511992,27.669973611831665,1.4450303343649342,1739502667.3512008,27.669973611831665,1.2009653456121931,1739502667.351202,27.669973611831665,0.6108,1739502667.3512034,27.669973611831665,0.9564932523813796,1739502667.351205,27.669973611831665,0.0,1739502667.3512063,27.669973611831665,-0.06562449896098865,1739502667.3512077,27.669973611831665,1.111304658212847,1739502667.3512092,27.669973611831665,1.0221177513423683 +1739502667.3709812,27.68997359275818,50.91760553420527,1739502667.3709838,27.68997359275818,2.7314581160579436,1739502667.3709867,27.68997359275818,52.30823866157963,1739502667.3709896,27.68997359275818,51.295775368264266,1739502667.370991,27.68997359275818,6.331240977351508,1739502667.370993,27.68997359275818,1.4661267404316305,1739502667.3709943,27.68997359275818,1.1633809878876011,1739502667.3709958,27.68997359275818,0.6108,1739502667.370997,27.68997359275818,0.9856893267747936,1739502667.3709989,27.68997359275818,0.0,1739502667.3709998,27.68997359275818,-0.012823751552775795,1739502667.3710012,27.68997359275818,1.1389063471553962,1739502667.3710027,27.68997359275818,1.0150133227110392 +1739502667.3907948,27.709973573684692,50.91760553420527,1739502667.3907979,27.709973573684692,2.7314581160579436,1739502667.3908012,27.709973573684692,52.30823866157963,1739502667.390804,27.709973573684692,51.295775368264266,1739502667.3908055,27.709973573684692,6.331240977351508,1739502667.3908072,27.709973573684692,1.4661267404316305,1739502667.3908086,27.709973573684692,1.1633809878876011,1739502667.3908107,27.709973573684692,0.6108,1739502667.3908122,27.709973573684692,0.9856893267747936,1739502667.390814,27.709973573684692,0.0,1739502667.3908155,27.709973573684692,-0.029323995936245573,1739502667.390817,27.709973573684692,1.1389063471553962,1739502667.3908184,27.709973573684692,1.0150133227110392 +1739502667.411516,27.729973554611206,50.91760553420527,1739502667.4115188,27.729973554611206,2.7314581160579436,1739502667.4115214,27.729973554611206,52.30823866157963,1739502667.4115243,27.729973554611206,51.295775368264266,1739502667.411526,27.729973554611206,6.331240977351508,1739502667.4115276,27.729973554611206,1.4661267404316305,1739502667.4115293,27.729973554611206,1.1633809878876011,1739502667.4115305,27.729973554611206,0.6108,1739502667.4115317,27.729973554611206,0.9856893267747936,1739502667.4115334,27.729973554611206,0.0,1739502667.4115348,27.729973554611206,-0.029323995936245573,1739502667.4115365,27.729973554611206,1.1389063471553962,1739502667.411538,27.729973554611206,1.0150133227110392 +1739502667.4308274,27.74997353553772,50.91760553420527,1739502667.4308302,27.74997353553772,2.7314581160579436,1739502667.4308333,27.74997353553772,52.30823866157963,1739502667.4308362,27.74997353553772,51.295775368264266,1739502667.4308374,27.74997353553772,6.331240977351508,1739502667.4308393,27.74997353553772,1.4661267404316305,1739502667.4308407,27.74997353553772,1.1633809878876011,1739502667.4308422,27.74997353553772,0.6108,1739502667.4308434,27.74997353553772,0.9856893267747936,1739502667.4308455,27.74997353553772,0.0,1739502667.4308467,27.74997353553772,-0.029323995936245573,1739502667.4308484,27.74997353553772,1.1389063471553962,1739502667.43085,27.74997353553772,1.0150133227110392 +1739502667.4507,27.769973516464233,50.91760553420527,1739502667.4507027,27.769973516464233,2.7314581160579436,1739502667.4507058,27.769973516464233,52.30823866157963,1739502667.4507084,27.769973516464233,51.295775368264266,1739502667.45071,27.769973516464233,6.331240977351508,1739502667.4507117,27.769973516464233,1.4661267404316305,1739502667.4507132,27.769973516464233,1.1633809878876011,1739502667.4507146,27.769973516464233,0.6108,1739502667.450716,27.769973516464233,0.9856893267747936,1739502667.4507174,27.769973516464233,0.0,1739502667.4507186,27.769973516464233,-0.029323995936245573,1739502667.4507203,27.769973516464233,1.1389063471553962,1739502667.4507217,27.769973516464233,1.0150133227110392 +1739502667.4709861,27.789973497390747,50.962996274365544,1739502667.470989,27.789973497390747,2.8332781315387328,1739502667.470992,27.789973497390747,52.42755100577242,1739502667.4709947,27.789973497390747,51.24103499807973,1739502667.4709961,27.789973497390747,6.429889759469732,1739502667.470998,27.789973497390747,1.4936440344676385,1739502667.4709995,27.789973497390747,1.1591554692364376,1739502667.4710011,27.789973497390747,0.6108,1739502667.4710023,27.789973497390747,0.9890270038707942,1739502667.4710042,27.789973497390747,0.0,1739502667.4710054,27.789973497390747,-0.01975386310945819,1739502667.4710066,27.789973497390747,1.1665080360979454,1739502667.4710083,27.789973497390747,1.0117715354494585 +1739502667.4904606,27.80997347831726,50.962996274365544,1739502667.4904633,27.80997347831726,2.8332781315387328,1739502667.4904664,27.80997347831726,52.42755100577242,1739502667.4904692,27.80997347831726,51.24103499807973,1739502667.4904704,27.80997347831726,6.429889759469732,1739502667.490472,27.80997347831726,1.4936440344676385,1739502667.4904735,27.80997347831726,1.1591554692364376,1739502667.490475,27.80997347831726,0.6108,1739502667.4904766,27.80997347831726,0.9890270038707942,1739502667.490478,27.80997347831726,0.0,1739502667.4904795,27.80997347831726,-0.022744531578664295,1739502667.490481,27.80997347831726,1.1665080360979454,1739502667.4904823,27.80997347831726,1.0117715354494585 +1739502667.5106747,27.829973459243774,50.962996274365544,1739502667.5106776,27.829973459243774,2.8332781315387328,1739502667.5106804,27.829973459243774,52.42755100577242,1739502667.510683,27.829973459243774,51.24103499807973,1739502667.5106847,27.829973459243774,6.429889759469732,1739502667.5106862,27.829973459243774,1.4936440344676385,1739502667.5106876,27.829973459243774,1.1591554692364376,1739502667.510689,27.829973459243774,0.6108,1739502667.5106902,27.829973459243774,0.9890270038707942,1739502667.510692,27.829973459243774,0.0,1739502667.510693,27.829973459243774,-0.022744531578664295,1739502667.5106947,27.829973459243774,1.1665080360979454,1739502667.5106962,27.829973459243774,1.0117715354494585 +1739502667.5308192,27.849973440170288,50.962996274365544,1739502667.5308213,27.849973440170288,2.8332781315387328,1739502667.5308244,27.849973440170288,52.42755100577242,1739502667.530827,27.849973440170288,51.24103499807973,1739502667.5308285,27.849973440170288,6.429889759469732,1739502667.5308304,27.849973440170288,1.4936440344676385,1739502667.5308316,27.849973440170288,1.1591554692364376,1739502667.5308332,27.849973440170288,0.6108,1739502667.530835,27.849973440170288,0.9890270038707942,1739502667.5308366,27.849973440170288,0.0,1739502667.530838,27.849973440170288,-0.022744531578664295,1739502667.5308392,27.849973440170288,1.1665080360979454,1739502667.5308409,27.849973440170288,1.0117715354494585 +1739502667.5531256,27.8699734210968,50.962996274365544,1739502667.5531294,27.8699734210968,2.8332781315387328,1739502667.553134,27.8699734210968,52.42755100577242,1739502667.5531392,27.8699734210968,51.24103499807973,1739502667.5531423,27.8699734210968,6.429889759469732,1739502667.5531461,27.8699734210968,1.4936440344676385,1739502667.5531495,27.8699734210968,1.1591554692364376,1739502667.553153,27.8699734210968,0.6108,1739502667.5531564,27.8699734210968,0.9890270038707942,1739502667.55316,27.8699734210968,0.0,1739502667.5531635,27.8699734210968,-0.022744531578664295,1739502667.5531669,27.8699734210968,1.1665080360979454,1739502667.5531704,27.8699734210968,1.0117715354494585 +1739502667.573303,27.889973402023315,50.962996274365544,1739502667.5733066,27.889973402023315,2.8332781315387328,1739502667.5733113,27.889973402023315,52.42755100577242,1739502667.5733166,27.889973402023315,51.24103499807973,1739502667.5733197,27.889973402023315,6.429889759469732,1739502667.5733235,27.889973402023315,1.4936440344676385,1739502667.573327,27.889973402023315,1.1591554692364376,1739502667.5733304,27.889973402023315,0.6108,1739502667.573334,27.889973402023315,0.9890270038707942,1739502667.5733373,27.889973402023315,0.0,1739502667.573341,27.889973402023315,-0.022744531578664295,1739502667.5733445,27.889973402023315,1.1665080360979454,1739502667.5733485,27.889973402023315,1.0117715354494585 +1739502667.593095,27.90997338294983,51.00544228915263,1739502667.593099,27.90997338294983,2.9360282869739134,1739502667.593104,27.90997338294983,52.56656956060017,1739502667.593109,27.90997338294983,51.17355641375544,1739502667.593112,27.90997338294983,6.545826372475461,1739502667.593116,27.90997338294983,1.5242583385796629,1739502667.5931194,27.90997338294983,1.1715057945934466,1739502667.5931227,27.90997338294983,0.6108,1739502667.5931263,27.90997338294983,0.9793032752300489,1739502667.5931299,27.90997338294983,0.0,1739502667.5931334,27.90997338294983,-0.03334818769347787,1739502667.5931373,27.90997338294983,1.1941097250404946,1739502667.593141,27.90997338294983,1.0093378182150528 +1739502667.6133366,27.929973363876343,51.00544228915263,1739502667.6133404,27.929973363876343,2.9360282869739134,1739502667.6133456,27.929973363876343,52.56656956060017,1739502667.6133509,27.929973363876343,51.17355641375544,1739502667.613354,27.929973363876343,6.545826372475461,1739502667.6133578,27.929973363876343,1.5242583385796629,1739502667.6133614,27.929973363876343,1.1715057945934466,1739502667.6133647,27.929973363876343,0.6108,1739502667.6133683,27.929973363876343,0.9793032752300489,1739502667.6133718,27.929973363876343,0.0,1739502667.6133754,27.929973363876343,-0.030034542985003854,1739502667.613379,27.929973363876343,1.1941097250404946,1739502667.6133826,27.929973363876343,1.0093378182150528 +1739502667.6329584,27.949973344802856,51.00544228915263,1739502667.6329625,27.949973344802856,2.9360282869739134,1739502667.6329675,27.949973344802856,52.56656956060017,1739502667.6329727,27.949973344802856,51.17355641375544,1739502667.6329756,27.949973344802856,6.545826372475461,1739502667.6329796,27.949973344802856,1.5242583385796629,1739502667.6329832,27.949973344802856,1.1715057945934466,1739502667.6329868,27.949973344802856,0.6108,1739502667.6329904,27.949973344802856,0.9793032752300489,1739502667.632994,27.949973344802856,0.0,1739502667.6329975,27.949973344802856,-0.030034542985003854,1739502667.6330013,27.949973344802856,1.1941097250404946,1739502667.6330044,27.949973344802856,1.0093378182150528 +1739502667.653573,27.96997332572937,51.00544228915263,1739502667.6535769,27.96997332572937,2.9360282869739134,1739502667.6535819,27.96997332572937,52.56656956060017,1739502667.653587,27.96997332572937,51.17355641375544,1739502667.6535902,27.96997332572937,6.545826372475461,1739502667.653594,27.96997332572937,1.5242583385796629,1739502667.6535974,27.96997332572937,1.1715057945934466,1739502667.653601,27.96997332572937,0.6108,1739502667.6536045,27.96997332572937,0.9793032752300489,1739502667.6536086,27.96997332572937,0.0,1739502667.6536117,27.96997332572937,-0.030034542985003854,1739502667.6536155,27.96997332572937,1.1941097250404946,1739502667.6536186,27.96997332572937,1.0093378182150528 +1739502667.6729295,27.989973306655884,51.00544228915263,1739502667.6729324,27.989973306655884,2.9360282869739134,1739502667.6729355,27.989973306655884,52.56656956060017,1739502667.6729383,27.989973306655884,51.17355641375544,1739502667.6729395,27.989973306655884,6.545826372475461,1739502667.6729412,27.989973306655884,1.5242583385796629,1739502667.6729429,27.989973306655884,1.1715057945934466,1739502667.672944,27.989973306655884,0.6108,1739502667.6729457,27.989973306655884,0.9793032752300489,1739502667.6729474,27.989973306655884,0.0,1739502667.6729488,27.989973306655884,-0.030034542985003854,1739502667.6729503,27.989973306655884,1.1941097250404946,1739502667.6729522,27.989973306655884,1.0093378182150528 +1739502667.6913996,28.009973287582397,51.04492566356124,1739502667.6914022,28.009973287582397,3.0396195318412964,1739502667.6914053,28.009973287582397,52.63620423956039,1739502667.6914082,28.009973287582397,51.14068694054335,1739502667.6914093,28.009973287582397,6.599650134860268,1739502667.6914113,28.009973287582397,1.5439038077547458,1739502667.6914127,28.009973287582397,1.1276804060314878,1739502667.6914144,28.009973287582397,0.6108,1739502667.6914155,28.009973287582397,1.0142469409703683,1739502667.691417,28.009973287582397,0.0,1739502667.6914184,28.009973287582397,0.0255693875166962,1739502667.6914198,28.009973287582397,1.2217114139830438,1739502667.6914213,28.009973287582397,1.0060537931282039 +1739502667.7104862,28.02997326850891,51.04492566356124,1739502667.7104893,28.02997326850891,3.0396195318412964,1739502667.7104926,28.02997326850891,52.63620423956039,1739502667.7104952,28.02997326850891,51.14068694054335,1739502667.7104967,28.02997326850891,6.599650134860268,1739502667.7104986,28.02997326850891,1.5439038077547458,1739502667.7105,28.02997326850891,1.1276804060314878,1739502667.7105014,28.02997326850891,0.6108,1739502667.7105029,28.02997326850891,1.0142469409703683,1739502667.7105045,28.02997326850891,0.0,1739502667.7105057,28.02997326850891,0.008193147842164406,1739502667.710507,28.02997326850891,1.2217114139830438,1739502667.7105086,28.02997326850891,1.0060537931282039 +1739502667.7310755,28.049973249435425,51.04492566356124,1739502667.7310784,28.049973249435425,3.0396195318412964,1739502667.7310812,28.049973249435425,52.63620423956039,1739502667.7310839,28.049973249435425,51.14068694054335,1739502667.7310853,28.049973249435425,6.599650134860268,1739502667.7310867,28.049973249435425,1.5439038077547458,1739502667.7310884,28.049973249435425,1.1276804060314878,1739502667.7310896,28.049973249435425,0.6108,1739502667.7310913,28.049973249435425,1.0142469409703683,1739502667.731093,28.049973249435425,0.0,1739502667.7310946,28.049973249435425,0.008193147842164406,1739502667.731096,28.049973249435425,1.2217114139830438,1739502667.7310977,28.049973249435425,1.0060537931282039 +1739502667.7510672,28.06997323036194,51.04492566356124,1739502667.7510698,28.06997323036194,3.0396195318412964,1739502667.7510724,28.06997323036194,52.63620423956039,1739502667.7510753,28.06997323036194,51.14068694054335,1739502667.751077,28.06997323036194,6.599650134860268,1739502667.7510786,28.06997323036194,1.5439038077547458,1739502667.75108,28.06997323036194,1.1276804060314878,1739502667.7510815,28.06997323036194,0.6108,1739502667.7510827,28.06997323036194,1.0142469409703683,1739502667.7510843,28.06997323036194,0.0,1739502667.7510858,28.06997323036194,0.008193147842164406,1739502667.7510872,28.06997323036194,1.2217114139830438,1739502667.7510889,28.06997323036194,1.0060537931282039 +1739502667.7709303,28.089973211288452,51.04492566356124,1739502667.7709327,28.089973211288452,3.0396195318412964,1739502667.7709358,28.089973211288452,52.63620423956039,1739502667.7709384,28.089973211288452,51.14068694054335,1739502667.7709398,28.089973211288452,6.599650134860268,1739502667.7709417,28.089973211288452,1.5439038077547458,1739502667.7709432,28.089973211288452,1.1276804060314878,1739502667.7709446,28.089973211288452,0.6108,1739502667.7709458,28.089973211288452,1.0142469409703683,1739502667.7709472,28.089973211288452,0.0,1739502667.770949,28.089973211288452,0.008193147842164406,1739502667.77095,28.089973211288452,1.2217114139830438,1739502667.7709517,28.089973211288452,1.0060537931282039 +1739502667.790621,28.109973192214966,51.04492566356124,1739502667.7906232,28.109973192214966,3.0396195318412964,1739502667.7906258,28.109973192214966,52.63620423956039,1739502667.7906287,28.109973192214966,51.14068694054335,1739502667.79063,28.109973192214966,6.599650134860268,1739502667.7906318,28.109973192214966,1.5439038077547458,1739502667.790633,28.109973192214966,1.1276804060314878,1739502667.7906342,28.109973192214966,0.6108,1739502667.7906356,28.109973192214966,1.0142469409703683,1739502667.790637,28.109973192214966,0.0,1739502667.7906384,28.109973192214966,0.008193147842164406,1739502667.7906399,28.109973192214966,1.2217114139830438,1739502667.790641,28.109973192214966,1.0060537931282039 +1739502667.8111198,28.12997317314148,51.08149427490017,1739502667.8111222,28.12997317314148,3.1441477770375865,1739502667.8111253,28.12997317314148,52.637850478049835,1739502667.811128,28.12997317314148,51.1385329516113,1739502667.8111293,28.12997317314148,6.603177291736486,1739502667.8111308,28.12997317314148,1.55430802929555,1739502667.8111324,28.12997317314148,1.038847425625865,1739502667.8111336,28.12997317314148,0.6108,1739502667.811135,28.12997317314148,1.0889487609487287,1739502667.8111365,28.12997317314148,0.0,1739502667.8111377,28.12997317314148,0.11504192282245913,1739502667.811139,28.12997317314148,1.249313102925593,1739502667.8111405,28.12997317314148,1.0072971021999748 +1739502667.8307784,28.149973154067993,51.08149427490017,1739502667.8307807,28.149973154067993,3.1441477770375865,1739502667.8307838,28.149973154067993,52.637850478049835,1739502667.8307862,28.149973154067993,51.1385329516113,1739502667.8307877,28.149973154067993,6.603177291736486,1739502667.8307893,28.149973154067993,1.55430802929555,1739502667.8307908,28.149973154067993,1.038847425625865,1739502667.830792,28.149973154067993,0.6108,1739502667.8307931,28.149973154067993,1.0889487609487287,1739502667.8307948,28.149973154067993,0.0,1739502667.8307962,28.149973154067993,0.08165165874875391,1739502667.830798,28.149973154067993,1.249313102925593,1739502667.830799,28.149973154067993,1.0072971021999748 +1739502667.8509812,28.169973134994507,51.08149427490017,1739502667.8509834,28.169973134994507,3.1441477770375865,1739502667.8509862,28.169973134994507,52.637850478049835,1739502667.850989,28.169973134994507,51.1385329516113,1739502667.8509905,28.169973134994507,6.603177291736486,1739502667.8509924,28.169973134994507,1.55430802929555,1739502667.8509936,28.169973134994507,1.038847425625865,1739502667.8509953,28.169973134994507,0.6108,1739502667.8509963,28.169973134994507,1.0889487609487287,1739502667.850998,28.169973134994507,0.0,1739502667.8509994,28.169973134994507,0.08165165874875391,1739502667.8510008,28.169973134994507,1.249313102925593,1739502667.8510022,28.169973134994507,1.0072971021999748 +1739502667.870813,28.18997311592102,51.08149427490017,1739502667.8708153,28.18997311592102,3.1441477770375865,1739502667.8708186,28.18997311592102,52.637850478049835,1739502667.8708212,28.18997311592102,51.1385329516113,1739502667.8708227,28.18997311592102,6.603177291736486,1739502667.870824,28.18997311592102,1.55430802929555,1739502667.8708255,28.18997311592102,1.038847425625865,1739502667.870827,28.18997311592102,0.6108,1739502667.870828,28.18997311592102,1.0889487609487287,1739502667.8708296,28.18997311592102,0.0,1739502667.8708308,28.18997311592102,0.08165165874875391,1739502667.8708327,28.18997311592102,1.249313102925593,1739502667.8708339,28.18997311592102,1.0072971021999748 +1739502667.8905694,28.209973096847534,51.08149427490017,1739502667.8905718,28.209973096847534,3.1441477770375865,1739502667.8905747,28.209973096847534,52.637850478049835,1739502667.890577,28.209973096847534,51.1385329516113,1739502667.8905785,28.209973096847534,6.603177291736486,1739502667.89058,28.209973096847534,1.55430802929555,1739502667.8905816,28.209973096847534,1.038847425625865,1739502667.8905826,28.209973096847534,0.6108,1739502667.890584,28.209973096847534,1.0889487609487287,1739502667.8905857,28.209973096847534,0.0,1739502667.8905869,28.209973096847534,0.08165165874875391,1739502667.890588,28.209973096847534,1.249313102925593,1739502667.89059,28.209973096847534,1.0072971021999748 +1739502667.9114227,28.229973077774048,51.11531129458047,1739502667.911425,28.229973077774048,3.250113147973728,1739502667.9114277,28.229973077774048,52.93682256746448,1739502667.9114304,28.229973077774048,50.96220618947752,1739502667.911432,28.229973077774048,6.866162839092416,1739502667.9114335,28.229973077774048,1.6131114843092988,1739502667.911435,28.229973077774048,1.19400036168493,1739502667.9114363,28.229973077774048,0.6108,1739502667.9114375,28.229973077774048,0.9618376962436943,1739502667.9114392,28.229973077774048,0.0,1739502667.9114404,28.229973077774048,-0.11615902830290756,1739502667.9114418,28.229973077774048,1.2769147918681423,1739502667.9114435,28.229973077774048,1.0161808443133082 +1739502667.9307625,28.24997305870056,51.11531129458047,1739502667.9307644,28.24997305870056,3.250113147973728,1739502667.9307675,28.24997305870056,52.93682256746448,1739502667.9307702,28.24997305870056,50.96220618947752,1739502667.9307714,28.24997305870056,6.866162839092416,1739502667.930773,28.24997305870056,1.6131114843092988,1739502667.9307745,28.24997305870056,1.19400036168493,1739502667.930776,28.24997305870056,0.6108,1739502667.930777,28.24997305870056,0.9618376962436943,1739502667.9307787,28.24997305870056,0.0,1739502667.93078,28.24997305870056,-0.054343148069613934,1739502667.9307811,28.24997305870056,1.2769147918681423,1739502667.9307828,28.24997305870056,1.0161808443133082 +1739502667.9509988,28.269973039627075,51.11531129458047,1739502667.9510014,28.269973039627075,3.250113147973728,1739502667.9510043,28.269973039627075,52.93682256746448,1739502667.9510067,28.269973039627075,50.96220618947752,1739502667.951008,28.269973039627075,6.866162839092416,1739502667.9510098,28.269973039627075,1.6131114843092988,1739502667.9510112,28.269973039627075,1.19400036168493,1739502667.9510124,28.269973039627075,0.6108,1739502667.9510136,28.269973039627075,0.9618376962436943,1739502667.9510157,28.269973039627075,0.0,1739502667.951017,28.269973039627075,-0.054343148069613934,1739502667.9510183,28.269973039627075,1.2769147918681423,1739502667.9510198,28.269973039627075,1.0161808443133082 +1739502667.9708016,28.28997302055359,51.11531129458047,1739502667.970804,28.28997302055359,3.250113147973728,1739502667.9708068,28.28997302055359,52.93682256746448,1739502667.9708095,28.28997302055359,50.96220618947752,1739502667.9708107,28.28997302055359,6.866162839092416,1739502667.9708123,28.28997302055359,1.6131114843092988,1739502667.970814,28.28997302055359,1.19400036168493,1739502667.9708152,28.28997302055359,0.6108,1739502667.9708164,28.28997302055359,0.9618376962436943,1739502667.9708178,28.28997302055359,0.0,1739502667.970819,28.28997302055359,-0.054343148069613934,1739502667.9708207,28.28997302055359,1.2769147918681423,1739502667.9708219,28.28997302055359,1.0161808443133082 +1739502667.9906292,28.309973001480103,51.11531129458047,1739502667.9906313,28.309973001480103,3.250113147973728,1739502667.9906344,28.309973001480103,52.93682256746448,1739502667.990637,28.309973001480103,50.96220618947752,1739502667.9906385,28.309973001480103,6.866162839092416,1739502667.9906404,28.309973001480103,1.6131114843092988,1739502667.9906416,28.309973001480103,1.19400036168493,1739502667.9906433,28.309973001480103,0.6108,1739502667.9906442,28.309973001480103,0.9618376962436943,1739502667.9906456,28.309973001480103,0.0,1739502667.990647,28.309973001480103,-0.054343148069613934,1739502667.9906487,28.309973001480103,1.2769147918681423,1739502667.9906502,28.309973001480103,1.0161808443133082 +1739502668.0109465,28.329972982406616,51.11531129458047,1739502668.010949,28.329972982406616,3.250113147973728,1739502668.0109518,28.329972982406616,52.93682256746448,1739502668.0109544,28.329972982406616,50.96220618947752,1739502668.0109558,28.329972982406616,6.866162839092416,1739502668.0109575,28.329972982406616,1.6131114843092988,1739502668.010959,28.329972982406616,1.19400036168493,1739502668.01096,28.329972982406616,0.6108,1739502668.0109613,28.329972982406616,0.9618376962436943,1739502668.010963,28.329972982406616,0.0,1739502668.0109644,28.329972982406616,-0.054343148069613934,1739502668.0109658,28.329972982406616,1.2769147918681423,1739502668.010967,28.329972982406616,1.0161808443133082 +1739502668.0303411,28.34997296333313,51.146231070215634,1739502668.0303435,28.34997296333313,3.3570956061457498,1739502668.030346,28.34997296333313,53.07183027847615,1739502668.0303485,28.34997296333313,50.89024392093808,1739502668.0303497,28.34997296333313,6.962978455256597,1739502668.0303516,28.34997296333313,1.6416689575912404,1739502668.0303528,28.34997296333313,1.195832508791774,1739502668.0303545,28.34997296333313,0.6108,1739502668.0303557,28.34997296333313,0.9604289463887462,1739502668.0303574,28.34997296333313,0.0,1739502668.0303586,28.34997296333313,-0.045941509722442375,1739502668.03036,28.34997296333313,1.3045164808106915,1739502668.0303614,28.34997296333313,1.0089959698161006 +1739502668.0506907,28.369972944259644,51.146231070215634,1739502668.0506928,28.369972944259644,3.3570956061457498,1739502668.050696,28.369972944259644,53.07183027847615,1739502668.0506985,28.369972944259644,50.89024392093808,1739502668.0507,28.369972944259644,6.962978455256597,1739502668.0507016,28.369972944259644,1.6416689575912404,1739502668.0507028,28.369972944259644,1.195832508791774,1739502668.0507042,28.369972944259644,0.6108,1739502668.0507054,28.369972944259644,0.9604289463887462,1739502668.0507069,28.369972944259644,0.0,1739502668.0507083,28.369972944259644,-0.04856702342735442,1739502668.0507097,28.369972944259644,1.3045164808106915,1739502668.0507112,28.369972944259644,1.0089959698161006 +1739502668.0707588,28.389972925186157,51.146231070215634,1739502668.070761,28.389972925186157,3.3570956061457498,1739502668.070764,28.389972925186157,53.07183027847615,1739502668.0707667,28.389972925186157,50.89024392093808,1739502668.0707679,28.389972925186157,6.962978455256597,1739502668.0707693,28.389972925186157,1.6416689575912404,1739502668.0707707,28.389972925186157,1.195832508791774,1739502668.070772,28.389972925186157,0.6108,1739502668.0707734,28.389972925186157,0.9604289463887462,1739502668.070775,28.389972925186157,0.0,1739502668.070776,28.389972925186157,-0.04856702342735442,1739502668.0707777,28.389972925186157,1.3045164808106915,1739502668.0707788,28.389972925186157,1.0089959698161006 +1739502668.096123,28.40997290611267,51.146231070215634,1739502668.0961285,28.40997290611267,3.3570956061457498,1739502668.0961356,28.40997290611267,53.07183027847615,1739502668.096144,28.40997290611267,50.89024392093808,1739502668.0961483,28.40997290611267,6.962978455256597,1739502668.0961542,28.40997290611267,1.6416689575912404,1739502668.0961595,28.40997290611267,1.195832508791774,1739502668.0961647,28.40997290611267,0.6108,1739502668.0961697,28.40997290611267,0.9604289463887462,1739502668.0961752,28.40997290611267,0.0,1739502668.0961802,28.40997290611267,-0.04856702342735442,1739502668.0961857,28.40997290611267,1.3045164808106915,1739502668.096191,28.40997290611267,1.0089959698161006 +1739502668.1120558,28.429972887039185,51.146231070215634,1739502668.1120603,28.429972887039185,3.3570956061457498,1739502668.1120656,28.429972887039185,53.07183027847615,1739502668.1120703,28.429972887039185,50.89024392093808,1739502668.1120727,28.429972887039185,6.962978455256597,1739502668.1120758,28.429972887039185,1.6416689575912404,1739502668.1120784,28.429972887039185,1.195832508791774,1739502668.1120808,28.429972887039185,0.6108,1739502668.1120832,28.429972887039185,0.9604289463887462,1739502668.112086,28.429972887039185,0.0,1739502668.1120887,28.429972887039185,-0.04856702342735442,1739502668.1120913,28.429972887039185,1.3045164808106915,1739502668.1120937,28.429972887039185,1.0089959698161006 +1739502668.1378832,28.4499728679657,51.174024943189856,1739502668.137892,28.4499728679657,3.4642689867526233,1739502668.1379023,28.4499728679657,53.2357069514314,1739502668.137912,28.4499728679657,50.794927632562164,1739502668.1379173,28.4499728679657,7.082937620667067,1739502668.1379232,28.4499728679657,1.675177122165626,1739502668.1379282,28.4499728679657,1.2238704827979388,1739502668.1379328,28.4499728679657,0.6108,1739502668.1379373,28.4499728679657,0.9391259709887139,1739502668.137943,28.4499728679657,0.0,1739502668.1379476,28.4499728679657,-0.07180943563854668,1739502668.1379528,28.4499728679657,1.3321181697532407,1739502668.1379576,28.4499728679657,1.0036721480490995 +1739502668.1721783,28.489972829818726,51.174024943189856,1739502668.1721823,28.489972829818726,3.4642689867526233,1739502668.1721873,28.489972829818726,53.2357069514314,1739502668.172192,28.489972829818726,50.794927632562164,1739502668.172194,28.489972829818726,7.082937620667067,1739502668.1721973,28.489972829818726,1.675177122165626,1739502668.1722004,28.489972829818726,1.2238704827979388,1739502668.1722026,28.489972829818726,0.6108,1739502668.1722045,28.489972829818726,0.9391259709887139,1739502668.172207,28.489972829818726,0.0,1739502668.1722095,28.489972829818726,-0.06454617706038568,1739502668.1722116,28.489972829818726,1.3321181697532407,1739502668.1722145,28.489972829818726,1.0036721480490995 +1739502668.1944196,28.50997281074524,51.174024943189856,1739502668.1944246,28.50997281074524,3.4642689867526233,1739502668.19443,28.50997281074524,53.2357069514314,1739502668.194436,28.50997281074524,50.794927632562164,1739502668.194439,28.50997281074524,7.082937620667067,1739502668.1944425,28.50997281074524,1.675177122165626,1739502668.1944456,28.50997281074524,1.2238704827979388,1739502668.1944485,28.50997281074524,0.6108,1739502668.194451,28.50997281074524,0.9391259709887139,1739502668.1944544,28.50997281074524,0.0,1739502668.1944573,28.50997281074524,-0.06454617706038568,1739502668.1944604,28.50997281074524,1.3321181697532407,1739502668.1944635,28.50997281074524,1.0036721480490995 +1739502668.2110329,28.529972791671753,51.174024943189856,1739502668.2110355,28.529972791671753,3.4642689867526233,1739502668.2110388,28.529972791671753,53.2357069514314,1739502668.2110422,28.529972791671753,50.794927632562164,1739502668.2110436,28.529972791671753,7.082937620667067,1739502668.2110453,28.529972791671753,1.675177122165626,1739502668.2110472,28.529972791671753,1.2238704827979388,1739502668.2110486,28.529972791671753,0.6108,1739502668.2110503,28.529972791671753,0.9391259709887139,1739502668.2110522,28.529972791671753,0.0,1739502668.2110538,28.529972791671753,-0.06454617706038568,1739502668.2110553,28.529972791671753,1.3321181697532407,1739502668.2110574,28.529972791671753,1.0036721480490995 +1739502668.2304006,28.549972772598267,51.174024943189856,1739502668.2304025,28.549972772598267,3.4642689867526233,1739502668.230405,28.549972772598267,53.2357069514314,1739502668.230408,28.549972772598267,50.794927632562164,1739502668.2304091,28.549972772598267,7.082937620667067,1739502668.2304108,28.549972772598267,1.675177122165626,1739502668.2304122,28.549972772598267,1.2238704827979388,1739502668.2304137,28.549972772598267,0.6108,1739502668.2304275,28.549972772598267,0.9391259709887139,1739502668.230429,28.549972772598267,0.0,1739502668.23043,28.549972772598267,-0.06454617706038568,1739502668.2304313,28.549972772598267,1.3321181697532407,1739502668.2304325,28.549972772598267,1.0036721480490995 +1739502668.2511919,28.56997275352478,51.19869989201104,1739502668.251194,28.56997275352478,3.5715120586092475,1739502668.2511969,28.56997275352478,53.314161817754545,1739502668.2511995,28.56997275352478,50.75352967188019,1739502668.2512007,28.56997275352478,7.132001870364223,1739502668.2512023,28.56997275352478,1.6951814622596875,1739502668.2512038,28.56997275352478,1.1812575593790242,1739502668.2512052,28.56997275352478,0.6108,1739502668.2512062,28.56997275352478,0.9716930509197603,1739502668.2512076,28.56997275352478,0.0,1739502668.251209,28.56997275352478,-0.006805580790054003,1739502668.2512102,28.56997275352478,1.35971985869579,1739502668.251212,28.56997275352478,0.9965425798748273 +1739502668.2710452,28.589972734451294,51.19869989201104,1739502668.2710474,28.589972734451294,3.5715120586092475,1739502668.2710507,28.589972734451294,53.314161817754545,1739502668.271053,28.589972734451294,50.75352967188019,1739502668.2710543,28.589972734451294,7.132001870364223,1739502668.2710564,28.589972734451294,1.6951814622596875,1739502668.2710576,28.589972734451294,1.1812575593790242,1739502668.271059,28.589972734451294,0.6108,1739502668.2710602,28.589972734451294,0.9716930509197603,1739502668.2710617,28.589972734451294,0.0,1739502668.271063,28.589972734451294,-0.02484952895506698,1739502668.2710643,28.589972734451294,1.35971985869579,1739502668.2710657,28.589972734451294,0.9965425798748273 +1739502668.2910852,28.609972715377808,51.19869989201104,1739502668.2910876,28.609972715377808,3.5715120586092475,1739502668.2910907,28.609972715377808,53.314161817754545,1739502668.2910933,28.609972715377808,50.75352967188019,1739502668.2910945,28.609972715377808,7.132001870364223,1739502668.291096,28.609972715377808,1.6951814622596875,1739502668.2910974,28.609972715377808,1.1812575593790242,1739502668.2910986,28.609972715377808,0.6108,1739502668.2910998,28.609972715377808,0.9716930509197603,1739502668.2911012,28.609972715377808,0.0,1739502668.2911024,28.609972715377808,-0.02484952895506698,1739502668.291104,28.609972715377808,1.35971985869579,1739502668.291105,28.609972715377808,0.9965425798748273 +1739502668.3107154,28.62997269630432,51.19869989201104,1739502668.310718,28.62997269630432,3.5715120586092475,1739502668.3107207,28.62997269630432,53.314161817754545,1739502668.3107235,28.62997269630432,50.75352967188019,1739502668.310725,28.62997269630432,7.132001870364223,1739502668.3107266,28.62997269630432,1.6951814622596875,1739502668.3107278,28.62997269630432,1.1812575593790242,1739502668.3107295,28.62997269630432,0.6108,1739502668.3107307,28.62997269630432,0.9716930509197603,1739502668.3107324,28.62997269630432,0.0,1739502668.3107336,28.62997269630432,-0.02484952895506698,1739502668.3107347,28.62997269630432,1.35971985869579,1739502668.3107364,28.62997269630432,0.9965425798748273 +1739502668.3308663,28.649972677230835,51.19869989201104,1739502668.3308687,28.649972677230835,3.5715120586092475,1739502668.3308716,28.649972677230835,53.314161817754545,1739502668.3308742,28.649972677230835,50.75352967188019,1739502668.3308754,28.649972677230835,7.132001870364223,1739502668.3308768,28.649972677230835,1.6951814622596875,1739502668.3308787,28.649972677230835,1.1812575593790242,1739502668.33088,28.649972677230835,0.6108,1739502668.330881,28.649972677230835,0.9716930509197603,1739502668.3308825,28.649972677230835,0.0,1739502668.3308837,28.649972677230835,-0.02484952895506698,1739502668.3308852,28.649972677230835,1.35971985869579,1739502668.3308864,28.649972677230835,0.9965425798748273 +1739502668.3508692,28.66997265815735,51.22029140892946,1739502668.350872,28.66997265815735,3.6788330139243666,1739502668.3508754,28.66997265815735,53.413577742155454,1739502668.3508787,28.66997265815735,50.69119904163215,1739502668.3508801,28.66997265815735,7.202237409128557,1739502668.3508823,28.66997265815735,1.719847735806075,1739502668.3508837,28.66997265815735,1.1630469076063648,1739502668.3508854,28.66997265815735,0.6108,1739502668.3508868,28.66997265815735,0.9859528014759066,1739502668.3508885,28.66997265815735,0.0,1739502668.35089,28.66997265815735,-0.00010164190528857541,1739502668.3508916,28.66997265815735,1.3873215476383391,1739502668.350893,28.66997265815735,0.9937881631548727 +1739502668.3713796,28.689972639083862,51.22029140892946,1739502668.3713832,28.689972639083862,3.6788330139243666,1739502668.3713875,28.689972639083862,53.413577742155454,1739502668.3713915,28.689972639083862,50.69119904163215,1739502668.3713932,28.689972639083862,7.202237409128557,1739502668.3713956,28.689972639083862,1.719847735806075,1739502668.3713977,28.689972639083862,1.1630469076063648,1739502668.3713994,28.689972639083862,0.6108,1739502668.3714015,28.689972639083862,0.9859528014759066,1739502668.3714035,28.689972639083862,0.0,1739502668.3714056,28.689972639083862,-0.007835361678966146,1739502668.3714075,28.689972639083862,1.3873215476383391,1739502668.3714097,28.689972639083862,0.9937881631548727 +1739502668.3917506,28.709972620010376,51.22029140892946,1739502668.3917537,28.709972620010376,3.6788330139243666,1739502668.3917577,28.709972620010376,53.413577742155454,1739502668.391762,28.709972620010376,50.69119904163215,1739502668.391764,28.709972620010376,7.202237409128557,1739502668.3917663,28.709972620010376,1.719847735806075,1739502668.3917682,28.709972620010376,1.1630469076063648,1739502668.3917701,28.709972620010376,0.6108,1739502668.3917718,28.709972620010376,0.9859528014759066,1739502668.3917742,28.709972620010376,0.0,1739502668.391776,28.709972620010376,-0.007835361678966146,1739502668.3917782,28.709972620010376,1.3873215476383391,1739502668.3917801,28.709972620010376,0.9937881631548727 +1739502668.4116967,28.72997260093689,51.22029140892946,1739502668.4117,28.72997260093689,3.6788330139243666,1739502668.4117045,28.72997260093689,53.413577742155454,1739502668.4117086,28.72997260093689,50.69119904163215,1739502668.4117107,28.72997260093689,7.202237409128557,1739502668.4117134,28.72997260093689,1.719847735806075,1739502668.411715,28.72997260093689,1.1630469076063648,1739502668.4117172,28.72997260093689,0.6108,1739502668.4117188,28.72997260093689,0.9859528014759066,1739502668.4117212,28.72997260093689,0.0,1739502668.4117234,28.72997260093689,-0.007835361678966146,1739502668.4117253,28.72997260093689,1.3873215476383391,1739502668.4117274,28.72997260093689,0.9937881631548727 +1739502668.4311664,28.749972581863403,51.22029140892946,1739502668.4311697,28.749972581863403,3.6788330139243666,1739502668.4311738,28.749972581863403,53.413577742155454,1739502668.4311776,28.749972581863403,50.69119904163215,1739502668.4311798,28.749972581863403,7.202237409128557,1739502668.4311824,28.749972581863403,1.719847735806075,1739502668.4311843,28.749972581863403,1.1630469076063648,1739502668.4311862,28.749972581863403,0.6108,1739502668.4311879,28.749972581863403,0.9859528014759066,1739502668.4311903,28.749972581863403,0.0,1739502668.4311924,28.749972581863403,-0.007835361678966146,1739502668.4311943,28.749972581863403,1.3873215476383391,1739502668.4311962,28.749972581863403,0.9937881631548727 +1739502668.4518793,28.769972562789917,51.22029140892946,1739502668.4518821,28.769972562789917,3.6788330139243666,1739502668.4518867,28.769972562789917,53.413577742155454,1739502668.4518907,28.769972562789917,50.69119904163215,1739502668.4518924,28.769972562789917,7.202237409128557,1739502668.451895,28.769972562789917,1.719847735806075,1739502668.4518974,28.769972562789917,1.1630469076063648,1739502668.451899,28.769972562789917,0.6108,1739502668.451901,28.769972562789917,0.9859528014759066,1739502668.4519033,28.769972562789917,0.0,1739502668.4519053,28.769972562789917,-0.007835361678966146,1739502668.4519074,28.769972562789917,1.3873215476383391,1739502668.4519093,28.769972562789917,0.9937881631548727 +1739502668.47113,28.78997254371643,51.23888067802692,1739502668.4711335,28.78997254371643,3.7865253034714446,1739502668.4711375,28.78997254371643,53.61364862531078,1739502668.4711413,28.78997254371643,50.55624149272735,1739502668.4711432,28.78997254371643,7.348008877154067,1739502668.4711456,28.78997254371643,1.7601721997567545,1739502668.4711478,28.78997254371643,1.2272573141099012,1739502668.4711497,28.78997254371643,0.6108,1739502668.4711514,28.78997254371643,0.9365848860381581,1739502668.4711537,28.78997254371643,0.0,1739502668.4711556,28.78997254371643,-0.07861746448066483,1739502668.4711578,28.78997254371643,1.4149232365808884,1739502668.4711597,28.78997254371643,0.9930829288906692 +1739502668.4980872,28.809972524642944,51.23888067802692,1739502668.4980955,28.809972524642944,3.7865253034714446,1739502668.4981058,28.809972524642944,53.61364862531078,1739502668.4981158,28.809972524642944,50.55624149272735,1739502668.4981208,28.809972524642944,7.348008877154067,1739502668.4981272,28.809972524642944,1.7601721997567545,1739502668.4981322,28.809972524642944,1.2272573141099012,1739502668.4981368,28.809972524642944,0.6108,1739502668.4981415,28.809972524642944,0.9365848860381581,1739502668.498147,28.809972524642944,0.0,1739502668.498152,28.809972524642944,-0.05649804285251103,1739502668.498157,28.809972524642944,1.4149232365808884,1739502668.498162,28.809972524642944,0.9930829288906692 +1739502668.5261295,28.839972496032715,51.23888067802692,1739502668.5261378,28.839972496032715,3.7865253034714446,1739502668.5261486,28.839972496032715,53.61364862531078,1739502668.5261588,28.839972496032715,50.55624149272735,1739502668.5261638,28.839972496032715,7.348008877154067,1739502668.5261698,28.839972496032715,1.7601721997567545,1739502668.5261753,28.839972496032715,1.2272573141099012,1739502668.5261903,28.839972496032715,0.6108,1739502668.5262043,28.839972496032715,0.9365848860381581,1739502668.526213,28.839972496032715,0.0,1739502668.526225,28.839972496032715,-0.05649804285251103,1739502668.5262332,28.839972496032715,1.4149232365808884,1739502668.526241,28.839972496032715,0.9930829288906692 +1739502668.550008,28.85997247695923,51.23888067802692,1739502668.5500183,28.85997247695923,3.7865253034714446,1739502668.5500307,28.85997247695923,53.61364862531078,1739502668.550042,28.85997247695923,50.55624149272735,1739502668.550047,28.85997247695923,7.348008877154067,1739502668.550054,28.85997247695923,1.7601721997567545,1739502668.5500596,28.85997247695923,1.2272573141099012,1739502668.550065,28.85997247695923,0.6108,1739502668.5500708,28.85997247695923,0.9365848860381581,1739502668.5500772,28.85997247695923,0.0,1739502668.5500824,28.85997247695923,-0.05649804285251103,1739502668.5500886,28.85997247695923,1.4149232365808884,1739502668.5500948,28.85997247695923,0.9930829288906692 +1739502668.5626264,28.879972457885742,51.23888067802692,1739502668.56263,28.879972457885742,3.7865253034714446,1739502668.5626345,28.879972457885742,53.61364862531078,1739502668.5626388,28.879972457885742,50.55624149272735,1739502668.562641,28.879972457885742,7.348008877154067,1739502668.5626435,28.879972457885742,1.7601721997567545,1739502668.5626454,28.879972457885742,1.2272573141099012,1739502668.5626478,28.879972457885742,0.6108,1739502668.5626495,28.879972457885742,0.9365848860381581,1739502668.562652,28.879972457885742,0.0,1739502668.5626543,28.879972457885742,-0.05649804285251103,1739502668.5626562,28.879972457885742,1.4149232365808884,1739502668.5626585,28.879972457885742,0.9930829288906692 +1739502668.5820873,28.899972438812256,51.254442419460545,1739502668.58209,28.899972438812256,3.8943447252683416,1739502668.582093,28.899972438812256,53.73649130023683,1739502668.5820963,28.899972438812256,50.47845365218066,1739502668.582098,28.899972438812256,7.4265463478193405,1739502668.5821002,28.899972438812256,1.7870507598913727,1739502668.582102,28.899972438812256,1.2214526393185032,1739502668.5821035,28.899972438812256,0.6108,1739502668.5821052,28.899972438812256,0.9409442566380992,1739502668.5821068,28.899972438812256,0.0,1739502668.5821085,28.899972438812256,-0.04121288185508482,1739502668.5821102,28.899972438812256,1.4425249255234376,1739502668.5821118,28.899972438812256,0.9869337544366732 +1739502668.6027932,28.91997241973877,51.254442419460545,1739502668.602796,28.91997241973877,3.8943447252683416,1739502668.6027997,28.91997241973877,53.73649130023683,1739502668.6028028,28.91997241973877,50.47845365218066,1739502668.6028042,28.91997241973877,7.4265463478193405,1739502668.602806,28.91997241973877,1.7870507598913727,1739502668.6028078,28.91997241973877,1.2214526393185032,1739502668.6028094,28.91997241973877,0.6108,1739502668.6028109,28.91997241973877,0.9409442566380992,1739502668.6028128,28.91997241973877,0.0,1739502668.6028142,28.91997241973877,-0.045989497798573975,1739502668.6028156,28.91997241973877,1.4425249255234376,1739502668.6028175,28.91997241973877,0.9869337544366732 +1739502668.6226869,28.939972400665283,51.254442419460545,1739502668.6226895,28.939972400665283,3.8943447252683416,1739502668.6226928,28.939972400665283,53.73649130023683,1739502668.6226962,28.939972400665283,50.47845365218066,1739502668.6226978,28.939972400665283,7.4265463478193405,1739502668.6226997,28.939972400665283,1.7870507598913727,1739502668.6227016,28.939972400665283,1.2214526393185032,1739502668.6227028,28.939972400665283,0.6108,1739502668.6227043,28.939972400665283,0.9409442566380992,1739502668.6227062,28.939972400665283,0.0,1739502668.6227076,28.939972400665283,-0.045989497798573975,1739502668.6227098,28.939972400665283,1.4425249255234376,1739502668.6227112,28.939972400665283,0.9869337544366732 +1739502668.6428657,28.959972381591797,51.254442419460545,1739502668.6428685,28.959972381591797,3.8943447252683416,1739502668.6428719,28.959972381591797,53.73649130023683,1739502668.642875,28.959972381591797,50.47845365218066,1739502668.6428764,28.959972381591797,7.4265463478193405,1739502668.6428783,28.959972381591797,1.7870507598913727,1739502668.6428797,28.959972381591797,1.2214526393185032,1739502668.6428814,28.959972381591797,0.6108,1739502668.6428828,28.959972381591797,0.9409442566380992,1739502668.6428845,28.959972381591797,0.0,1739502668.642886,28.959972381591797,-0.045989497798573975,1739502668.6428876,28.959972381591797,1.4425249255234376,1739502668.6428893,28.959972381591797,0.9869337544366732 +1739502668.662112,28.97997236251831,51.254442419460545,1739502668.6621146,28.97997236251831,3.8943447252683416,1739502668.6621182,28.97997236251831,53.73649130023683,1739502668.6621215,28.97997236251831,50.47845365218066,1739502668.662123,28.97997236251831,7.4265463478193405,1739502668.6621253,28.97997236251831,1.7870507598913727,1739502668.6621268,28.97997236251831,1.2214526393185032,1739502668.6621287,28.97997236251831,0.6108,1739502668.6621299,28.97997236251831,0.9409442566380992,1739502668.662132,28.97997236251831,0.0,1739502668.6621335,28.97997236251831,-0.045989497798573975,1739502668.6621351,28.97997236251831,1.4425249255234376,1739502668.6621366,28.97997236251831,0.9869337544366732 +1739502668.6820714,28.999972343444824,51.266949315596854,1739502668.682074,28.999972343444824,4.001925103129183,1739502668.6820772,28.999972343444824,53.84386624838429,1739502668.6820798,28.999972343444824,50.40768635415465,1739502668.682081,28.999972343444824,7.493288554177723,1739502668.682083,28.999972343444824,1.812111421628833,1739502668.682084,28.999972343444824,1.2057937755127,1739502668.6820853,28.999972343444824,0.6108,1739502668.6820867,28.999972343444824,0.9528056905245168,1739502668.6820881,28.999972343444824,0.0,1739502668.6820896,28.999972343444824,-0.021396313932027657,1739502668.6820908,28.999972343444824,1.4701266144659868,1739502668.682092,28.999972343444824,0.9818873794537647 +1739502668.7022254,29.019972324371338,51.266949315596854,1739502668.7022274,29.019972324371338,4.001925103129183,1739502668.7022302,29.019972324371338,53.84386624838429,1739502668.7022328,29.019972324371338,50.40768635415465,1739502668.702234,29.019972324371338,7.493288554177723,1739502668.7022357,29.019972324371338,1.812111421628833,1739502668.702237,29.019972324371338,1.2057937755127,1739502668.7022383,29.019972324371338,0.6108,1739502668.7022395,29.019972324371338,0.9528056905245168,1739502668.7022407,29.019972324371338,0.0,1739502668.7022421,29.019972324371338,-0.029081688929247895,1739502668.7022433,29.019972324371338,1.4701266144659868,1739502668.7022445,29.019972324371338,0.9818873794537647 +1739502668.721684,29.03997230529785,51.266949315596854,1739502668.7216861,29.03997230529785,4.001925103129183,1739502668.7216885,29.03997230529785,53.84386624838429,1739502668.7216911,29.03997230529785,50.40768635415465,1739502668.7216923,29.03997230529785,7.493288554177723,1739502668.721694,29.03997230529785,1.812111421628833,1739502668.7216952,29.03997230529785,1.2057937755127,1739502668.7216966,29.03997230529785,0.6108,1739502668.7216976,29.03997230529785,0.9528056905245168,1739502668.721699,29.03997230529785,0.0,1739502668.7217002,29.03997230529785,-0.029081688929247895,1739502668.7217016,29.03997230529785,1.4701266144659868,1739502668.7217026,29.03997230529785,0.9818873794537647 +1739502668.7421427,29.059972286224365,51.266949315596854,1739502668.7421458,29.059972286224365,4.001925103129183,1739502668.7421498,29.059972286224365,53.84386624838429,1739502668.742154,29.059972286224365,50.40768635415465,1739502668.7421556,29.059972286224365,7.493288554177723,1739502668.7421584,29.059972286224365,1.812111421628833,1739502668.74216,29.059972286224365,1.2057937755127,1739502668.7421618,29.059972286224365,0.6108,1739502668.742163,29.059972286224365,0.9528056905245168,1739502668.7421722,29.059972286224365,0.0,1739502668.7421782,29.059972286224365,-0.029081688929247895,1739502668.7421846,29.059972286224365,1.4701266144659868,1739502668.7421863,29.059972286224365,0.9818873794537647 +1739502668.761755,29.07997226715088,51.266949315596854,1739502668.761757,29.07997226715088,4.001925103129183,1739502668.7617598,29.07997226715088,53.84386624838429,1739502668.7617624,29.07997226715088,50.40768635415465,1739502668.7617633,29.07997226715088,7.493288554177723,1739502668.761765,29.07997226715088,1.812111421628833,1739502668.7617664,29.07997226715088,1.2057937755127,1739502668.7617676,29.07997226715088,0.6108,1739502668.761769,29.07997226715088,0.9528056905245168,1739502668.7617705,29.07997226715088,0.0,1739502668.7617717,29.07997226715088,-0.029081688929247895,1739502668.761773,29.07997226715088,1.4701266144659868,1739502668.7617743,29.07997226715088,0.9818873794537647 +1739502668.7816024,29.099972248077393,51.266949315596854,1739502668.7816045,29.099972248077393,4.001925103129183,1739502668.7816072,29.099972248077393,53.84386624838429,1739502668.7816098,29.099972248077393,50.40768635415465,1739502668.781611,29.099972248077393,7.493288554177723,1739502668.7816126,29.099972248077393,1.812111421628833,1739502668.7816138,29.099972248077393,1.2057937755127,1739502668.781615,29.099972248077393,0.6108,1739502668.7816162,29.099972248077393,0.9528056905245168,1739502668.7816176,29.099972248077393,0.0,1739502668.7816188,29.099972248077393,-0.029081688929247895,1739502668.7816205,29.099972248077393,1.4701266144659868,1739502668.7816217,29.099972248077393,0.9818873794537647 +1739502668.8017697,29.119972229003906,51.27644271424494,1739502668.801772,29.119972229003906,4.109365661867949,1739502668.8017747,29.119972229003906,53.99293654410807,1739502668.8017776,29.119972229003906,50.301376771383886,1739502668.801779,29.119972229003906,7.588917846279991,1739502668.8017805,29.119972229003906,1.8440159069810937,1739502668.8017817,29.119972229003906,1.2264820220581045,1739502668.8017833,29.119972229003906,0.6108,1739502668.8017848,29.119972229003906,0.9371659676771033,1739502668.8017864,29.119972229003906,0.0,1739502668.8017876,29.119972229003906,-0.04741557542617229,1739502668.8017893,29.119972229003906,1.497728303408536,1739502668.8017905,29.119972229003906,0.9788521998165365 +1739502668.821707,29.13997220993042,51.27644271424494,1739502668.8217094,29.13997220993042,4.109365661867949,1739502668.821712,29.13997220993042,53.99293654410807,1739502668.8217149,29.13997220993042,50.301376771383886,1739502668.8217163,29.13997220993042,7.588917846279991,1739502668.821718,29.13997220993042,1.8440159069810937,1739502668.8217194,29.13997220993042,1.2264820220581045,1739502668.821721,29.13997220993042,0.6108,1739502668.8217223,29.13997220993042,0.9371659676771033,1739502668.821724,29.13997220993042,0.0,1739502668.8217251,29.13997220993042,-0.04168623213943323,1739502668.8217268,29.13997220993042,1.497728303408536,1739502668.821728,29.13997220993042,0.9788521998165365 +1739502668.8417227,29.159972190856934,51.27644271424494,1739502668.8417249,29.159972190856934,4.109365661867949,1739502668.8417275,29.159972190856934,53.99293654410807,1739502668.8417304,29.159972190856934,50.301376771383886,1739502668.8417315,29.159972190856934,7.588917846279991,1739502668.8417335,29.159972190856934,1.8440159069810937,1739502668.8417346,29.159972190856934,1.2264820220581045,1739502668.8417358,29.159972190856934,0.6108,1739502668.8417373,29.159972190856934,0.9371659676771033,1739502668.8417387,29.159972190856934,0.0,1739502668.8417401,29.159972190856934,-0.04168623213943323,1739502668.8417413,29.159972190856934,1.497728303408536,1739502668.8417428,29.159972190856934,0.9788521998165365 +1739502668.8618593,29.179972171783447,51.27644271424494,1739502668.861862,29.179972171783447,4.109365661867949,1739502668.861865,29.179972171783447,53.99293654410807,1739502668.8618677,29.179972171783447,50.301376771383886,1739502668.8618693,29.179972171783447,7.588917846279991,1739502668.861871,29.179972171783447,1.8440159069810937,1739502668.8618727,29.179972171783447,1.2264820220581045,1739502668.861874,29.179972171783447,0.6108,1739502668.8618755,29.179972171783447,0.9371659676771033,1739502668.8618772,29.179972171783447,0.0,1739502668.8618789,29.179972171783447,-0.04168623213943323,1739502668.8618803,29.179972171783447,1.497728303408536,1739502668.861882,29.179972171783447,0.9788521998165365 +1739502668.881848,29.19997215270996,51.27644271424494,1739502668.8818505,29.19997215270996,4.109365661867949,1739502668.8818536,29.19997215270996,53.99293654410807,1739502668.8818567,29.19997215270996,50.301376771383886,1739502668.8818583,29.19997215270996,7.588917846279991,1739502668.8818603,29.19997215270996,1.8440159069810937,1739502668.881862,29.19997215270996,1.2264820220581045,1739502668.8818634,29.19997215270996,0.6108,1739502668.881865,29.19997215270996,0.9371659676771033,1739502668.8818665,29.19997215270996,0.0,1739502668.8818681,29.19997215270996,-0.04168623213943323,1739502668.8818696,29.19997215270996,1.497728303408536,1739502668.881871,29.19997215270996,0.9788521998165365 +1739502668.9019036,29.219972133636475,51.2829426463818,1739502668.901906,29.219972133636475,4.216613497061765,1739502668.9019096,29.219972133636475,54.07109689191094,1739502668.9019122,29.219972133636475,50.24875824083117,1739502668.901914,29.219972133636475,7.6336162306940984,1739502668.9019163,29.219972133636475,1.8646901855550937,1739502668.9019175,29.219972133636475,1.1884207318285136,1739502668.901919,29.219972133636475,0.6108,1739502668.9019203,29.219972133636475,0.9661406513193578,1739502668.9019222,29.219972133636475,0.0,1739502668.9019237,29.219972133636475,0.007085998391138791,1739502668.901925,29.219972133636475,1.5253299923510852,1739502668.9019268,29.219972133636475,0.9742959849620187 +1739502668.9218657,29.23997211456299,51.2829426463818,1739502668.921868,29.23997211456299,4.216613497061765,1739502668.9218712,29.23997211456299,54.07109689191094,1739502668.9218738,29.23997211456299,50.24875824083117,1739502668.9218755,29.23997211456299,7.6336162306940984,1739502668.9218771,29.23997211456299,1.8646901855550937,1739502668.921879,29.23997211456299,1.1884207318285136,1739502668.9218805,29.23997211456299,0.6108,1739502668.921882,29.23997211456299,0.9661406513193578,1739502668.9218836,29.23997211456299,0.0,1739502668.9218853,29.23997211456299,-0.008155333642660967,1739502668.9218864,29.23997211456299,1.5253299923510852,1739502668.921888,29.23997211456299,0.9742959849620187 +1739502668.9419458,29.259972095489502,51.2829426463818,1739502668.941951,29.259972095489502,4.216613497061765,1739502668.9419556,29.259972095489502,54.07109689191094,1739502668.9419587,29.259972095489502,50.24875824083117,1739502668.94196,29.259972095489502,7.6336162306940984,1739502668.9419622,29.259972095489502,1.8646901855550937,1739502668.9419637,29.259972095489502,1.1884207318285136,1739502668.941965,29.259972095489502,0.6108,1739502668.9419665,29.259972095489502,0.9661406513193578,1739502668.9419682,29.259972095489502,0.0,1739502668.9419696,29.259972095489502,-0.008155333642660967,1739502668.9419713,29.259972095489502,1.5253299923510852,1739502668.9419727,29.259972095489502,0.9742959849620187 +1739502668.9618661,29.279972076416016,51.2829426463818,1739502668.9618685,29.279972076416016,4.216613497061765,1739502668.9618716,29.279972076416016,54.07109689191094,1739502668.9618745,29.279972076416016,50.24875824083117,1739502668.961876,29.279972076416016,7.6336162306940984,1739502668.9618778,29.279972076416016,1.8646901855550937,1739502668.9618793,29.279972076416016,1.1884207318285136,1739502668.961881,29.279972076416016,0.6108,1739502668.961882,29.279972076416016,0.9661406513193578,1739502668.961884,29.279972076416016,0.0,1739502668.9618855,29.279972076416016,-0.008155333642660967,1739502668.961887,29.279972076416016,1.5253299923510852,1739502668.9618883,29.279972076416016,0.9742959849620187 +1739502668.9819448,29.29997205734253,51.2829426463818,1739502668.9819472,29.29997205734253,4.216613497061765,1739502668.9819505,29.29997205734253,54.07109689191094,1739502668.9819534,29.29997205734253,50.24875824083117,1739502668.981955,29.29997205734253,7.6336162306940984,1739502668.981957,29.29997205734253,1.8646901855550937,1739502668.9819584,29.29997205734253,1.1884207318285136,1739502668.9819596,29.29997205734253,0.6108,1739502668.9819615,29.29997205734253,0.9661406513193578,1739502668.981963,29.29997205734253,0.0,1739502668.9819646,29.29997205734253,-0.008155333642660967,1739502668.981966,29.29997205734253,1.5253299923510852,1739502668.9819677,29.29997205734253,0.9742959849620187 +1739502669.0081062,29.319972038269043,51.2829426463818,1739502669.0081158,29.319972038269043,4.216613497061765,1739502669.0081263,29.319972038269043,54.07109689191094,1739502669.0081365,29.319972038269043,50.24875824083117,1739502669.0081413,29.319972038269043,7.6336162306940984,1739502669.0081477,29.319972038269043,1.8646901855550937,1739502669.0081527,29.319972038269043,1.1884207318285136,1739502669.008158,29.319972038269043,0.6108,1739502669.008163,29.319972038269043,0.9661406513193578,1739502669.0081685,29.319972038269043,0.0,1739502669.0081735,29.319972038269043,-0.008155333642660967,1739502669.0081787,29.319972038269043,1.5253299923510852,1739502669.0081837,29.319972038269043,0.9742959849620187 +1739502669.0219216,29.339972019195557,51.28646967912529,1739502669.0219243,29.339972019195557,4.32370873086624,1739502669.0219283,29.339972019195557,54.17115707217145,1739502669.021931,29.339972019195557,50.17216065609314,1739502669.0219324,29.339972019195557,7.696139172701053,1739502669.021934,29.339972019195557,1.8899200689863644,1739502669.0219355,29.339972019195557,1.1743752841370059,1739502669.0219371,29.339972019195557,0.6108,1739502669.0219383,29.339972019195557,0.9770577731874058,1739502669.02194,29.339972019195557,0.0,1739502669.0219412,29.339972019195557,0.0085839848036056,1739502669.0219429,29.339972019195557,1.5529316812936345,1739502669.0219445,29.339972019195557,0.9737048288279959 +1739502669.041669,29.35997200012207,51.28646967912529,1739502669.0416708,29.35997200012207,4.32370873086624,1739502669.041674,29.35997200012207,54.17115707217145,1739502669.0416765,29.35997200012207,50.17216065609314,1739502669.0416777,29.35997200012207,7.696139172701053,1739502669.0416796,29.35997200012207,1.8899200689863644,1739502669.0416808,29.35997200012207,1.1743752841370059,1739502669.0416822,29.35997200012207,0.6108,1739502669.0416834,29.35997200012207,0.9770577731874058,1739502669.041685,29.35997200012207,0.0,1739502669.0416863,29.35997200012207,0.003352944359409915,1739502669.0416875,29.35997200012207,1.5529316812936345,1739502669.041689,29.35997200012207,0.9737048288279959 +1739502669.0616963,29.379971981048584,51.28646967912529,1739502669.0616987,29.379971981048584,4.32370873086624,1739502669.0617013,29.379971981048584,54.17115707217145,1739502669.061704,29.379971981048584,50.17216065609314,1739502669.061705,29.379971981048584,7.696139172701053,1739502669.061707,29.379971981048584,1.8899200689863644,1739502669.0617082,29.379971981048584,1.1743752841370059,1739502669.06171,29.379971981048584,0.6108,1739502669.061711,29.379971981048584,0.9770577731874058,1739502669.0617123,29.379971981048584,0.0,1739502669.061714,29.379971981048584,0.003352944359409915,1739502669.0617151,29.379971981048584,1.5529316812936345,1739502669.0617166,29.379971981048584,0.9737048288279959 +1739502669.089278,29.399971961975098,51.28646967912529,1739502669.089289,29.399971961975098,4.32370873086624,1739502669.0893023,29.399971961975098,54.17115707217145,1739502669.0893135,29.399971961975098,50.17216065609314,1739502669.089319,29.399971961975098,7.696139172701053,1739502669.089326,29.399971961975098,1.8899200689863644,1739502669.0893319,29.399971961975098,1.1743752841370059,1739502669.089338,29.399971961975098,0.6108,1739502669.0893433,29.399971961975098,0.9770577731874058,1739502669.0893645,29.399971961975098,0.0,1739502669.0893693,29.399971961975098,0.003352944359409915,1739502669.0893755,29.399971961975098,1.5529316812936345,1739502669.0893815,29.399971961975098,0.9737048288279959 +1739502669.1038787,29.41997194290161,51.28646967912529,1739502669.103883,29.41997194290161,4.32370873086624,1739502669.1038897,29.41997194290161,54.17115707217145,1739502669.1038947,29.41997194290161,50.17216065609314,1739502669.1038978,29.41997194290161,7.696139172701053,1739502669.1039011,29.41997194290161,1.8899200689863644,1739502669.1039038,29.41997194290161,1.1743752841370059,1739502669.1039064,29.41997194290161,0.6108,1739502669.103909,29.41997194290161,0.9770577731874058,1739502669.1039119,29.41997194290161,0.0,1739502669.1039145,29.41997194290161,0.003352944359409915,1739502669.1039174,29.41997194290161,1.5529316812936345,1739502669.1039202,29.41997194290161,0.9737048288279959 +1739502669.1234276,29.439971923828125,51.28703928045949,1739502669.123431,29.439971923828125,4.430827216195938,1739502669.123435,29.439971923828125,54.345856065072894,1739502669.1234388,29.439971923828125,50.03228739613409,1739502669.1234412,29.439971923828125,7.8019474387463275,1739502669.1234434,29.439971923828125,1.9271154007670748,1739502669.1234455,29.439971923828125,1.2218681779033929,1739502669.1234477,29.439971923828125,0.6108,1739502669.123449,29.439971923828125,0.9406315097084551,1739502669.1234515,29.439971923828125,0.0,1739502669.1234531,29.439971923828125,-0.05015097783791825,1739502669.123455,29.439971923828125,1.5805333702361837,1739502669.1234567,29.439971923828125,0.9740625008972308 +1739502669.1433365,29.45997190475464,51.28703928045949,1739502669.1433396,29.45997190475464,4.430827216195938,1739502669.1433434,29.45997190475464,54.345856065072894,1739502669.143347,29.45997190475464,50.03228739613409,1739502669.143349,29.45997190475464,7.8019474387463275,1739502669.1433513,29.45997190475464,1.9271154007670748,1739502669.143353,29.45997190475464,1.2218681779033929,1739502669.1433551,29.45997190475464,0.6108,1739502669.1433566,29.45997190475464,0.9406315097084551,1739502669.1433587,29.45997190475464,0.0,1739502669.1433606,29.45997190475464,-0.03343099118877568,1739502669.1433623,29.45997190475464,1.5805333702361837,1739502669.1433647,29.45997190475464,0.9740625008972308 +1739502669.163354,29.479971885681152,51.28703928045949,1739502669.1633575,29.479971885681152,4.430827216195938,1739502669.1633615,29.479971885681152,54.345856065072894,1739502669.1633651,29.479971885681152,50.03228739613409,1739502669.1633673,29.479971885681152,7.8019474387463275,1739502669.1633692,29.479971885681152,1.9271154007670748,1739502669.1633713,29.479971885681152,1.2218681779033929,1739502669.163373,29.479971885681152,0.6108,1739502669.163375,29.479971885681152,0.9406315097084551,1739502669.1633768,29.479971885681152,0.0,1739502669.1633787,29.479971885681152,-0.03343099118877568,1739502669.1633806,29.479971885681152,1.5805333702361837,1739502669.1633828,29.479971885681152,0.9740625008972308 +1739502669.1830356,29.499971866607666,51.28703928045949,1739502669.1830387,29.499971866607666,4.430827216195938,1739502669.1830425,29.499971866607666,54.345856065072894,1739502669.1830463,29.499971866607666,50.03228739613409,1739502669.1830482,29.499971866607666,7.8019474387463275,1739502669.1830504,29.499971866607666,1.9271154007670748,1739502669.1830525,29.499971866607666,1.2218681779033929,1739502669.1830544,29.499971866607666,0.6108,1739502669.183056,29.499971866607666,0.9406315097084551,1739502669.1830583,29.499971866607666,0.0,1739502669.1830602,29.499971866607666,-0.03343099118877568,1739502669.183062,29.499971866607666,1.5805333702361837,1739502669.1830637,29.499971866607666,0.9740625008972308 +1739502669.2058315,29.51997184753418,51.28703928045949,1739502669.205836,29.51997184753418,4.430827216195938,1739502669.205841,29.51997184753418,54.345856065072894,1739502669.2058456,29.51997184753418,50.03228739613409,1739502669.2058473,29.51997184753418,7.8019474387463275,1739502669.20585,29.51997184753418,1.9271154007670748,1739502669.2058516,29.51997184753418,1.2218681779033929,1739502669.2058535,29.51997184753418,0.6108,1739502669.2058554,29.51997184753418,0.9406315097084551,1739502669.2058578,29.51997184753418,0.0,1739502669.2058597,29.51997184753418,-0.03343099118877568,1739502669.2058616,29.51997184753418,1.5805333702361837,1739502669.2058637,29.51997184753418,0.9740625008972308 +1739502669.2238426,29.539971828460693,51.28703928045949,1739502669.2238455,29.539971828460693,4.430827216195938,1739502669.2238495,29.539971828460693,54.345856065072894,1739502669.2238533,29.539971828460693,50.03228739613409,1739502669.223855,29.539971828460693,7.8019474387463275,1739502669.2238574,29.539971828460693,1.9271154007670748,1739502669.2238593,29.539971828460693,1.2218681779033929,1739502669.223861,29.539971828460693,0.6108,1739502669.223863,29.539971828460693,0.9406315097084551,1739502669.2238648,29.539971828460693,0.0,1739502669.2238667,29.539971828460693,-0.03343099118877568,1739502669.2238686,29.539971828460693,1.5805333702361837,1739502669.2238705,29.539971828460693,0.9740625008972308 +1739502669.25591,29.559971809387207,51.28465774264606,1739502669.2559192,29.559971809387207,4.537729038449298,1739502669.2559302,29.559971809387207,54.45590196602243,1739502669.2559407,29.559971809387207,49.9497262390568,1739502669.2559457,29.559971809387207,7.861933279435291,1739502669.2559521,29.559971809387207,1.9526633994298583,1739502669.2559574,29.559971809387207,1.2099083104405213,1739502669.2559621,29.559971809387207,0.6108,1739502669.2559671,29.559971809387207,0.9496745647676575,1739502669.2559729,29.559971809387207,0.0,1739502669.2559776,29.559971809387207,-0.014463829605130952,1739502669.255983,29.559971809387207,1.608135059178733,1739502669.2559881,29.559971809387207,0.9700656362538801 +1739502669.2848563,29.599971771240234,51.28465774264606,1739502669.2848613,29.599971771240234,4.537729038449298,1739502669.284867,29.599971771240234,54.45590196602243,1739502669.2848725,29.599971771240234,49.9497262390568,1739502669.284875,29.599971771240234,7.861933279435291,1739502669.2848785,29.599971771240234,1.9526633994298583,1739502669.2848814,29.599971771240234,1.2099083104405213,1739502669.284884,29.599971771240234,0.6108,1739502669.2848866,29.599971771240234,0.9496745647676575,1739502669.28489,29.599971771240234,0.0,1739502669.2848923,29.599971771240234,-0.020391071486222545,1739502669.2848952,29.599971771240234,1.608135059178733,1739502669.284898,29.599971771240234,0.9700656362538801 +1739502669.306282,29.619971752166748,51.28465774264606,1739502669.3062887,29.619971752166748,4.537729038449298,1739502669.3062975,29.619971752166748,54.45590196602243,1739502669.3063037,29.619971752166748,49.9497262390568,1739502669.306307,29.619971752166748,7.861933279435291,1739502669.3063111,29.619971752166748,1.9526633994298583,1739502669.3063142,29.619971752166748,1.2099083104405213,1739502669.306317,29.619971752166748,0.6108,1739502669.306321,29.619971752166748,0.9496745647676575,1739502669.306324,29.619971752166748,0.0,1739502669.3063276,29.619971752166748,-0.020391071486222545,1739502669.3063312,29.619971752166748,1.608135059178733,1739502669.3063345,29.619971752166748,0.9700656362538801 +1739502669.3241274,29.63997173309326,51.28465774264606,1739502669.3241305,29.63997173309326,4.537729038449298,1739502669.324134,29.63997173309326,54.45590196602243,1739502669.3241377,29.63997173309326,49.9497262390568,1739502669.3241396,29.63997173309326,7.861933279435291,1739502669.3241417,29.63997173309326,1.9526633994298583,1739502669.3241436,29.63997173309326,1.2099083104405213,1739502669.3241453,29.63997173309326,0.6108,1739502669.3241472,29.63997173309326,0.9496745647676575,1739502669.3241491,29.63997173309326,0.0,1739502669.324151,29.63997173309326,-0.020391071486222545,1739502669.3241532,29.63997173309326,1.608135059178733,1739502669.3241549,29.63997173309326,0.9700656362538801 +1739502669.3438148,29.659971714019775,51.279343743527996,1739502669.3438172,29.659971714019775,4.644176671039832,1739502669.3438203,29.659971714019775,54.614108735412216,1739502669.3438232,29.659971714019775,49.821976384962674,1739502669.3438244,29.659971714019775,7.947151283567967,1739502669.3438258,29.659971714019775,1.9863321834037386,1739502669.3438272,29.659971714019775,1.2399495609029203,1739502669.3438287,29.659971714019775,0.6108,1739502669.34383,29.659971714019775,0.9271231105927804,1739502669.3438313,29.659971714019775,0.0,1739502669.3438325,29.659971714019775,-0.04983048014058825,1739502669.3438342,29.659971714019775,1.6357367481212821,1739502669.3438356,29.659971714019775,0.9677537694970065 +1739502669.3634598,29.67997169494629,51.279343743527996,1739502669.3634624,29.67997169494629,4.644176671039832,1739502669.3634655,29.67997169494629,54.614108735412216,1739502669.3634686,29.67997169494629,49.821976384962674,1739502669.3634698,29.67997169494629,7.947151283567967,1739502669.3634715,29.67997169494629,1.9863321834037386,1739502669.3634732,29.67997169494629,1.2399495609029203,1739502669.3634746,29.67997169494629,0.6108,1739502669.363476,29.67997169494629,0.9271231105927804,1739502669.3634777,29.67997169494629,0.0,1739502669.3634791,29.67997169494629,-0.040630658904226125,1739502669.3634806,29.67997169494629,1.6357367481212821,1739502669.363482,29.67997169494629,0.9677537694970065 +1739502669.384998,29.699971675872803,51.279343743527996,1739502669.385001,29.699971675872803,4.644176671039832,1739502669.385004,29.699971675872803,54.614108735412216,1739502669.3850071,29.699971675872803,49.821976384962674,1739502669.3850088,29.699971675872803,7.947151283567967,1739502669.3850105,29.699971675872803,1.9863321834037386,1739502669.385012,29.699971675872803,1.2399495609029203,1739502669.3850133,29.699971675872803,0.6108,1739502669.3850145,29.699971675872803,0.9271231105927804,1739502669.385016,29.699971675872803,0.0,1739502669.3850174,29.699971675872803,-0.040630658904226125,1739502669.3850188,29.699971675872803,1.6357367481212821,1739502669.3850205,29.699971675872803,0.9677537694970065 +1739502669.403325,29.719971656799316,51.279343743527996,1739502669.4033272,29.719971656799316,4.644176671039832,1739502669.4033303,29.719971656799316,54.614108735412216,1739502669.403333,29.719971656799316,49.821976384962674,1739502669.4033341,29.719971656799316,7.947151283567967,1739502669.403336,29.719971656799316,1.9863321834037386,1739502669.4033372,29.719971656799316,1.2399495609029203,1739502669.4033387,29.719971656799316,0.6108,1739502669.40334,29.719971656799316,0.9271231105927804,1739502669.4033415,29.719971656799316,0.0,1739502669.4033425,29.719971656799316,-0.040630658904226125,1739502669.4033442,29.719971656799316,1.6357367481212821,1739502669.4033453,29.719971656799316,0.9677537694970065 +1739502669.4229498,29.73997163772583,51.279343743527996,1739502669.422952,29.73997163772583,4.644176671039832,1739502669.4229546,29.73997163772583,54.614108735412216,1739502669.422957,29.73997163772583,49.821976384962674,1739502669.4229584,29.73997163772583,7.947151283567967,1739502669.42296,29.73997163772583,1.9863321834037386,1739502669.4229617,29.73997163772583,1.2399495609029203,1739502669.422963,29.73997163772583,0.6108,1739502669.4229643,29.73997163772583,0.9271231105927804,1739502669.4229658,29.73997163772583,0.0,1739502669.422967,29.73997163772583,-0.040630658904226125,1739502669.4229684,29.73997163772583,1.6357367481212821,1739502669.4229696,29.73997163772583,0.9677537694970065 +1739502669.4430902,29.759971618652344,51.279343743527996,1739502669.4430928,29.759971618652344,4.644176671039832,1739502669.4430952,29.759971618652344,54.614108735412216,1739502669.4430978,29.759971618652344,49.821976384962674,1739502669.4430997,29.759971618652344,7.947151283567967,1739502669.4431012,29.759971618652344,1.9863321834037386,1739502669.4431024,29.759971618652344,1.2399495609029203,1739502669.4431038,29.759971618652344,0.6108,1739502669.4431047,29.759971618652344,0.9271231105927804,1739502669.4431064,29.759971618652344,0.0,1739502669.4431076,29.759971618652344,-0.040630658904226125,1739502669.4431088,29.759971618652344,1.6357367481212821,1739502669.4431105,29.759971618652344,0.9677537694970065 +1739502669.4650154,29.779971599578857,51.271123333442496,1739502669.4650176,29.779971599578857,4.750067208471215,1739502669.4650204,29.779971599578857,54.69719249701436,1739502669.465023,29.779971599578857,49.75954781348303,1739502669.4650245,29.779971599578857,7.986517341063742,1739502669.4650261,29.779971599578857,2.007736061686445,1739502669.4650276,29.779971599578857,1.2060269313719993,1739502669.4650295,29.779971599578857,0.6108,1739502669.4650307,29.779971599578857,0.9526279853146208,1739502669.465032,29.779971599578857,0.0,1739502669.4650335,29.779971599578857,0.003211645908907032,1739502669.465035,29.779971599578857,1.6633384370638313,1739502669.4650366,29.779971599578857,0.963117068642716 +1739502669.48298,29.79997158050537,51.271123333442496,1739502669.4829824,29.79997158050537,4.750067208471215,1739502669.482985,29.79997158050537,54.69719249701436,1739502669.4829874,29.79997158050537,49.75954781348303,1739502669.4829888,29.79997158050537,7.986517341063742,1739502669.4829905,29.79997158050537,2.007736061686445,1739502669.482992,29.79997158050537,1.2060269313719993,1739502669.4829931,29.79997158050537,0.6108,1739502669.4829943,29.79997158050537,0.9526279853146208,1739502669.482996,29.79997158050537,0.0,1739502669.4829972,29.79997158050537,-0.010489083328095172,1739502669.482999,29.79997158050537,1.6633384370638313,1739502669.4830003,29.79997158050537,0.963117068642716 +1739502669.5031073,29.819971561431885,51.271123333442496,1739502669.50311,29.819971561431885,4.750067208471215,1739502669.503113,29.819971561431885,54.69719249701436,1739502669.503116,29.819971561431885,49.75954781348303,1739502669.5031173,29.819971561431885,7.986517341063742,1739502669.503119,29.819971561431885,2.007736061686445,1739502669.5031204,29.819971561431885,1.2060269313719993,1739502669.5031219,29.819971561431885,0.6108,1739502669.5031233,29.819971561431885,0.9526279853146208,1739502669.503125,29.819971561431885,0.0,1739502669.5031266,29.819971561431885,-0.010489083328095172,1739502669.503128,29.819971561431885,1.6633384370638313,1739502669.5031295,29.819971561431885,0.963117068642716 +1739502669.5231285,29.8399715423584,51.271123333442496,1739502669.5231311,29.8399715423584,4.750067208471215,1739502669.5231342,29.8399715423584,54.69719249701436,1739502669.5231373,29.8399715423584,49.75954781348303,1739502669.5231388,29.8399715423584,7.986517341063742,1739502669.5231407,29.8399715423584,2.007736061686445,1739502669.5231419,29.8399715423584,1.2060269313719993,1739502669.5231435,29.8399715423584,0.6108,1739502669.523145,29.8399715423584,0.9526279853146208,1739502669.5231464,29.8399715423584,0.0,1739502669.5231478,29.8399715423584,-0.010489083328095172,1739502669.5231493,29.8399715423584,1.6633384370638313,1739502669.523151,29.8399715423584,0.963117068642716 +1739502669.5432827,29.859971523284912,51.271123333442496,1739502669.5432851,29.859971523284912,4.750067208471215,1739502669.543289,29.859971523284912,54.69719249701436,1739502669.5432918,29.859971523284912,49.75954781348303,1739502669.5432937,29.859971523284912,7.986517341063742,1739502669.5432959,29.859971523284912,2.007736061686445,1739502669.5432973,29.859971523284912,1.2060269313719993,1739502669.5432987,29.859971523284912,0.6108,1739502669.5433004,29.859971523284912,0.9526279853146208,1739502669.543302,29.859971523284912,0.0,1739502669.5433037,29.859971523284912,-0.010489083328095172,1739502669.5433054,29.859971523284912,1.6633384370638313,1739502669.543307,29.859971523284912,0.963117068642716 +1739502669.5634098,29.879971504211426,51.260017776037174,1739502669.5634124,29.879971504211426,4.855358629228681,1739502669.563416,29.879971504211426,54.85595339944647,1739502669.5634189,29.879971504211426,49.624966532008045,1739502669.5634205,29.879971504211426,8.066203146363867,1739502669.5634224,29.879971504211426,2.041798883373426,1739502669.563424,29.879971504211426,1.2384291547610147,1739502669.5634258,29.879971504211426,0.6108,1739502669.5634272,29.879971504211426,0.9282514796226669,1739502669.5634296,29.879971504211426,0.0,1739502669.5634313,29.879971504211426,-0.044238847506355816,1739502669.5634327,29.879971504211426,1.6909401260063806,1739502669.5634346,29.879971504211426,0.9619435189082899 +1739502669.583261,29.89997148513794,51.260017776037174,1739502669.5832636,29.89997148513794,4.855358629228681,1739502669.5832672,29.89997148513794,54.85595339944647,1739502669.5832703,29.89997148513794,49.624966532008045,1739502669.583272,29.89997148513794,8.066203146363867,1739502669.583274,29.89997148513794,2.041798883373426,1739502669.5832756,29.89997148513794,1.2384291547610147,1739502669.583277,29.89997148513794,0.6108,1739502669.5832787,29.89997148513794,0.9282514796226669,1739502669.5832806,29.89997148513794,0.0,1739502669.5832822,29.89997148513794,-0.03369203928562303,1739502669.5832837,29.89997148513794,1.6909401260063806,1739502669.5832856,29.89997148513794,0.9619435189082899 +1739502669.6034148,29.919971466064453,51.260017776037174,1739502669.6034179,29.919971466064453,4.855358629228681,1739502669.6034212,29.919971466064453,54.85595339944647,1739502669.6034243,29.919971466064453,49.624966532008045,1739502669.6034257,29.919971466064453,8.066203146363867,1739502669.603428,29.919971466064453,2.041798883373426,1739502669.6034293,29.919971466064453,1.2384291547610147,1739502669.603431,29.919971466064453,0.6108,1739502669.6034324,29.919971466064453,0.9282514796226669,1739502669.6034343,29.919971466064453,0.0,1739502669.6034358,29.919971466064453,-0.03369203928562303,1739502669.6034377,29.919971466064453,1.6909401260063806,1739502669.603439,29.919971466064453,0.9619435189082899 +1739502669.6232972,29.939971446990967,51.260017776037174,1739502669.6232998,29.939971446990967,4.855358629228681,1739502669.6233034,29.939971446990967,54.85595339944647,1739502669.6233065,29.939971446990967,49.624966532008045,1739502669.623308,29.939971446990967,8.066203146363867,1739502669.6233099,29.939971446990967,2.041798883373426,1739502669.6233115,29.939971446990967,1.2384291547610147,1739502669.6233132,29.939971446990967,0.6108,1739502669.6233146,29.939971446990967,0.9282514796226669,1739502669.6233165,29.939971446990967,0.0,1739502669.623318,29.939971446990967,-0.03369203928562303,1739502669.6233196,29.939971446990967,1.6909401260063806,1739502669.623321,29.939971446990967,0.9619435189082899 +1739502669.6433008,29.95997142791748,51.260017776037174,1739502669.6433034,29.95997142791748,4.855358629228681,1739502669.6433067,29.95997142791748,54.85595339944647,1739502669.6433098,29.95997142791748,49.624966532008045,1739502669.6433113,29.95997142791748,8.066203146363867,1739502669.6433134,29.95997142791748,2.041798883373426,1739502669.6433148,29.95997142791748,1.2384291547610147,1739502669.6433165,29.95997142791748,0.6108,1739502669.643318,29.95997142791748,0.9282514796226669,1739502669.6433198,29.95997142791748,0.0,1739502669.6433213,29.95997142791748,-0.03369203928562303,1739502669.643323,29.95997142791748,1.6909401260063806,1739502669.6433244,29.95997142791748,0.9619435189082899 +1739502669.6635091,29.979971408843994,51.260017776037174,1739502669.663512,29.979971408843994,4.855358629228681,1739502669.6635156,29.979971408843994,54.85595339944647,1739502669.663519,29.979971408843994,49.624966532008045,1739502669.6635206,29.979971408843994,8.066203146363867,1739502669.6635222,29.979971408843994,2.041798883373426,1739502669.6635242,29.979971408843994,1.2384291547610147,1739502669.6635256,29.979971408843994,0.6108,1739502669.663527,29.979971408843994,0.9282514796226669,1739502669.6635287,29.979971408843994,0.0,1739502669.6635306,29.979971408843994,-0.03369203928562303,1739502669.663532,29.979971408843994,1.6909401260063806,1739502669.663534,29.979971408843994,0.9619435189082899 +1739502669.6851568,29.999971389770508,51.24604701077133,1739502669.68516,29.999971389770508,4.960036000753799,1739502669.6851635,29.999971389770508,54.95589043784319,1739502669.6851668,29.999971389770508,49.54458746937684,1739502669.6851683,29.999971389770508,8.111225016703541,1739502669.6851704,29.999971389770508,2.065884743029347,1739502669.685172,29.999971389770508,1.2190409550679555,1739502669.6851735,29.999971389770508,0.6108,1739502669.685175,29.999971389770508,0.9427614173971139,1739502669.685177,29.999971389770508,0.0,1739502669.6851785,29.999971389770508,-0.006909753123853512,1739502669.6851804,29.999971389770508,1.7185418149489298,1739502669.685182,29.999971389770508,0.9580406404339725 +1739502669.703638,30.01997137069702,51.24604701077133,1739502669.703641,30.01997137069702,4.960036000753799,1739502669.7036445,30.01997137069702,54.95589043784319,1739502669.7036479,30.01997137069702,49.54458746937684,1739502669.7036493,30.01997137069702,8.111225016703541,1739502669.7036514,30.01997137069702,2.065884743029347,1739502669.703653,30.01997137069702,1.2190409550679555,1739502669.7036548,30.01997137069702,0.6108,1739502669.7036562,30.01997137069702,0.9427614173971139,1739502669.7036583,30.01997137069702,0.0,1739502669.7036598,30.01997137069702,-0.01527922303685858,1739502669.7036612,30.01997137069702,1.7185418149489298,1739502669.703663,30.01997137069702,0.9580406404339725 +1739502669.724633,30.039971351623535,51.24604701077133,1739502669.724638,30.039971351623535,4.960036000753799,1739502669.724644,30.039971351623535,54.95589043784319,1739502669.7246487,30.039971351623535,49.54458746937684,1739502669.7246518,30.039971351623535,8.111225016703541,1739502669.724655,30.039971351623535,2.065884743029347,1739502669.7246573,30.039971351623535,1.2190409550679555,1739502669.7246604,30.039971351623535,0.6108,1739502669.724663,30.039971351623535,0.9427614173971139,1739502669.7246659,30.039971351623535,0.0,1739502669.7246687,30.039971351623535,-0.01527922303685858,1739502669.7246876,30.039971351623535,1.7185418149489298,1739502669.7246914,30.039971351623535,0.9580406404339725 +1739502669.7434523,30.05997133255005,51.24604701077133,1739502669.7434554,30.05997133255005,4.960036000753799,1739502669.7434587,30.05997133255005,54.95589043784319,1739502669.7434618,30.05997133255005,49.54458746937684,1739502669.7434635,30.05997133255005,8.111225016703541,1739502669.7434654,30.05997133255005,2.065884743029347,1739502669.743467,30.05997133255005,1.2190409550679555,1739502669.7434685,30.05997133255005,0.6108,1739502669.7434702,30.05997133255005,0.9427614173971139,1739502669.743472,30.05997133255005,0.0,1739502669.7434738,30.05997133255005,-0.01527922303685858,1739502669.7434757,30.05997133255005,1.7185418149489298,1739502669.7434773,30.05997133255005,0.9580406404339725 +1739502669.7633424,30.079971313476562,51.24604701077133,1739502669.763345,30.079971313476562,4.960036000753799,1739502669.7633483,30.079971313476562,54.95589043784319,1739502669.7633512,30.079971313476562,49.54458746937684,1739502669.7633529,30.079971313476562,8.111225016703541,1739502669.7633548,30.079971313476562,2.065884743029347,1739502669.7633564,30.079971313476562,1.2190409550679555,1739502669.763358,30.079971313476562,0.6108,1739502669.7633595,30.079971313476562,0.9427614173971139,1739502669.7633615,30.079971313476562,0.0,1739502669.7633631,30.079971313476562,-0.01527922303685858,1739502669.7633646,30.079971313476562,1.7185418149489298,1739502669.7633662,30.079971313476562,0.9580406404339725 +1739502669.783594,30.099971294403076,51.22924192706406,1739502669.7835968,30.099971294403076,5.0639796824833425,1739502669.7836003,30.099971294403076,54.97110417790889,1739502669.7836034,30.099971294403076,49.534196370928065,1739502669.783605,30.099971294403076,8.116892888584694,1739502669.783607,30.099971294403076,2.0776401536723714,1739502669.783609,30.099971294403076,1.136473070186046,1739502669.7836106,30.099971294403076,0.6108,1739502669.7836123,30.099971294403076,1.0071376280268611,1739502669.783614,30.099971294403076,0.0,1739502669.7836156,30.099971294403076,0.0808151979452264,1739502669.783617,30.099971294403076,1.746143503891479,1739502669.783619,30.099971294403076,0.956351956327428 +1739502669.8036284,30.11997127532959,51.22924192706406,1739502669.803633,30.11997127532959,5.0639796824833425,1739502669.8036382,30.11997127532959,54.97110417790889,1739502669.8036444,30.11997127532959,49.534196370928065,1739502669.8036478,30.11997127532959,8.116892888584694,1739502669.8036523,30.11997127532959,2.0776401536723714,1739502669.803656,30.11997127532959,1.136473070186046,1739502669.8036604,30.11997127532959,0.6108,1739502669.8036642,30.11997127532959,1.0071376280268611,1739502669.8036683,30.11997127532959,0.0,1739502669.8036723,30.11997127532959,0.050785671699433155,1739502669.8036764,30.11997127532959,1.746143503891479,1739502669.8036804,30.11997127532959,0.956351956327428 +1739502669.8232903,30.139971256256104,51.22924192706406,1739502669.8232927,30.139971256256104,5.0639796824833425,1739502669.8232965,30.139971256256104,54.97110417790889,1739502669.8232996,30.139971256256104,49.534196370928065,1739502669.8233013,30.139971256256104,8.116892888584694,1739502669.8233035,30.139971256256104,2.0776401536723714,1739502669.823305,30.139971256256104,1.136473070186046,1739502669.8233066,30.139971256256104,0.6108,1739502669.823308,30.139971256256104,1.0071376280268611,1739502669.82331,30.139971256256104,0.0,1739502669.8233113,30.139971256256104,0.050785671699433155,1739502669.823313,30.139971256256104,1.746143503891479,1739502669.8233144,30.139971256256104,0.956351956327428 +1739502669.8432553,30.159971237182617,51.22924192706406,1739502669.8432581,30.159971237182617,5.0639796824833425,1739502669.8432615,30.159971237182617,54.97110417790889,1739502669.8432646,30.159971237182617,49.534196370928065,1739502669.843266,30.159971237182617,8.116892888584694,1739502669.8432682,30.159971237182617,2.0776401536723714,1739502669.8432696,30.159971237182617,1.136473070186046,1739502669.8432713,30.159971237182617,0.6108,1739502669.8432727,30.159971237182617,1.0071376280268611,1739502669.8432746,30.159971237182617,0.0,1739502669.843276,30.159971237182617,0.050785671699433155,1739502669.843278,30.159971237182617,1.746143503891479,1739502669.8432794,30.159971237182617,0.956351956327428 +1739502669.863506,30.17997121810913,51.22924192706406,1739502669.8635092,30.17997121810913,5.0639796824833425,1739502669.8635125,30.17997121810913,54.97110417790889,1739502669.8635159,30.17997121810913,49.534196370928065,1739502669.8635175,30.17997121810913,8.116892888584694,1739502669.8635194,30.17997121810913,2.0776401536723714,1739502669.863521,30.17997121810913,1.136473070186046,1739502669.8635225,30.17997121810913,0.6108,1739502669.8635242,30.17997121810913,1.0071376280268611,1739502669.8635259,30.17997121810913,0.0,1739502669.8635275,30.17997121810913,0.050785671699433155,1739502669.863529,30.17997121810913,1.746143503891479,1739502669.8635304,30.17997121810913,0.956351956327428 +1739502669.8833628,30.199971199035645,51.22924192706406,1739502669.8833656,30.199971199035645,5.0639796824833425,1739502669.883369,30.199971199035645,54.97110417790889,1739502669.883372,30.199971199035645,49.534196370928065,1739502669.8833735,30.199971199035645,8.116892888584694,1739502669.8833756,30.199971199035645,2.0776401536723714,1739502669.883377,30.199971199035645,1.136473070186046,1739502669.8833787,30.199971199035645,0.6108,1739502669.8833802,30.199971199035645,1.0071376280268611,1739502669.8833826,30.199971199035645,0.0,1739502669.883384,30.199971199035645,0.050785671699433155,1739502669.8833857,30.199971199035645,1.746143503891479,1739502669.883387,30.199971199035645,0.956351956327428 +1739502669.9033246,30.219971179962158,51.20952833422985,1739502669.903327,30.219971179962158,5.1676530698808545,1739502669.9033303,30.219971179962158,55.179767958856246,1739502669.9033337,30.219971179962158,49.33701563510973,1739502669.903335,30.219971179962158,8.216587416023167,1739502669.9033372,30.219971179962158,2.1215576253138853,1739502669.9033387,30.219971179962158,1.2195433458938258,1739502669.90334,30.219971179962158,0.6108,1739502669.9033415,30.219971179962158,0.942382585781157,1739502669.9033434,30.219971179962158,0.0,1739502669.9033449,30.219971179962158,-0.052369038292911556,1739502669.9033465,30.219971179962158,1.7737451928340282,1739502669.903348,30.219971179962158,0.9625157560659787 +1739502669.9232893,30.239971160888672,51.20952833422985,1739502669.923292,30.239971160888672,5.1676530698808545,1739502669.9232953,30.239971160888672,55.179767958856246,1739502669.9232986,30.239971160888672,49.33701563510973,1739502669.9233,30.239971160888672,8.216587416023167,1739502669.9233022,30.239971160888672,2.1215576253138853,1739502669.9233036,30.239971160888672,1.2195433458938258,1739502669.9233055,30.239971160888672,0.6108,1739502669.9233067,30.239971160888672,0.942382585781157,1739502669.9233086,30.239971160888672,0.0,1739502669.92331,30.239971160888672,-0.020133170284821755,1739502669.9233117,30.239971160888672,1.7737451928340282,1739502669.9233134,30.239971160888672,0.9625157560659787 +1739502669.9434295,30.259971141815186,51.20952833422985,1739502669.9434319,30.259971141815186,5.1676530698808545,1739502669.9434354,30.259971141815186,55.179767958856246,1739502669.9434385,30.259971141815186,49.33701563510973,1739502669.9434402,30.259971141815186,8.216587416023167,1739502669.943442,30.259971141815186,2.1215576253138853,1739502669.9434438,30.259971141815186,1.2195433458938258,1739502669.9434452,30.259971141815186,0.6108,1739502669.9434469,30.259971141815186,0.942382585781157,1739502669.9434485,30.259971141815186,0.0,1739502669.9434502,30.259971141815186,-0.020133170284821755,1739502669.943452,30.259971141815186,1.7737451928340282,1739502669.9434536,30.259971141815186,0.9625157560659787 +1739502669.963293,30.2799711227417,51.20952833422985,1739502669.963296,30.2799711227417,5.1676530698808545,1739502669.9632993,30.2799711227417,55.179767958856246,1739502669.9633026,30.2799711227417,49.33701563510973,1739502669.9633043,30.2799711227417,8.216587416023167,1739502669.9633062,30.2799711227417,2.1215576253138853,1739502669.9633079,30.2799711227417,1.2195433458938258,1739502669.9633093,30.2799711227417,0.6108,1739502669.963311,30.2799711227417,0.942382585781157,1739502669.9633124,30.2799711227417,0.0,1739502669.9633143,30.2799711227417,-0.020133170284821755,1739502669.9633157,30.2799711227417,1.7737451928340282,1739502669.9633174,30.2799711227417,0.9625157560659787 +1739502669.9832716,30.299971103668213,51.20952833422985,1739502669.9832747,30.299971103668213,5.1676530698808545,1739502669.983278,30.299971103668213,55.179767958856246,1739502669.9832811,30.299971103668213,49.33701563510973,1739502669.9832828,30.299971103668213,8.216587416023167,1739502669.9832847,30.299971103668213,2.1215576253138853,1739502669.9832866,30.299971103668213,1.2195433458938258,1739502669.983288,30.299971103668213,0.6108,1739502669.9832897,30.299971103668213,0.942382585781157,1739502669.9832914,30.299971103668213,0.0,1739502669.9832928,30.299971103668213,-0.020133170284821755,1739502669.9832945,30.299971103668213,1.7737451928340282,1739502669.983296,30.299971103668213,0.9625157560659787 +1739502670.0033176,30.319971084594727,51.18691021985771,1739502670.0033207,30.319971084594727,5.270985132356767,1739502670.0033238,30.319971084594727,55.24955587930495,1739502670.0033267,30.319971084594727,49.27724237599002,1739502670.0033283,30.319971084594727,8.243346069486984,1739502670.0033302,30.319971084594727,2.141863422233805,1739502670.003332,30.319971084594727,1.1799146957883533,1739502670.0033336,30.319971084594727,0.6108,1739502670.003335,30.319971084594727,0.9727374928120174,1739502670.0033371,30.319971084594727,0.0,1739502670.0033388,30.319971084594727,0.027143614380528137,1739502670.0033402,30.319971084594727,1.8013468817765774,1739502670.0033422,30.319971084594727,0.9603678833260035 +1739502670.0233,30.33997106552124,51.18691021985771,1739502670.0233023,30.33997106552124,5.270985132356767,1739502670.0233057,30.33997106552124,55.24955587930495,1739502670.0233088,30.33997106552124,49.27724237599002,1739502670.0233104,30.33997106552124,8.243346069486984,1739502670.023312,30.33997106552124,2.141863422233805,1739502670.0233138,30.33997106552124,1.1799146957883533,1739502670.0233152,30.33997106552124,0.6108,1739502670.0233166,30.33997106552124,0.9727374928120174,1739502670.0233188,30.33997106552124,0.0,1739502670.02332,30.33997106552124,0.012369609486013844,1739502670.0233219,30.33997106552124,1.8013468817765774,1739502670.0233233,30.33997106552124,0.9603678833260035 +1739502670.0432727,30.359971046447754,51.18691021985771,1739502670.0432754,30.359971046447754,5.270985132356767,1739502670.0432782,30.359971046447754,55.24955587930495,1739502670.0432813,30.359971046447754,49.27724237599002,1739502670.043283,30.359971046447754,8.243346069486984,1739502670.043285,30.359971046447754,2.141863422233805,1739502670.0432866,30.359971046447754,1.1799146957883533,1739502670.043288,30.359971046447754,0.6108,1739502670.0432897,30.359971046447754,0.9727374928120174,1739502670.0432913,30.359971046447754,0.0,1739502670.043293,30.359971046447754,0.012369609486013844,1739502670.0432944,30.359971046447754,1.8013468817765774,1739502670.043296,30.359971046447754,0.9603678833260035 +1739502670.0632634,30.379971027374268,51.18691021985771,1739502670.063266,30.379971027374268,5.270985132356767,1739502670.0632694,30.379971027374268,55.24955587930495,1739502670.0632727,30.379971027374268,49.27724237599002,1739502670.0632741,30.379971027374268,8.243346069486984,1739502670.0632763,30.379971027374268,2.141863422233805,1739502670.0632782,30.379971027374268,1.1799146957883533,1739502670.0632796,30.379971027374268,0.6108,1739502670.063281,30.379971027374268,0.9727374928120174,1739502670.063283,30.379971027374268,0.0,1739502670.0632844,30.379971027374268,0.012369609486013844,1739502670.0632863,30.379971027374268,1.8013468817765774,1739502670.0632877,30.379971027374268,0.9603678833260035 +1739502670.083256,30.39997100830078,51.18691021985771,1739502670.0832586,30.39997100830078,5.270985132356767,1739502670.0832617,30.39997100830078,55.24955587930495,1739502670.083265,30.39997100830078,49.27724237599002,1739502670.0832665,30.39997100830078,8.243346069486984,1739502670.0832686,30.39997100830078,2.141863422233805,1739502670.08327,30.39997100830078,1.1799146957883533,1739502670.083272,30.39997100830078,0.6108,1739502670.0832732,30.39997100830078,0.9727374928120174,1739502670.083275,30.39997100830078,0.0,1739502670.0832765,30.39997100830078,0.012369609486013844,1739502670.0832784,30.39997100830078,1.8013468817765774,1739502670.0832798,30.39997100830078,0.9603678833260035 +1739502670.103362,30.419970989227295,51.18691021985771,1739502670.1033647,30.419970989227295,5.270985132356767,1739502670.1033683,30.419970989227295,55.24955587930495,1739502670.1033714,30.419970989227295,49.27724237599002,1739502670.103373,30.419970989227295,8.243346069486984,1739502670.103375,30.419970989227295,2.141863422233805,1739502670.1033766,30.419970989227295,1.1799146957883533,1739502670.103378,30.419970989227295,0.6108,1739502670.1033797,30.419970989227295,0.9727374928120174,1739502670.1033814,30.419970989227295,0.0,1739502670.103383,30.419970989227295,0.012369609486013844,1739502670.103385,30.419970989227295,1.8013468817765774,1739502670.1033869,30.419970989227295,0.9603678833260035 +1739502670.123322,30.43997097015381,51.16145889775232,1739502670.1233246,30.43997097015381,5.373609210269073,1739502670.123328,30.43997097015381,55.42036614623544,1739502670.123331,30.43997097015381,49.11762331623492,1739502670.1233325,30.43997097015381,8.312842882053099,1739502670.1233346,30.43997097015381,2.17840371029853,1739502670.123336,30.43997097015381,1.2257396415274684,1739502670.1233377,30.43997097015381,0.6108,1739502670.1233392,30.43997097015381,0.9377227200042761,1739502670.123341,30.43997097015381,0.0,1739502670.1233425,30.43997097015381,-0.040960258488494175,1739502670.1233442,30.43997097015381,1.8289485707191266,1739502670.1233456,30.43997097015381,0.9620173838239212 +1739502670.143268,30.459970951080322,51.16145889775232,1739502670.1432705,30.459970951080322,5.373609210269073,1739502670.1432743,30.459970951080322,55.42036614623544,1739502670.1432772,30.459970951080322,49.11762331623492,1739502670.1432788,30.459970951080322,8.312842882053099,1739502670.143281,30.459970951080322,2.17840371029853,1739502670.1432824,30.459970951080322,1.2257396415274684,1739502670.143284,30.459970951080322,0.6108,1739502670.1432853,30.459970951080322,0.9377227200042761,1739502670.143287,30.459970951080322,0.0,1739502670.1432886,30.459970951080322,-0.024294663819645068,1739502670.1432903,30.459970951080322,1.8289485707191266,1739502670.143292,30.459970951080322,0.9620173838239212 +1739502670.1632876,30.479970932006836,51.16145889775232,1739502670.16329,30.479970932006836,5.373609210269073,1739502670.1632934,30.479970932006836,55.42036614623544,1739502670.1632967,30.479970932006836,49.11762331623492,1739502670.1632986,30.479970932006836,8.312842882053099,1739502670.1633005,30.479970932006836,2.17840371029853,1739502670.1633022,30.479970932006836,1.2257396415274684,1739502670.1633036,30.479970932006836,0.6108,1739502670.1633053,30.479970932006836,0.9377227200042761,1739502670.163307,30.479970932006836,0.0,1739502670.1633086,30.479970932006836,-0.024294663819645068,1739502670.16331,30.479970932006836,1.8289485707191266,1739502670.163312,30.479970932006836,0.9620173838239212 +1739502670.1832905,30.49997091293335,51.16145889775232,1739502670.1832929,30.49997091293335,5.373609210269073,1739502670.1832962,30.49997091293335,55.42036614623544,1739502670.1832993,30.49997091293335,49.11762331623492,1739502670.183301,30.49997091293335,8.312842882053099,1739502670.1833029,30.49997091293335,2.17840371029853,1739502670.1833045,30.49997091293335,1.2257396415274684,1739502670.1833062,30.49997091293335,0.6108,1739502670.183308,30.49997091293335,0.9377227200042761,1739502670.1833096,30.49997091293335,0.0,1739502670.183311,30.49997091293335,-0.024294663819645068,1739502670.183313,30.49997091293335,1.8289485707191266,1739502670.1833143,30.49997091293335,0.9620173838239212 +1739502670.2033885,30.519970893859863,51.16145889775232,1739502670.203391,30.519970893859863,5.373609210269073,1739502670.203394,30.519970893859863,55.42036614623544,1739502670.2033973,30.519970893859863,49.11762331623492,1739502670.203399,30.519970893859863,8.312842882053099,1739502670.2034006,30.519970893859863,2.17840371029853,1739502670.2034025,30.519970893859863,1.2257396415274684,1739502670.203404,30.519970893859863,0.6108,1739502670.2034056,30.519970893859863,0.9377227200042761,1739502670.2034073,30.519970893859863,0.0,1739502670.2034087,30.519970893859863,-0.024294663819645068,1739502670.2034104,30.519970893859863,1.8289485707191266,1739502670.203412,30.519970893859863,0.9620173838239212 +1739502670.2233377,30.539970874786377,51.13319668289231,1739502670.2233403,30.539970874786377,5.475453926419348,1739502670.2233434,30.539970874786377,55.56232906291481,1739502670.2233465,30.539970874786377,48.99062061549687,1739502670.223348,30.539970874786377,8.363392269188672,1739502670.22335,30.539970874786377,2.2090965116794195,1739502670.2233515,30.539970874786377,1.2416386999006102,1739502670.2233531,30.539970874786377,0.6108,1739502670.2233548,30.539970874786377,0.925871124853061,1739502670.2233567,30.539970874786377,0.0,1739502670.2233582,30.539970874786377,-0.03770562842705671,1739502670.2233598,30.539970874786377,1.8565502596616759,1739502670.2233615,30.539970874786377,0.9593858240925143 +1739502670.2432785,30.55997085571289,51.13319668289231,1739502670.2432811,30.55997085571289,5.475453926419348,1739502670.2432842,30.55997085571289,55.56232906291481,1739502670.2432873,30.55997085571289,48.99062061549687,1739502670.2432888,30.55997085571289,8.363392269188672,1739502670.243291,30.55997085571289,2.2090965116794195,1739502670.2432923,30.55997085571289,1.2416386999006102,1739502670.2432942,30.55997085571289,0.6108,1739502670.2432957,30.55997085571289,0.925871124853061,1739502670.2432976,30.55997085571289,0.0,1739502670.2432988,30.55997085571289,-0.03351469923945327,1739502670.2433007,30.55997085571289,1.8565502596616759,1739502670.243302,30.55997085571289,0.9593858240925143 +1739502670.2632866,30.579970836639404,51.13319668289231,1739502670.263289,30.579970836639404,5.475453926419348,1739502670.2632923,30.579970836639404,55.56232906291481,1739502670.2632954,30.579970836639404,48.99062061549687,1739502670.263297,30.579970836639404,8.363392269188672,1739502670.2632987,30.579970836639404,2.2090965116794195,1739502670.263301,30.579970836639404,1.2416386999006102,1739502670.2633023,30.579970836639404,0.6108,1739502670.263304,30.579970836639404,0.925871124853061,1739502670.2633057,30.579970836639404,0.0,1739502670.2633073,30.579970836639404,-0.03351469923945327,1739502670.263309,30.579970836639404,1.8565502596616759,1739502670.2633107,30.579970836639404,0.9593858240925143 +1739502670.2832782,30.599970817565918,51.13319668289231,1739502670.283281,30.599970817565918,5.475453926419348,1739502670.2832847,30.599970817565918,55.56232906291481,1739502670.2832878,30.599970817565918,48.99062061549687,1739502670.2832894,30.599970817565918,8.363392269188672,1739502670.283291,30.599970817565918,2.2090965116794195,1739502670.2832928,30.599970817565918,1.2416386999006102,1739502670.2832944,30.599970817565918,0.6108,1739502670.2832956,30.599970817565918,0.925871124853061,1739502670.2832975,30.599970817565918,0.0,1739502670.283299,30.599970817565918,-0.03351469923945327,1739502670.2833006,30.599970817565918,1.8565502596616759,1739502670.283302,30.599970817565918,0.9593858240925143 +1739502670.303321,30.61997079849243,51.13319668289231,1739502670.3033235,30.61997079849243,5.475453926419348,1739502670.303327,30.61997079849243,55.56232906291481,1739502670.30333,30.61997079849243,48.99062061549687,1739502670.3033316,30.61997079849243,8.363392269188672,1739502670.3033335,30.61997079849243,2.2090965116794195,1739502670.3033354,30.61997079849243,1.2416386999006102,1739502670.3033369,30.61997079849243,0.6108,1739502670.3033385,30.61997079849243,0.925871124853061,1739502670.3033402,30.61997079849243,0.0,1739502670.3033419,30.61997079849243,-0.03351469923945327,1739502670.3033435,30.61997079849243,1.8565502596616759,1739502670.3033452,30.61997079849243,0.9593858240925143 +1739502670.3233771,30.639970779418945,51.13319668289231,1739502670.3233798,30.639970779418945,5.475453926419348,1739502670.323383,30.639970779418945,55.56232906291481,1739502670.3233864,30.639970779418945,48.99062061549687,1739502670.3233879,30.639970779418945,8.363392269188672,1739502670.32339,30.639970779418945,2.2090965116794195,1739502670.3233914,30.639970779418945,1.2416386999006102,1739502670.323393,30.639970779418945,0.6108,1739502670.3233945,30.639970779418945,0.925871124853061,1739502670.3233964,30.639970779418945,0.0,1739502670.3233979,30.639970779418945,-0.03351469923945327,1739502670.3233993,30.639970779418945,1.8565502596616759,1739502670.323401,30.639970779418945,0.9593858240925143 +1739502670.3433318,30.65997076034546,51.10223940101324,1739502670.3433342,30.65997076034546,5.5761394766254835,1739502670.3433375,30.65997076034546,55.65915920985995,1739502670.3433409,30.65997076034546,48.90668153065347,1739502670.3433423,30.65997076034546,8.393882483404452,1739502670.3433444,30.65997076034546,2.232718970595635,1739502670.3433459,30.65997076034546,1.220067625385146,1739502670.3433475,30.65997076034546,0.6108,1739502670.343349,30.65997076034546,0.9419874111695661,1739502670.3433504,30.65997076034546,0.0,1739502670.343352,30.65997076034546,-0.00460785407826594,1739502670.3433537,30.65997076034546,1.884151948604225,1739502670.3433554,30.65997076034546,0.9556286602834584 +1739502670.3632996,30.679970741271973,51.10223940101324,1739502670.3633022,30.679970741271973,5.5761394766254835,1739502670.3633056,30.679970741271973,55.65915920985995,1739502670.363309,30.679970741271973,48.90668153065347,1739502670.3633103,30.679970741271973,8.393882483404452,1739502670.3633125,30.679970741271973,2.232718970595635,1739502670.3633142,30.679970741271973,1.220067625385146,1739502670.3633158,30.679970741271973,0.6108,1739502670.3633173,30.679970741271973,0.9419874111695661,1739502670.3633192,30.679970741271973,0.0,1739502670.3633206,30.679970741271973,-0.013641249113892306,1739502670.3633223,30.679970741271973,1.884151948604225,1739502670.363324,30.679970741271973,0.9556286602834584 +1739502670.3833013,30.699970722198486,51.10223940101324,1739502670.383304,30.699970722198486,5.5761394766254835,1739502670.3833075,30.699970722198486,55.65915920985995,1739502670.3833108,30.699970722198486,48.90668153065347,1739502670.3833127,30.699970722198486,8.393882483404452,1739502670.3833146,30.699970722198486,2.232718970595635,1739502670.3833163,30.699970722198486,1.220067625385146,1739502670.383318,30.699970722198486,0.6108,1739502670.3833196,30.699970722198486,0.9419874111695661,1739502670.3833213,30.699970722198486,0.0,1739502670.383323,30.699970722198486,-0.013641249113892306,1739502670.3833244,30.699970722198486,1.884151948604225,1739502670.3833263,30.699970722198486,0.9556286602834584 +1739502670.4032888,30.719970703125,51.10223940101324,1739502670.4032915,30.719970703125,5.5761394766254835,1739502670.403295,30.719970703125,55.65915920985995,1739502670.4032981,30.719970703125,48.90668153065347,1739502670.4032996,30.719970703125,8.393882483404452,1739502670.4033017,30.719970703125,2.232718970595635,1739502670.4033031,30.719970703125,1.220067625385146,1739502670.4033048,30.719970703125,0.6108,1739502670.4033062,30.719970703125,0.9419874111695661,1739502670.403308,30.719970703125,0.0,1739502670.4033096,30.719970703125,-0.013641249113892306,1739502670.403311,30.719970703125,1.884151948604225,1739502670.4033127,30.719970703125,0.9556286602834584 +1739502670.423299,30.739970684051514,51.10223940101324,1739502670.4233017,30.739970684051514,5.5761394766254835,1739502670.423305,30.739970684051514,55.65915920985995,1739502670.4233081,30.739970684051514,48.90668153065347,1739502670.4233096,30.739970684051514,8.393882483404452,1739502670.4233117,30.739970684051514,2.232718970595635,1739502670.4233131,30.739970684051514,1.220067625385146,1739502670.4233146,30.739970684051514,0.6108,1739502670.4233162,30.739970684051514,0.9419874111695661,1739502670.423318,30.739970684051514,0.0,1739502670.4233196,30.739970684051514,-0.013641249113892306,1739502670.423321,30.739970684051514,1.884151948604225,1739502670.423323,30.739970684051514,0.9556286602834584 +1739502670.4434621,30.759970664978027,51.068610827096464,1739502670.4434648,30.759970664978027,5.675647443335077,1739502670.4434679,30.759970664978027,55.73611080028489,1739502670.4434712,30.759970664978027,48.83657176045372,1739502670.4434729,30.759970664978027,8.417339177852542,1739502670.4434748,30.759970664978027,2.2540819956962963,1739502670.4434762,30.759970664978027,1.1867589126920939,1739502670.4434779,30.759970664978027,0.6108,1739502670.4434793,30.759970664978027,0.967425946319449,1739502670.4434814,30.759970664978027,0.0,1739502670.4434826,30.759970664978027,0.025557416389428437,1739502670.4434843,30.759970664978027,1.9117536375467743,1739502670.443486,30.759970664978027,0.954118120931266 +1739502670.463302,30.77997064590454,51.068610827096464,1739502670.4633048,30.77997064590454,5.675647443335077,1739502670.463308,30.77997064590454,55.73611080028489,1739502670.4633114,30.77997064590454,48.83657176045372,1739502670.4633129,30.77997064590454,8.417339177852542,1739502670.463315,30.77997064590454,2.2540819956962963,1739502670.4633167,30.77997064590454,1.1867589126920939,1739502670.4633183,30.77997064590454,0.6108,1739502670.4633195,30.77997064590454,0.967425946319449,1739502670.4633214,30.77997064590454,0.0,1739502670.4633229,30.77997064590454,0.013307825388182981,1739502670.4633243,30.77997064590454,1.9117536375467743,1739502670.463326,30.77997064590454,0.954118120931266 +1739502670.4832811,30.799970626831055,51.068610827096464,1739502670.4832838,30.799970626831055,5.675647443335077,1739502670.483287,30.799970626831055,55.73611080028489,1739502670.4832904,30.799970626831055,48.83657176045372,1739502670.4832919,30.799970626831055,8.417339177852542,1739502670.4832938,30.799970626831055,2.2540819956962963,1739502670.4832954,30.799970626831055,1.1867589126920939,1739502670.483297,30.799970626831055,0.6108,1739502670.4832985,30.799970626831055,0.967425946319449,1739502670.4833004,30.799970626831055,0.0,1739502670.4833019,30.799970626831055,0.013307825388182981,1739502670.4833038,30.799970626831055,1.9117536375467743,1739502670.4833052,30.799970626831055,0.954118120931266 +1739502670.5032995,30.81997060775757,51.068610827096464,1739502670.503302,30.81997060775757,5.675647443335077,1739502670.503306,30.81997060775757,55.73611080028489,1739502670.5033092,30.81997060775757,48.83657176045372,1739502670.5033112,30.81997060775757,8.417339177852542,1739502670.5033128,30.81997060775757,2.2540819956962963,1739502670.5033147,30.81997060775757,1.1867589126920939,1739502670.5033162,30.81997060775757,0.6108,1739502670.5033176,30.81997060775757,0.967425946319449,1739502670.5033195,30.81997060775757,0.0,1739502670.5033212,30.81997060775757,0.013307825388182981,1739502670.5033226,30.81997060775757,1.9117536375467743,1739502670.5033243,30.81997060775757,0.954118120931266 +1739502670.5233188,30.839970588684082,51.068610827096464,1739502670.5233216,30.839970588684082,5.675647443335077,1739502670.523325,30.839970588684082,55.73611080028489,1739502670.523328,30.839970588684082,48.83657176045372,1739502670.5233295,30.839970588684082,8.417339177852542,1739502670.5233316,30.839970588684082,2.2540819956962963,1739502670.523333,30.839970588684082,1.1867589126920939,1739502670.5233347,30.839970588684082,0.6108,1739502670.5233366,30.839970588684082,0.967425946319449,1739502670.5233383,30.839970588684082,0.0,1739502670.52334,30.839970588684082,0.013307825388182981,1739502670.5233417,30.839970588684082,1.9117536375467743,1739502670.523343,30.839970588684082,0.954118120931266 +1739502670.5433915,30.859970569610596,51.068610827096464,1739502670.543394,30.859970569610596,5.675647443335077,1739502670.5433977,30.859970569610596,55.73611080028489,1739502670.543401,30.859970569610596,48.83657176045372,1739502670.5434024,30.859970569610596,8.417339177852542,1739502670.5434048,30.859970569610596,2.2540819956962963,1739502670.5434062,30.859970569610596,1.1867589126920939,1739502670.543408,30.859970569610596,0.6108,1739502670.5434093,30.859970569610596,0.967425946319449,1739502670.5434113,30.859970569610596,0.0,1739502670.5434124,30.859970569610596,0.013307825388182981,1739502670.5434144,30.859970569610596,1.9117536375467743,1739502670.5434158,30.859970569610596,0.954118120931266 +1739502670.5633252,30.87997055053711,51.03224492590729,1739502670.5633278,30.87997055053711,5.774197782836119,1739502670.5633311,30.87997055053711,55.73780725078454,1739502670.5633345,30.87997055053711,48.831720673031455,1739502670.563336,30.87997055053711,8.418915781264777,1739502670.5633378,30.87997055053711,2.264773763247304,1739502670.5633397,30.87997055053711,1.099936758406893,1739502670.5633414,30.87997055053711,0.6108,1739502670.5633428,30.87997055053711,1.0370097435953713,1739502670.5633447,30.87997055053711,0.0,1739502670.5633461,30.87997055053711,0.11204471989496578,1739502670.5633478,30.87997055053711,1.9393553264893235,1739502670.5633495,30.87997055053711,0.9558203234640862 +1739502670.5832818,30.899970531463623,51.03224492590729,1739502670.5832841,30.899970531463623,5.774197782836119,1739502670.5832875,30.899970531463623,55.73780725078454,1739502670.5832906,30.899970531463623,48.831720673031455,1739502670.5832922,30.899970531463623,8.418915781264777,1739502670.5832942,30.899970531463623,2.264773763247304,1739502670.5832963,30.899970531463623,1.099936758406893,1739502670.5832977,30.899970531463623,0.6108,1739502670.5832994,30.899970531463623,1.0370097435953713,1739502670.583301,30.899970531463623,0.0,1739502670.5833027,30.899970531463623,0.08118942013128516,1739502670.5833042,30.899970531463623,1.9393553264893235,1739502670.5833058,30.899970531463623,0.9558203234640862 +1739502670.6033685,30.919970512390137,51.03224492590729,1739502670.6033714,30.919970512390137,5.774197782836119,1739502670.6033745,30.919970512390137,55.73780725078454,1739502670.6033778,30.919970512390137,48.831720673031455,1739502670.6033795,30.919970512390137,8.418915781264777,1739502670.6033814,30.919970512390137,2.264773763247304,1739502670.6033833,30.919970512390137,1.099936758406893,1739502670.603385,30.919970512390137,0.6108,1739502670.6033864,30.919970512390137,1.0370097435953713,1739502670.603388,30.919970512390137,0.0,1739502670.6033897,30.919970512390137,0.08118942013128516,1739502670.6033914,30.919970512390137,1.9393553264893235,1739502670.603393,30.919970512390137,0.9558203234640862 +1739502670.6233134,30.93997049331665,51.03224492590729,1739502670.623316,30.93997049331665,5.774197782836119,1739502670.6233191,30.93997049331665,55.73780725078454,1739502670.623322,30.93997049331665,48.831720673031455,1739502670.623324,30.93997049331665,8.418915781264777,1739502670.6233256,30.93997049331665,2.264773763247304,1739502670.6233275,30.93997049331665,1.099936758406893,1739502670.623329,30.93997049331665,0.6108,1739502670.6233306,30.93997049331665,1.0370097435953713,1739502670.6233323,30.93997049331665,0.0,1739502670.623334,30.93997049331665,0.08118942013128516,1739502670.6233354,30.93997049331665,1.9393553264893235,1739502670.623337,30.93997049331665,0.9558203234640862 +1739502670.6432936,30.959970474243164,51.03224492590729,1739502670.6432965,30.959970474243164,5.774197782836119,1739502670.6432998,30.959970474243164,55.73780725078454,1739502670.643303,30.959970474243164,48.831720673031455,1739502670.6433043,30.959970474243164,8.418915781264777,1739502670.6433063,30.959970474243164,2.264773763247304,1739502670.643308,30.959970474243164,1.099936758406893,1739502670.6433096,30.959970474243164,0.6108,1739502670.6433108,30.959970474243164,1.0370097435953713,1739502670.6433127,30.959970474243164,0.0,1739502670.6433141,30.959970474243164,0.08118942013128516,1739502670.6433158,30.959970474243164,1.9393553264893235,1739502670.6433175,30.959970474243164,0.9558203234640862 +1739502670.6630244,30.979970455169678,50.99297746932043,1739502670.6630266,30.979970455169678,5.872189979938453,1739502670.6630294,30.979970455169678,55.979435253213886,1739502670.663032,30.979970455169678,48.58330507812356,1739502670.6630335,30.979970455169678,8.493166103516021,1739502670.6630352,30.979970455169678,2.3142158870075153,1739502670.6630366,30.979970455169678,1.2116613011031172,1739502670.663038,30.979970455169678,0.6108,1739502670.6630392,30.979970455169678,0.9483436816803946,1739502670.6630409,30.979970455169678,0.0,1739502670.663042,30.979970455169678,-0.06063499629076618,1739502670.6630435,30.979970455169678,1.9669570154318727,1739502670.663045,30.979970455169678,0.964658518780709 +1739502670.6877122,30.99997043609619,50.99297746932043,1739502670.6877215,30.99997043609619,5.872189979938453,1739502670.6877322,30.99997043609619,55.979435253213886,1739502670.687743,30.99997043609619,48.58330507812356,1739502670.687748,30.99997043609619,8.493166103516021,1739502670.687754,30.99997043609619,2.3142158870075153,1739502670.6877594,30.99997043609619,1.2116613011031172,1739502670.6877642,30.99997043609619,0.6108,1739502670.687769,30.99997043609619,0.9483436816803946,1739502670.6877747,30.99997043609619,0.0,1739502670.68778,30.99997043609619,-0.01631483710031434,1739502670.687785,30.99997043609619,1.9669570154318727,1739502670.6877902,30.99997043609619,0.964658518780709 +1739502670.7131073,31.019970417022705,50.99297746932043,1739502670.7131164,31.019970417022705,5.872189979938453,1739502670.7131274,31.019970417022705,55.979435253213886,1739502670.7131374,31.019970417022705,48.58330507812356,1739502670.7131422,31.019970417022705,8.493166103516021,1739502670.7131486,31.019970417022705,2.3142158870075153,1739502670.7131536,31.019970417022705,1.2116613011031172,1739502670.7131584,31.019970417022705,0.6108,1739502670.713163,31.019970417022705,0.9483436816803946,1739502670.7131689,31.019970417022705,0.0,1739502670.7131734,31.019970417022705,-0.01631483710031434,1739502670.7131789,31.019970417022705,1.9669570154318727,1739502670.7131836,31.019970417022705,0.964658518780709 +1739502670.7281613,31.03997039794922,50.99297746932043,1739502670.7281692,31.03997039794922,5.872189979938453,1739502670.7281795,31.03997039794922,55.979435253213886,1739502670.7281897,31.03997039794922,48.58330507812356,1739502670.7281947,31.03997039794922,8.493166103516021,1739502670.728201,31.03997039794922,2.3142158870075153,1739502670.7282062,31.03997039794922,1.2116613011031172,1739502670.7282112,31.03997039794922,0.6108,1739502670.7282162,31.03997039794922,0.9483436816803946,1739502670.7282214,31.03997039794922,0.0,1739502670.7282262,31.03997039794922,-0.01631483710031434,1739502670.7282312,31.03997039794922,1.9669570154318727,1739502670.728236,31.03997039794922,0.964658518780709 +1739502670.7498615,31.059970378875732,50.99297746932043,1739502670.7498696,31.059970378875732,5.872189979938453,1739502670.7498794,31.059970378875732,55.979435253213886,1739502670.7498891,31.059970378875732,48.58330507812356,1739502670.7498941,31.059970378875732,8.493166103516021,1739502670.7499006,31.059970378875732,2.3142158870075153,1739502670.7499053,31.059970378875732,1.2116613011031172,1739502670.7499104,31.059970378875732,0.6108,1739502670.749915,31.059970378875732,0.9483436816803946,1739502670.7499206,31.059970378875732,0.0,1739502670.7499251,31.059970378875732,-0.01631483710031434,1739502670.7499304,31.059970378875732,1.9669570154318727,1739502670.7499356,31.059970378875732,0.964658518780709 +1739502670.7797887,31.079970359802246,50.99297746932043,1739502670.779807,31.079970359802246,5.872189979938453,1739502670.7798297,31.079970359802246,55.979435253213886,1739502670.7798567,31.079970359802246,48.58330507812356,1739502670.7798731,31.079970359802246,8.493166103516021,1739502670.7798927,31.079970359802246,2.3142158870075153,1739502670.7799103,31.079970359802246,1.2116613011031172,1739502670.7799275,31.079970359802246,0.6108,1739502670.7799447,31.079970359802246,0.9483436816803946,1739502670.7799625,31.079970359802246,0.0,1739502670.7799797,31.079970359802246,-0.01631483710031434,1739502670.7799976,31.079970359802246,1.9669570154318727,1739502670.780015,31.079970359802246,0.964658518780709 +1739502670.7939517,31.109970331192017,50.95087677224477,1739502670.7939563,31.109970331192017,5.969400482561571,1739502670.7939618,31.109970331192017,56.14054697476636,1739502670.793967,31.109970331192017,48.43235565847738,1739502670.7939694,31.109970331192017,8.531573277453415,1739502670.7939727,31.109970331192017,2.347603024561999,1739502670.7939756,31.109970331192017,1.2422063464171988,1739502670.7939782,31.109970331192017,0.6108,1739502670.7939804,31.109970331192017,0.9254507662912479,1739502670.7939835,31.109970331192017,0.0,1739502670.793986,31.109970331192017,-0.04573142703750262,1739502670.793989,31.109970331192017,1.994558704374422,1739502670.7939916,31.109970331192017,0.9619895029461817 +1739502670.8125165,31.12997031211853,50.95087677224477,1739502670.812519,31.12997031211853,5.969400482561571,1739502670.8125226,31.12997031211853,56.14054697476636,1739502670.8125257,31.12997031211853,48.43235565847738,1739502670.8125274,31.12997031211853,8.531573277453415,1739502670.8125293,31.12997031211853,2.347603024561999,1739502670.812531,31.12997031211853,1.2422063464171988,1739502670.812533,31.12997031211853,0.6108,1739502670.8125346,31.12997031211853,0.9254507662912479,1739502670.8125362,31.12997031211853,0.0,1739502670.812538,31.12997031211853,-0.03653873665493379,1739502670.8125393,31.12997031211853,1.994558704374422,1739502670.8125412,31.12997031211853,0.9619895029461817 +1739502670.8310742,31.149970293045044,50.95087677224477,1739502670.8310776,31.149970293045044,5.969400482561571,1739502670.8310807,31.149970293045044,56.14054697476636,1739502670.8310835,31.149970293045044,48.43235565847738,1739502670.831085,31.149970293045044,8.531573277453415,1739502670.8310869,31.149970293045044,2.347603024561999,1739502670.8310883,31.149970293045044,1.2422063464171988,1739502670.83109,31.149970293045044,0.6108,1739502670.8310914,31.149970293045044,0.9254507662912479,1739502670.8310938,31.149970293045044,0.0,1739502670.831095,31.149970293045044,-0.03653873665493379,1739502670.8310966,31.149970293045044,1.994558704374422,1739502670.831098,31.149970293045044,0.9619895029461817 +1739502670.8518724,31.169970273971558,50.95087677224477,1739502670.8518755,31.169970273971558,5.969400482561571,1739502670.8518786,31.169970273971558,56.14054697476636,1739502670.8518813,31.169970273971558,48.43235565847738,1739502670.8518825,31.169970273971558,8.531573277453415,1739502670.8518844,31.169970273971558,2.347603024561999,1739502670.8518858,31.169970273971558,1.2422063464171988,1739502670.8518875,31.169970273971558,0.6108,1739502670.8518887,31.169970273971558,0.9254507662912479,1739502670.85189,31.169970273971558,0.0,1739502670.8518915,31.169970273971558,-0.03653873665493379,1739502670.851893,31.169970273971558,1.994558704374422,1739502670.8518946,31.169970273971558,0.9619895029461817 +1739502670.8730583,31.18997025489807,50.95087677224477,1739502670.8730612,31.18997025489807,5.969400482561571,1739502670.8730645,31.18997025489807,56.14054697476636,1739502670.8730674,31.18997025489807,48.43235565847738,1739502670.8730688,31.18997025489807,8.531573277453415,1739502670.8730705,31.18997025489807,2.347603024561999,1739502670.8730721,31.18997025489807,1.2422063464171988,1739502670.8730736,31.18997025489807,0.6108,1739502670.873075,31.18997025489807,0.9254507662912479,1739502670.8730764,31.18997025489807,0.0,1739502670.8730779,31.18997025489807,-0.03653873665493379,1739502670.8730793,31.18997025489807,1.994558704374422,1739502670.8730807,31.18997025489807,0.9619895029461817 +1739502670.9266908,31.2299702167511,50.90623460202116,1739502670.9266958,31.2299702167511,6.065144205310764,1739502670.926702,31.2299702167511,56.22552676781097,1739502670.9267077,31.2299702167511,48.3569866482854,1739502670.9267106,31.2299702167511,8.54920267034292,1739502670.9267144,31.2299702167511,2.3691453893799963,1739502670.9267178,31.2299702167511,1.2104183686212844,1739502670.9267206,31.2299702167511,0.6108,1739502670.926723,31.2299702167511,0.9492871323935961,1739502670.926726,31.2299702167511,0.0,1739502670.9267292,31.2299702167511,0.003634581974682062,1739502670.9267325,31.2299702167511,2.022160393316969,1739502670.9267354,31.2299702167511,0.9582067207218244 +1739502670.9403338,31.249970197677612,50.90623460202116,1739502670.9403374,31.249970197677612,6.065144205310764,1739502670.9403422,31.249970197677612,56.22552676781097,1739502670.9403467,31.249970197677612,48.3569866482854,1739502670.9403489,31.249970197677612,8.54920267034292,1739502670.9403517,31.249970197677612,2.3691453893799963,1739502670.940354,31.249970197677612,1.2104183686212844,1739502670.9403563,31.249970197677612,0.6108,1739502670.9403582,31.249970197677612,0.9492871323935961,1739502670.9403608,31.249970197677612,0.0,1739502670.9403627,31.249970197677612,-0.008919588328228367,1739502670.940365,31.249970197677612,2.022160393316969,1739502670.9403677,31.249970197677612,0.9582067207218244 +1739502670.9594548,31.269970178604126,50.90623460202116,1739502670.9594584,31.269970178604126,6.065144205310764,1739502670.9594626,31.269970178604126,56.22552676781097,1739502670.959468,31.269970178604126,48.3569866482854,1739502670.9594698,31.269970178604126,8.54920267034292,1739502670.9594724,31.269970178604126,2.3691453893799963,1739502670.9594743,31.269970178604126,1.2104183686212844,1739502670.9594767,31.269970178604126,0.6108,1739502670.9594789,31.269970178604126,0.9492871323935961,1739502670.959481,31.269970178604126,0.0,1739502670.9594834,31.269970178604126,-0.008919588328228367,1739502670.9594855,31.269970178604126,2.022160393316969,1739502670.9594877,31.269970178604126,0.9582067207218244 +1739502670.9783359,31.28997015953064,50.90623460202116,1739502670.9783394,31.28997015953064,6.065144205310764,1739502670.9783437,31.28997015953064,56.22552676781097,1739502670.9783475,31.28997015953064,48.3569866482854,1739502670.97835,31.28997015953064,8.54920267034292,1739502670.978352,31.28997015953064,2.3691453893799963,1739502670.9783542,31.28997015953064,1.2104183686212844,1739502670.9783561,31.28997015953064,0.6108,1739502670.9783583,31.28997015953064,0.9492871323935961,1739502670.9783607,31.28997015953064,0.0,1739502670.9783623,31.28997015953064,-0.008919588328228367,1739502670.9783645,31.28997015953064,2.022160393316969,1739502670.9783664,31.28997015953064,0.9582067207218244 +1739502670.9978418,31.309970140457153,50.85912165671652,1739502670.9978447,31.309970140457153,6.159308991127009,1739502670.997848,31.309970140457153,56.38617265374674,1739502670.9978511,31.309970140457153,48.20223738705996,1739502670.9978526,31.309970140457153,8.57879376882334,1739502670.9978547,31.309970140457153,2.4029260517680737,1739502670.9978561,31.309970140457153,1.2428629783844412,1739502670.9978583,31.309970140457153,0.6108,1739502670.99786,31.309970140457153,0.9249647495102815,1739502670.9978616,31.309970140457153,0.0,1739502670.997863,31.309970140457153,-0.042052606378144924,1739502670.997865,31.309970140457153,2.049762082259516,1739502670.9978664,31.309970140457153,0.956663280959167 +1739502671.0181243,31.329970121383667,50.85912165671652,1739502671.0181265,31.329970121383667,6.159308991127009,1739502671.0181293,31.329970121383667,56.38617265374674,1739502671.0181322,31.329970121383667,48.20223738705996,1739502671.0181334,31.329970121383667,8.57879376882334,1739502671.0181353,31.329970121383667,2.4029260517680737,1739502671.0181365,31.329970121383667,1.2428629783844412,1739502671.0181384,31.329970121383667,0.6108,1739502671.0181396,31.329970121383667,0.9249647495102815,1739502671.0181413,31.329970121383667,0.0,1739502671.0181427,31.329970121383667,-0.03169853144888546,1739502671.018144,31.329970121383667,2.049762082259516,1739502671.0181456,31.329970121383667,0.956663280959167 +1739502671.0436454,31.34997010231018,50.85912165671652,1739502671.043654,31.34997010231018,6.159308991127009,1739502671.0436642,31.34997010231018,56.38617265374674,1739502671.0436745,31.34997010231018,48.20223738705996,1739502671.0436792,31.34997010231018,8.57879376882334,1739502671.0436852,31.34997010231018,2.4029260517680737,1739502671.0436902,31.34997010231018,1.2428629783844412,1739502671.0436947,31.34997010231018,0.6108,1739502671.0436995,31.34997010231018,0.9249647495102815,1739502671.043705,31.34997010231018,0.0,1739502671.0437098,31.34997010231018,-0.03169853144888546,1739502671.043715,31.34997010231018,2.049762082259516,1739502671.04372,31.34997010231018,0.956663280959167 +1739502671.0832016,31.389970064163208,50.85912165671652,1739502671.0832107,31.389970064163208,6.159308991127009,1739502671.0832214,31.389970064163208,56.38617265374674,1739502671.0832317,31.389970064163208,48.20223738705996,1739502671.083237,31.389970064163208,8.57879376882334,1739502671.0832434,31.389970064163208,2.4029260517680737,1739502671.0832484,31.389970064163208,1.2428629783844412,1739502671.0832536,31.389970064163208,0.6108,1739502671.0832582,31.389970064163208,0.9249647495102815,1739502671.0832636,31.389970064163208,0.0,1739502671.0832684,31.389970064163208,-0.03169853144888546,1739502671.0832736,31.389970064163208,2.049762082259516,1739502671.083279,31.389970064163208,0.956663280959167 +1739502671.1049566,31.40997004508972,50.85912165671652,1739502671.1049626,31.40997004508972,6.159308991127009,1739502671.1049685,31.40997004508972,56.38617265374674,1739502671.1049743,31.40997004508972,48.20223738705996,1739502671.1049771,31.40997004508972,8.57879376882334,1739502671.1049805,31.40997004508972,2.4029260517680737,1739502671.104984,31.40997004508972,1.2428629783844412,1739502671.1049867,31.40997004508972,0.6108,1739502671.1049893,31.40997004508972,0.9249647495102815,1739502671.1049922,31.40997004508972,0.0,1739502671.104995,31.40997004508972,-0.03169853144888546,1739502671.1049979,31.40997004508972,2.049762082259516,1739502671.1050007,31.40997004508972,0.956663280959167 +1739502671.1184402,31.429970026016235,50.80954970058305,1739502671.1184428,31.429970026016235,6.25191133823656,1739502671.118446,31.429970026016235,56.47109413012366,1739502671.1184492,31.429970026016235,48.125641442629295,1739502671.1184506,31.429970026016235,8.590974066743769,1739502671.1184528,31.429970026016235,2.4247406289497153,1739502671.1184542,31.429970026016235,1.2119865394617189,1739502671.118456,31.429970026016235,0.6108,1739502671.1184573,31.429970026016235,0.948096963584726,1739502671.1184592,31.429970026016235,0.0,1739502671.1184607,31.429970026016235,0.007301850680402464,1739502671.1184623,31.429970026016235,2.0773637712020627,1739502671.1184638,31.429970026016235,0.9529827403105572 +1739502671.1390908,31.44997000694275,50.80954970058305,1739502671.1390934,31.44997000694275,6.25191133823656,1739502671.1390965,31.44997000694275,56.47109413012366,1739502671.1390994,31.44997000694275,48.125641442629295,1739502671.139101,31.44997000694275,8.590974066743769,1739502671.1391025,31.44997000694275,2.4247406289497153,1739502671.139104,31.44997000694275,1.2119865394617189,1739502671.139106,31.44997000694275,0.6108,1739502671.1391072,31.44997000694275,0.948096963584726,1739502671.139109,31.44997000694275,0.0,1739502671.1391103,31.44997000694275,-0.004885776725831237,1739502671.139112,31.44997000694275,2.0773637712020627,1739502671.1391132,31.44997000694275,0.9529827403105572 +1739502671.1586778,31.469969987869263,50.80954970058305,1739502671.1586804,31.469969987869263,6.25191133823656,1739502671.1586833,31.469969987869263,56.47109413012366,1739502671.1586862,31.469969987869263,48.125641442629295,1739502671.1586876,31.469969987869263,8.590974066743769,1739502671.158689,31.469969987869263,2.4247406289497153,1739502671.1586902,31.469969987869263,1.2119865394617189,1739502671.1586916,31.469969987869263,0.6108,1739502671.1586928,31.469969987869263,0.948096963584726,1739502671.1586947,31.469969987869263,0.0,1739502671.158696,31.469969987869263,-0.004885776725831237,1739502671.1586971,31.469969987869263,2.0773637712020627,1739502671.1586988,31.469969987869263,0.9529827403105572 +1739502671.1844747,31.489969968795776,50.80954970058305,1739502671.1844828,31.489969968795776,6.25191133823656,1739502671.1844933,31.489969968795776,56.47109413012366,1739502671.1845036,31.489969968795776,48.125641442629295,1739502671.184508,31.489969968795776,8.590974066743769,1739502671.1845143,31.489969968795776,2.4247406289497153,1739502671.184519,31.489969968795776,1.2119865394617189,1739502671.184524,31.489969968795776,0.6108,1739502671.1845286,31.489969968795776,0.948096963584726,1739502671.1845345,31.489969968795776,0.0,1739502671.1845393,31.489969968795776,-0.004885776725831237,1739502671.1845446,31.489969968795776,2.0773637712020627,1739502671.1845493,31.489969968795776,0.9529827403105572 +1739502671.2056665,31.50996994972229,50.80954970058305,1739502671.2056754,31.50996994972229,6.25191133823656,1739502671.2056856,31.50996994972229,56.47109413012366,1739502671.205695,31.50996994972229,48.125641442629295,1739502671.2057,31.50996994972229,8.590974066743769,1739502671.205706,31.50996994972229,2.4247406289497153,1739502671.205711,31.50996994972229,1.2119865394617189,1739502671.2057157,31.50996994972229,0.6108,1739502671.2057204,31.50996994972229,0.948096963584726,1739502671.2057264,31.50996994972229,0.0,1739502671.2057314,31.50996994972229,-0.004885776725831237,1739502671.2057362,31.50996994972229,2.0773637712020627,1739502671.2057412,31.50996994972229,0.9529827403105572 +1739502671.239588,31.529969930648804,50.75755700338367,1739502671.2396016,31.529969930648804,6.342905534800188,1739502671.2396185,31.529969930648804,56.57822856046014,1739502671.2396386,31.529969930648804,48.02045754993868,1739502671.239649,31.529969930648804,8.606017586427322,1739502671.2396631,31.529969930648804,2.4507055499644097,1739502671.239676,31.529969930648804,1.2035900431649036,1739502671.2396884,31.529969930648804,0.6108,1739502671.239701,31.529969930648804,0.9544869550889936,1739502671.2397141,31.529969930648804,0.0,1739502671.2397268,31.529969930648804,0.0050425423792873885,1739502671.2397397,31.529969930648804,2.1049654601446095,1739502671.2397525,31.529969930648804,0.95254701446428 +1739502671.2533479,31.549969911575317,50.75755700338367,1739502671.2533557,31.549969911575317,6.342905534800188,1739502671.2533662,31.549969911575317,56.57822856046014,1739502671.2533762,31.549969911575317,48.02045754993868,1739502671.2533815,31.549969911575317,8.606017586427322,1739502671.2533872,31.549969911575317,2.4507055499644097,1739502671.2533925,31.549969911575317,1.2035900431649036,1739502671.253397,31.549969911575317,0.6108,1739502671.2534015,31.549969911575317,0.9544869550889936,1739502671.2534072,31.549969911575317,0.0,1739502671.253412,31.549969911575317,0.0019399406247135875,1739502671.2534173,31.549969911575317,2.1049654601446095,1739502671.253422,31.549969911575317,0.95254701446428 +1739502671.2880185,31.579969882965088,50.75755700338367,1739502671.2880237,31.579969882965088,6.342905534800188,1739502671.2880309,31.579969882965088,56.57822856046014,1739502671.2880394,31.579969882965088,48.02045754993868,1739502671.2880442,31.579969882965088,8.606017586427322,1739502671.2880502,31.579969882965088,2.4507055499644097,1739502671.288056,31.579969882965088,1.2035900431649036,1739502671.2880611,31.579969882965088,0.6108,1739502671.2880666,31.579969882965088,0.9544869550889936,1739502671.288072,31.579969882965088,0.0,1739502671.2880776,31.579969882965088,0.0019399406247135875,1739502671.2880833,31.579969882965088,2.1049654601446095,1739502671.2880888,31.579969882965088,0.95254701446428 +1739502671.3065062,31.5999698638916,50.75755700338367,1739502671.306511,31.5999698638916,6.342905534800188,1739502671.306517,31.5999698638916,56.57822856046014,1739502671.3065245,31.5999698638916,48.02045754993868,1739502671.3065283,31.5999698638916,8.606017586427322,1739502671.3065336,31.5999698638916,2.4507055499644097,1739502671.3065383,31.5999698638916,1.2035900431649036,1739502671.3065429,31.5999698638916,0.6108,1739502671.3065474,31.5999698638916,0.9544869550889936,1739502671.3065524,31.5999698638916,0.0,1739502671.306557,31.5999698638916,0.0019399406247135875,1739502671.3065617,31.5999698638916,2.1049654601446095,1739502671.3065665,31.5999698638916,0.95254701446428 +1739502671.3251996,31.619969844818115,50.75755700338367,1739502671.325203,31.619969844818115,6.342905534800188,1739502671.3252072,31.619969844818115,56.57822856046014,1739502671.3252108,31.619969844818115,48.02045754993868,1739502671.325213,31.619969844818115,8.606017586427322,1739502671.3252153,31.619969844818115,2.4507055499644097,1739502671.325217,31.619969844818115,1.2035900431649036,1739502671.3252192,31.619969844818115,0.6108,1739502671.325221,31.619969844818115,0.9544869550889936,1739502671.3252234,31.619969844818115,0.0,1739502671.325225,31.619969844818115,0.0019399406247135875,1739502671.325227,31.619969844818115,2.1049654601446095,1739502671.3252296,31.619969844818115,0.95254701446428 +1739502671.3445368,31.63996982574463,50.703076519506574,1739502671.344541,31.63996982574463,6.4324238741589745,1739502671.344549,31.63996982574463,56.72491892260526,1739502671.3445559,31.63996982574463,47.87415929178772,1739502671.344559,31.63996982574463,8.622561061968575,1739502671.3445635,31.63996982574463,2.4827849109464952,1739502671.3445673,31.63996982574463,1.2274950743111706,1739502671.3445714,31.63996982574463,0.6108,1739502671.3445766,31.63996982574463,0.9364067568906959,1739502671.3445792,31.63996982574463,0.0,1739502671.3445818,31.63996982574463,-0.024757525643129864,1739502671.3445845,31.63996982574463,2.1325671490871563,1739502671.3445873,31.63996982574463,0.9528213188550514 +1739502671.364773,31.659969806671143,50.703076519506574,1739502671.3647764,31.659969806671143,6.4324238741589745,1739502671.3647802,31.659969806671143,56.72491892260526,1739502671.3647838,31.659969806671143,47.87415929178772,1739502671.3647857,31.659969806671143,8.622561061968575,1739502671.3647878,31.659969806671143,2.4827849109464952,1739502671.3647895,31.659969806671143,1.2274950743111706,1739502671.3647914,31.659969806671143,0.6108,1739502671.364793,31.659969806671143,0.9364067568906959,1739502671.3647952,31.659969806671143,0.0,1739502671.3647969,31.659969806671143,-0.016414561964355534,1739502671.3647988,31.659969806671143,2.1325671490871563,1739502671.3648005,31.659969806671143,0.9528213188550514 +1739502671.384172,31.679969787597656,50.703076519506574,1739502671.384175,31.679969787597656,6.4324238741589745,1739502671.3841786,31.679969787597656,56.72491892260526,1739502671.3841817,31.679969787597656,47.87415929178772,1739502671.3841836,31.679969787597656,8.622561061968575,1739502671.3841856,31.679969787597656,2.4827849109464952,1739502671.3841872,31.679969787597656,1.2274950743111706,1739502671.384189,31.679969787597656,0.6108,1739502671.3841906,31.679969787597656,0.9364067568906959,1739502671.3841922,31.679969787597656,0.0,1739502671.384194,31.679969787597656,-0.016414561964355534,1739502671.3841953,31.679969787597656,2.1325671490871563,1739502671.3841972,31.679969787597656,0.9528213188550514 +1739502671.4037638,31.69996976852417,50.703076519506574,1739502671.4037662,31.69996976852417,6.4324238741589745,1739502671.4037695,31.69996976852417,56.72491892260526,1739502671.4037726,31.69996976852417,47.87415929178772,1739502671.4037745,31.69996976852417,8.622561061968575,1739502671.4037762,31.69996976852417,2.4827849109464952,1739502671.4037778,31.69996976852417,1.2274950743111706,1739502671.4037795,31.69996976852417,0.6108,1739502671.4037812,31.69996976852417,0.9364067568906959,1739502671.403783,31.69996976852417,0.0,1739502671.4037845,31.69996976852417,-0.016414561964355534,1739502671.4037862,31.69996976852417,2.1325671490871563,1739502671.4037879,31.69996976852417,0.9528213188550514 +1739502671.4244258,31.719969749450684,50.703076519506574,1739502671.4244282,31.719969749450684,6.4324238741589745,1739502671.4244316,31.719969749450684,56.72491892260526,1739502671.4244347,31.719969749450684,47.87415929178772,1739502671.4244363,31.719969749450684,8.622561061968575,1739502671.4244382,31.719969749450684,2.4827849109464952,1739502671.42444,31.719969749450684,1.2274950743111706,1739502671.4244413,31.719969749450684,0.6108,1739502671.4244428,31.719969749450684,0.9364067568906959,1739502671.4244447,31.719969749450684,0.0,1739502671.424446,31.719969749450684,-0.016414561964355534,1739502671.424448,31.719969749450684,2.1325671490871563,1739502671.4244494,31.719969749450684,0.9528213188550514 +1739502671.4490814,31.739969730377197,50.703076519506574,1739502671.4490898,31.739969730377197,6.4324238741589745,1739502671.4491007,31.739969730377197,56.72491892260526,1739502671.449111,31.739969730377197,47.87415929178772,1739502671.449116,31.739969730377197,8.622561061968575,1739502671.4491217,31.739969730377197,2.4827849109464952,1739502671.449127,31.739969730377197,1.2274950743111706,1739502671.4491317,31.739969730377197,0.6108,1739502671.4491365,31.739969730377197,0.9364067568906959,1739502671.4491422,31.739969730377197,0.0,1739502671.4491472,31.739969730377197,-0.016414561964355534,1739502671.4491522,31.739969730377197,2.1325671490871563,1739502671.4491575,31.739969730377197,0.9528213188550514 +1739502671.4684365,31.75996971130371,50.64618597792596,1739502671.4684405,31.75996971130371,6.520344135815201,1739502671.4684463,31.75996971130371,56.812354518353025,1739502671.4684513,31.75996971130371,47.79056935244804,1739502671.468454,31.75996971130371,8.629339415471998,1739502671.4684572,31.75996971130371,2.505464526447172,1739502671.4684598,31.75996971130371,1.2015815784542747,1739502671.4684622,31.75996971130371,0.6108,1739502671.4684649,31.75996971130371,0.956021830548896,1739502671.4684684,31.75996971130371,0.0,1739502671.468471,31.75996971130371,0.014710165835820558,1739502671.468474,31.75996971130371,2.160168838029703,1739502671.4684765,31.75996971130371,0.9510381485278102 +1739502671.485197,31.779969692230225,50.64618597792596,1739502671.485201,31.779969692230225,6.520344135815201,1739502671.4852054,31.779969692230225,56.812354518353025,1739502671.4852104,31.779969692230225,47.79056935244804,1739502671.4852123,31.779969692230225,8.629339415471998,1739502671.4852154,31.779969692230225,2.505464526447172,1739502671.4852178,31.779969692230225,1.2015815784542747,1739502671.48522,31.779969692230225,0.6108,1739502671.4852219,31.779969692230225,0.956021830548896,1739502671.4852242,31.779969692230225,0.0,1739502671.4852262,31.779969692230225,0.004983682021085789,1739502671.4852288,31.779969692230225,2.160168838029703,1739502671.4852312,31.779969692230225,0.9510381485278102 +1739502671.5043602,31.79996967315674,50.64618597792596,1739502671.5043628,31.79996967315674,6.520344135815201,1739502671.5043662,31.79996967315674,56.812354518353025,1739502671.5043693,31.79996967315674,47.79056935244804,1739502671.5043705,31.79996967315674,8.629339415471998,1739502671.5043726,31.79996967315674,2.505464526447172,1739502671.504374,31.79996967315674,1.2015815784542747,1739502671.5043752,31.79996967315674,0.6108,1739502671.504377,31.79996967315674,0.956021830548896,1739502671.5043786,31.79996967315674,0.0,1739502671.5043802,31.79996967315674,0.004983682021085789,1739502671.5043821,31.79996967315674,2.160168838029703,1739502671.5043838,31.79996967315674,0.9510381485278102 +1739502671.52357,31.819969654083252,50.64618597792596,1739502671.5235727,31.819969654083252,6.520344135815201,1739502671.5235763,31.819969654083252,56.812354518353025,1739502671.5235794,31.819969654083252,47.79056935244804,1739502671.5235808,31.819969654083252,8.629339415471998,1739502671.5235825,31.819969654083252,2.505464526447172,1739502671.523584,31.819969654083252,1.2015815784542747,1739502671.5235856,31.819969654083252,0.6108,1739502671.523587,31.819969654083252,0.956021830548896,1739502671.5235887,31.819969654083252,0.0,1739502671.5235898,31.819969654083252,0.004983682021085789,1739502671.5235915,31.819969654083252,2.160168838029703,1739502671.5235927,31.819969654083252,0.9510381485278102 +1739502671.5431669,31.839969635009766,50.64618597792596,1739502671.5431695,31.839969635009766,6.520344135815201,1739502671.5431724,31.839969635009766,56.812354518353025,1739502671.543175,31.839969635009766,47.79056935244804,1739502671.5431762,31.839969635009766,8.629339415471998,1739502671.5431778,31.839969635009766,2.505464526447172,1739502671.543179,31.839969635009766,1.2015815784542747,1739502671.5431802,31.839969635009766,0.6108,1739502671.5431817,31.839969635009766,0.956021830548896,1739502671.5431833,31.839969635009766,0.0,1739502671.5431848,31.839969635009766,0.004983682021085789,1739502671.543186,31.839969635009766,2.160168838029703,1739502671.5431871,31.839969635009766,0.9510381485278102 +1739502671.5634706,31.85996961593628,50.586955527586525,1739502671.563473,31.85996961593628,6.606565417077631,1739502671.5634754,31.85996961593628,56.97688168153525,1739502671.5634782,31.85996961593628,47.625827499492,1739502671.5634797,31.85996961593628,8.637810105655268,1739502671.563481,31.85996961593628,2.5403450586952463,1739502671.5634823,31.85996961593628,1.2399762390055067,1739502671.5634842,31.85996961593628,0.6108,1739502671.5634851,31.85996961593628,0.9271033236955684,1739502671.5634868,31.85996961593628,0.0,1739502671.5634878,31.85996961593628,-0.037400086310676886,1739502671.5634892,31.85996961593628,2.18777052697225,1739502671.5634906,31.85996961593628,0.9512584737185125 +1739502671.5834577,31.879969596862793,50.586955527586525,1739502671.5834606,31.879969596862793,6.606565417077631,1739502671.5834637,31.879969596862793,56.97688168153525,1739502671.5834665,31.879969596862793,47.625827499492,1739502671.583468,31.879969596862793,8.637810105655268,1739502671.5834699,31.879969596862793,2.5403450586952463,1739502671.583471,31.879969596862793,1.2399762390055067,1739502671.5834725,31.879969596862793,0.6108,1739502671.583474,31.879969596862793,0.9271033236955684,1739502671.5834754,31.879969596862793,0.0,1739502671.583477,31.879969596862793,-0.024155150022944105,1739502671.5834785,31.879969596862793,2.18777052697225,1739502671.5834796,31.879969596862793,0.9512584737185125 +1739502671.603617,31.899969577789307,50.586955527586525,1739502671.6036193,31.899969577789307,6.606565417077631,1739502671.603622,31.899969577789307,56.97688168153525,1739502671.6036243,31.899969577789307,47.625827499492,1739502671.6036258,31.899969577789307,8.637810105655268,1739502671.6036272,31.899969577789307,2.5403450586952463,1739502671.6036286,31.899969577789307,1.2399762390055067,1739502671.6036298,31.899969577789307,0.6108,1739502671.603631,31.899969577789307,0.9271033236955684,1739502671.6036327,31.899969577789307,0.0,1739502671.6036339,31.899969577789307,-0.024155150022944105,1739502671.6036353,31.899969577789307,2.18777052697225,1739502671.6036365,31.899969577789307,0.9512584737185125 +1739502671.623381,31.91996955871582,50.586955527586525,1739502671.6233835,31.91996955871582,6.606565417077631,1739502671.6233864,31.91996955871582,56.97688168153525,1739502671.6233892,31.91996955871582,47.625827499492,1739502671.6233904,31.91996955871582,8.637810105655268,1739502671.623392,31.91996955871582,2.5403450586952463,1739502671.6233933,31.91996955871582,1.2399762390055067,1739502671.6233947,31.91996955871582,0.6108,1739502671.623396,31.91996955871582,0.9271033236955684,1739502671.6233976,31.91996955871582,0.0,1739502671.623399,31.91996955871582,-0.024155150022944105,1739502671.6234004,31.91996955871582,2.18777052697225,1739502671.6234016,31.91996955871582,0.9512584737185125 +1739502671.6433306,31.939969539642334,50.586955527586525,1739502671.6433327,31.939969539642334,6.606565417077631,1739502671.6433353,31.939969539642334,56.97688168153525,1739502671.643338,31.939969539642334,47.625827499492,1739502671.6433392,31.939969539642334,8.637810105655268,1739502671.643341,31.939969539642334,2.5403450586952463,1739502671.6433425,31.939969539642334,1.2399762390055067,1739502671.643344,31.939969539642334,0.6108,1739502671.643345,31.939969539642334,0.9271033236955684,1739502671.643347,31.939969539642334,0.0,1739502671.6433482,31.939969539642334,-0.024155150022944105,1739502671.6433494,31.939969539642334,2.18777052697225,1739502671.6433508,31.939969539642334,0.9512584737185125 +1739502671.6634324,31.959969520568848,50.586955527586525,1739502671.6634347,31.959969520568848,6.606565417077631,1739502671.6634374,31.959969520568848,56.97688168153525,1739502671.66344,31.959969520568848,47.625827499492,1739502671.6634414,31.959969520568848,8.637810105655268,1739502671.663443,31.959969520568848,2.5403450586952463,1739502671.6634445,31.959969520568848,1.2399762390055067,1739502671.6634457,31.959969520568848,0.6108,1739502671.6634471,31.959969520568848,0.9271033236955684,1739502671.6634486,31.959969520568848,0.0,1739502671.6634495,31.959969520568848,-0.024155150022944105,1739502671.6634512,31.959969520568848,2.18777052697225,1739502671.6634524,31.959969520568848,0.9512584737185125 +1739502671.6835394,31.97996950149536,50.5254255862397,1739502671.683542,31.97996950149536,6.6910416052682695,1739502671.683545,31.97996950149536,57.06386284198682,1739502671.6835482,31.97996950149536,47.54414621671242,1739502671.6835494,31.97996950149536,8.640755791981965,1739502671.6835515,31.97996950149536,2.56242060970074,1739502671.683553,31.97996950149536,1.2115953386096179,1739502671.6835544,31.97996950149536,0.6108,1739502671.6835556,31.97996950149536,0.9483937270919816,1739502671.6835573,31.97996950149536,0.0,1739502671.6835587,31.97996950149536,0.01062658708344018,1739502671.6835601,31.97996950149536,2.2153722159147966,1739502671.6835616,31.97996950149536,0.9486364399807549 +1739502671.7032628,31.999969482421875,50.5254255862397,1739502671.703265,31.999969482421875,6.6910416052682695,1739502671.703268,31.999969482421875,57.06386284198682,1739502671.703271,31.999969482421875,47.54414621671242,1739502671.7032723,31.999969482421875,8.640755791981965,1739502671.7032743,31.999969482421875,2.56242060970074,1739502671.7032757,31.999969482421875,1.2115953386096179,1739502671.703277,31.999969482421875,0.6108,1739502671.7032785,31.999969482421875,0.9483937270919816,1739502671.7032804,31.999969482421875,0.0,1739502671.7032816,31.999969482421875,-0.00024271288877331099,1739502671.7032833,31.999969482421875,2.2153722159147966,1739502671.7032845,31.999969482421875,0.9486364399807549 +1739502671.72361,32.01996946334839,50.5254255862397,1739502671.723612,32.01996946334839,6.6910416052682695,1739502671.7236152,32.01996946334839,57.06386284198682,1739502671.723618,32.01996946334839,47.54414621671242,1739502671.7236197,32.01996946334839,8.640755791981965,1739502671.7236214,32.01996946334839,2.56242060970074,1739502671.7236226,32.01996946334839,1.2115953386096179,1739502671.7236242,32.01996946334839,0.6108,1739502671.7236254,32.01996946334839,0.9483937270919816,1739502671.7236273,32.01996946334839,0.0,1739502671.7236285,32.01996946334839,-0.00024271288877331099,1739502671.7236302,32.01996946334839,2.2153722159147966,1739502671.7236316,32.01996946334839,0.9486364399807549 +1739502671.743494,32.0399694442749,50.5254255862397,1739502671.743497,32.0399694442749,6.6910416052682695,1739502671.7434998,32.0399694442749,57.06386284198682,1739502671.7435024,32.0399694442749,47.54414621671242,1739502671.7435038,32.0399694442749,8.640755791981965,1739502671.7435057,32.0399694442749,2.56242060970074,1739502671.7435071,32.0399694442749,1.2115953386096179,1739502671.7435086,32.0399694442749,0.6108,1739502671.7435098,32.0399694442749,0.9483937270919816,1739502671.7435114,32.0399694442749,0.0,1739502671.7435129,32.0399694442749,-0.00024271288877331099,1739502671.7435143,32.0399694442749,2.2153722159147966,1739502671.7435157,32.0399694442749,0.9486364399807549 +1739502671.7634943,32.059969425201416,50.5254255862397,1739502671.7634966,32.059969425201416,6.6910416052682695,1739502671.7634995,32.059969425201416,57.06386284198682,1739502671.7635026,32.059969425201416,47.54414621671242,1739502671.7635038,32.059969425201416,8.640755791981965,1739502671.763506,32.059969425201416,2.56242060970074,1739502671.7635074,32.059969425201416,1.2115953386096179,1739502671.763509,32.059969425201416,0.6108,1739502671.7635102,32.059969425201416,0.9483937270919816,1739502671.763512,32.059969425201416,0.0,1739502671.763513,32.059969425201416,-0.00024271288877331099,1739502671.763515,32.059969425201416,2.2153722159147966,1739502671.7635162,32.059969425201416,0.9486364399807549 +1739502671.783554,32.07996940612793,50.46170937077643,1739502671.7835565,32.07996940612793,6.773628735777631,1739502671.7835593,32.07996940612793,57.149642414129254,1739502671.7835622,32.07996940612793,47.459162474573816,1739502671.7835639,32.07996940612793,8.642,1739502671.7835655,32.07996940612793,2.5849645577694824,1739502671.7835672,32.07996940612793,1.1859769351861194,1739502671.7835684,32.07996940612793,0.6108,1739502671.7835696,32.07996940612793,0.9680313399243524,1739502671.7835717,32.07996940612793,0.0,1739502671.783573,32.07996940612793,0.028888429409519266,1739502671.7835746,32.07996940612793,2.2429739048573434,1739502671.783576,32.07996940612793,0.9482463984517614 +1739502671.8036761,32.09996938705444,50.46170937077643,1739502671.8036788,32.09996938705444,6.773628735777631,1739502671.803682,32.09996938705444,57.149642414129254,1739502671.8036852,32.09996938705444,47.459162474573816,1739502671.8036866,32.09996938705444,8.642,1739502671.8036885,32.09996938705444,2.5849645577694824,1739502671.80369,32.09996938705444,1.1859769351861194,1739502671.8036916,32.09996938705444,0.6108,1739502671.803693,32.09996938705444,0.9680313399243524,1739502671.803695,32.09996938705444,0.0,1739502671.8036964,32.09996938705444,0.019784941472591022,1739502671.803698,32.09996938705444,2.2429739048573434,1739502671.8036997,32.09996938705444,0.9482463984517614 +1739502671.823815,32.11996936798096,50.46170937077643,1739502671.8238187,32.11996936798096,6.773628735777631,1739502671.823822,32.11996936798096,57.149642414129254,1739502671.8238254,32.11996936798096,47.459162474573816,1739502671.823827,32.11996936798096,8.642,1739502671.823829,32.11996936798096,2.5849645577694824,1739502671.8238308,32.11996936798096,1.1859769351861194,1739502671.8238323,32.11996936798096,0.6108,1739502671.8238337,32.11996936798096,0.9680313399243524,1739502671.8238356,32.11996936798096,0.0,1739502671.823837,32.11996936798096,0.019784941472591022,1739502671.8238387,32.11996936798096,2.2429739048573434,1739502671.8238409,32.11996936798096,0.9482463984517614 +1739502671.8437865,32.13996934890747,50.46170937077643,1739502671.843789,32.13996934890747,6.773628735777631,1739502671.8437924,32.13996934890747,57.149642414129254,1739502671.8437955,32.13996934890747,47.459162474573816,1739502671.843797,32.13996934890747,8.642,1739502671.843799,32.13996934890747,2.5849645577694824,1739502671.8438005,32.13996934890747,1.1859769351861194,1739502671.8438022,32.13996934890747,0.6108,1739502671.8438036,32.13996934890747,0.9680313399243524,1739502671.8438058,32.13996934890747,0.0,1739502671.843807,32.13996934890747,0.019784941472591022,1739502671.8438087,32.13996934890747,2.2429739048573434,1739502671.8438103,32.13996934890747,0.9482463984517614 +1739502671.863678,32.159969329833984,50.46170937077643,1739502671.8636808,32.159969329833984,6.773628735777631,1739502671.8636844,32.159969329833984,57.149642414129254,1739502671.8636875,32.159969329833984,47.459162474573816,1739502671.863689,32.159969329833984,8.642,1739502671.8636909,32.159969329833984,2.5849645577694824,1739502671.8636925,32.159969329833984,1.1859769351861194,1739502671.8636942,32.159969329833984,0.6108,1739502671.8636956,32.159969329833984,0.9680313399243524,1739502671.863698,32.159969329833984,0.0,1739502671.8636992,32.159969329833984,0.019784941472591022,1739502671.863701,32.159969329833984,2.2429739048573434,1739502671.8637025,32.159969329833984,0.9482463984517614 +1739502671.8839128,32.1799693107605,50.46170937077643,1739502671.8839152,32.1799693107605,6.773628735777631,1739502671.8839188,32.1799693107605,57.149642414129254,1739502671.883922,32.1799693107605,47.459162474573816,1739502671.8839238,32.1799693107605,8.642,1739502671.883926,32.1799693107605,2.5849645577694824,1739502671.8839276,32.1799693107605,1.1859769351861194,1739502671.8839293,32.1799693107605,0.6108,1739502671.883931,32.1799693107605,0.9680313399243524,1739502671.8839326,32.1799693107605,0.0,1739502671.8839343,32.1799693107605,0.019784941472591022,1739502671.883936,32.1799693107605,2.2429739048573434,1739502671.8839376,32.1799693107605,0.9482463984517614 +1739502671.903757,32.19996929168701,50.3956752016473,1739502671.90376,32.19996929168701,6.854502089755112,1739502671.9037633,32.19996929168701,57.31332172780676,1739502671.9037662,32.19996929168701,47.29120282908766,1739502671.9037678,32.19996929168701,8.639774431515068,1739502671.90377,32.19996929168701,2.6197097832778895,1739502671.9037716,32.19996929168701,1.2250702473644608,1739502671.903773,32.19996929168701,0.6108,1739502671.9037747,32.19996929168701,0.9382250193790125,1739502671.9037764,32.19996929168701,0.0,1739502671.903778,32.19996929168701,-0.026698776182173173,1739502671.9037795,32.19996929168701,2.27057559379989,1739502671.9037814,32.19996929168701,0.9503976242699718 +1739502671.9237936,32.219969272613525,50.3956752016473,1739502671.9237967,32.219969272613525,6.854502089755112,1739502671.9238005,32.219969272613525,57.31332172780676,1739502671.923804,32.219969272613525,47.29120282908766,1739502671.9238057,32.219969272613525,8.639774431515068,1739502671.9238079,32.219969272613525,2.6197097832778895,1739502671.9238098,32.219969272613525,1.2250702473644608,1739502671.9238117,32.219969272613525,0.6108,1739502671.923813,32.219969272613525,0.9382250193790125,1739502671.9238155,32.219969272613525,0.0,1739502671.9238172,32.219969272613525,-0.012172604890959282,1739502671.923819,32.219969272613525,2.27057559379989,1739502671.9238207,32.219969272613525,0.9503976242699718 +1739502671.943949,32.23996925354004,50.3956752016473,1739502671.9439518,32.23996925354004,6.854502089755112,1739502671.9439554,32.23996925354004,57.31332172780676,1739502671.943959,32.23996925354004,47.29120282908766,1739502671.943961,32.23996925354004,8.639774431515068,1739502671.943963,32.23996925354004,2.6197097832778895,1739502671.943965,32.23996925354004,1.2250702473644608,1739502671.9439666,32.23996925354004,0.6108,1739502671.9439685,32.23996925354004,0.9382250193790125,1739502671.9439704,32.23996925354004,0.0,1739502671.9439723,32.23996925354004,-0.012172604890959282,1739502671.9439743,32.23996925354004,2.27057559379989,1739502671.943976,32.23996925354004,0.9503976242699718 +1739502671.9640222,32.25996923446655,50.3956752016473,1739502671.9640253,32.25996923446655,6.854502089755112,1739502671.9640288,32.25996923446655,57.31332172780676,1739502671.9640322,32.25996923446655,47.29120282908766,1739502671.964034,32.25996923446655,8.639774431515068,1739502671.964036,32.25996923446655,2.6197097832778895,1739502671.964038,32.25996923446655,1.2250702473644608,1739502671.9640396,32.25996923446655,0.6108,1739502671.9640415,32.25996923446655,0.9382250193790125,1739502671.9640436,32.25996923446655,0.0,1739502671.9640453,32.25996923446655,-0.012172604890959282,1739502671.964047,32.25996923446655,2.27057559379989,1739502671.9640486,32.25996923446655,0.9503976242699718 +1739502671.9842708,32.279969215393066,50.3956752016473,1739502671.9842746,32.279969215393066,6.854502089755112,1739502671.9842784,32.279969215393066,57.31332172780676,1739502671.984282,32.279969215393066,47.29120282908766,1739502671.984284,32.279969215393066,8.639774431515068,1739502671.9842863,32.279969215393066,2.6197097832778895,1739502671.9842882,32.279969215393066,1.2250702473644608,1739502671.9842901,32.279969215393066,0.6108,1739502671.9842916,32.279969215393066,0.9382250193790125,1739502671.984294,32.279969215393066,0.0,1739502671.9842954,32.279969215393066,-0.012172604890959282,1739502671.9842978,32.279969215393066,2.27057559379989,1739502671.9842994,32.279969215393066,0.9503976242699718 +1739502672.0041163,32.29996919631958,50.327360089310055,1739502672.0041196,32.29996919631958,6.9336093431591,1739502672.0041234,32.29996919631958,57.416074394901955,1739502672.0041268,32.29996919631958,47.190246690152975,1739502672.0041285,32.29996919631958,8.63537162513605,1739502672.0041306,32.29996919631958,2.644555811888228,1739502672.0041325,32.29996919631958,1.21163926992367,1739502672.0041342,32.29996919631958,0.6108,1739502672.0041358,32.29996919631958,0.9483603963315547,1739502672.004138,32.29996919631958,0.0,1739502672.0041394,32.29996919631958,0.003801495085516744,1739502672.0041416,32.29996919631958,2.298177282742437,1739502672.0041435,32.29996919631958,0.9495508107616376 +1739502672.0243893,32.319969177246094,50.327360089310055,1739502672.0243926,32.319969177246094,6.9336093431591,1739502672.0243971,32.319969177246094,57.416074394901955,1739502672.0244007,32.319969177246094,47.190246690152975,1739502672.0244024,32.319969177246094,8.63537162513605,1739502672.0244048,32.319969177246094,2.644555811888228,1739502672.0244064,32.319969177246094,1.21163926992367,1739502672.0244083,32.319969177246094,0.6108,1739502672.0244098,32.319969177246094,0.9483603963315547,1739502672.0244122,32.319969177246094,0.0,1739502672.024414,32.319969177246094,-0.0011904144300829422,1739502672.024416,32.319969177246094,2.298177282742437,1739502672.0244179,32.319969177246094,0.9495508107616376 +1739502672.0571666,32.33996915817261,50.327360089310055,1739502672.057176,32.33996915817261,6.9336093431591,1739502672.0571868,32.33996915817261,57.416074394901955,1739502672.0571966,32.33996915817261,47.190246690152975,1739502672.0572014,32.33996915817261,8.63537162513605,1739502672.0572076,32.33996915817261,2.644555811888228,1739502672.0572128,32.33996915817261,1.21163926992367,1739502672.0572178,32.33996915817261,0.6108,1739502672.0572224,32.33996915817261,0.9483603963315547,1739502672.057228,32.33996915817261,0.0,1739502672.0572329,32.33996915817261,-0.0011904144300829422,1739502672.057238,32.33996915817261,2.298177282742437,1739502672.057243,32.33996915817261,0.9495508107616376 +1739502672.0736125,32.35996913909912,50.327360089310055,1739502672.073626,32.35996913909912,6.9336093431591,1739502672.0736425,32.35996913909912,57.416074394901955,1739502672.0736592,32.35996913909912,47.190246690152975,1739502672.0736666,32.35996913909912,8.63537162513605,1739502672.0736773,32.35996913909912,2.644555811888228,1739502672.0736868,32.35996913909912,1.21163926992367,1739502672.073695,32.35996913909912,0.6108,1739502672.0737026,32.35996913909912,0.9483603963315547,1739502672.0737116,32.35996913909912,0.0,1739502672.07372,32.35996913909912,-0.0011904144300829422,1739502672.073729,32.35996913909912,2.298177282742437,1739502672.0737374,32.35996913909912,0.9495508107616376 +1739502672.1011305,32.38996911048889,50.327360089310055,1739502672.1011345,32.38996911048889,6.9336093431591,1739502672.1011393,32.38996911048889,57.416074394901955,1739502672.1011438,32.38996911048889,47.190246690152975,1739502672.1011462,32.38996911048889,8.63537162513605,1739502672.1011486,32.38996911048889,2.644555811888228,1739502672.1011508,32.38996911048889,1.21163926992367,1739502672.1011531,32.38996911048889,0.6108,1739502672.101155,32.38996911048889,0.9483603963315547,1739502672.1011577,32.38996911048889,0.0,1739502672.10116,32.38996911048889,-0.0011904144300829422,1739502672.1011622,32.38996911048889,2.298177282742437,1739502672.1011646,32.38996911048889,0.9495508107616376 +1739502672.1182125,32.41996908187866,50.256944209287575,1739502672.118215,32.41996908187866,7.01073891650125,1739502672.118219,32.41996908187866,57.55859229668236,1739502672.1182225,32.41996908187866,47.048347939360305,1739502672.1182246,32.41996908187866,8.625915840711823,1739502672.1182268,32.41996908187866,2.6752363139488198,1739502672.1182284,32.41996908187866,1.22992548799359,1739502672.1182303,32.41996908187866,0.6108,1739502672.118232,32.41996908187866,0.9345878411154276,1739502672.118234,32.41996908187866,0.0,1739502672.1182356,32.41996908187866,-0.021019988808318037,1739502672.1182375,32.41996908187866,2.3257789716849837,1739502672.1182392,32.41996908187866,0.9494110838676438 +1739502672.1384838,32.439969062805176,50.256944209287575,1739502672.1384869,32.439969062805176,7.01073891650125,1739502672.1384907,32.439969062805176,57.55859229668236,1739502672.1384943,32.439969062805176,47.048347939360305,1739502672.1384962,32.439969062805176,8.625915840711823,1739502672.1384983,32.439969062805176,2.6752363139488198,1739502672.1385005,32.439969062805176,1.22992548799359,1739502672.1385021,32.439969062805176,0.6108,1739502672.1385043,32.439969062805176,0.9345878411154276,1739502672.1385062,32.439969062805176,0.0,1739502672.138508,32.439969062805176,-0.014823242752216248,1739502672.13851,32.439969062805176,2.3257789716849837,1739502672.138512,32.439969062805176,0.9494110838676438 +1739502672.1582131,32.45996904373169,50.256944209287575,1739502672.1582167,32.45996904373169,7.01073891650125,1739502672.1582208,32.45996904373169,57.55859229668236,1739502672.1582246,32.45996904373169,47.048347939360305,1739502672.1582265,32.45996904373169,8.625915840711823,1739502672.1582286,32.45996904373169,2.6752363139488198,1739502672.1582305,32.45996904373169,1.22992548799359,1739502672.158232,32.45996904373169,0.6108,1739502672.158234,32.45996904373169,0.9345878411154276,1739502672.1582358,32.45996904373169,0.0,1739502672.1582377,32.45996904373169,-0.014823242752216248,1739502672.1582398,32.45996904373169,2.3257789716849837,1739502672.1582415,32.45996904373169,0.9494110838676438 +1739502672.178295,32.4799690246582,50.256944209287575,1739502672.1782978,32.4799690246582,7.01073891650125,1739502672.178302,32.4799690246582,57.55859229668236,1739502672.1783056,32.4799690246582,47.048347939360305,1739502672.1783073,32.4799690246582,8.625915840711823,1739502672.1783097,32.4799690246582,2.6752363139488198,1739502672.1783113,32.4799690246582,1.22992548799359,1739502672.1783133,32.4799690246582,0.6108,1739502672.178315,32.4799690246582,0.9345878411154276,1739502672.178317,32.4799690246582,0.0,1739502672.1783187,32.4799690246582,-0.014823242752216248,1739502672.1783206,32.4799690246582,2.3257789716849837,1739502672.1783223,32.4799690246582,0.9494110838676438 +1739502672.1978278,32.49996900558472,50.256944209287575,1739502672.1978314,32.49996900558472,7.01073891650125,1739502672.1978354,32.49996900558472,57.55859229668236,1739502672.1978393,32.49996900558472,47.048347939360305,1739502672.1978414,32.49996900558472,8.625915840711823,1739502672.197844,32.49996900558472,2.6752363139488198,1739502672.1978457,32.49996900558472,1.22992548799359,1739502672.1978476,32.49996900558472,0.6108,1739502672.1978493,32.49996900558472,0.9345878411154276,1739502672.1978517,32.49996900558472,0.0,1739502672.1978533,32.49996900558472,-0.014823242752216248,1739502672.1978555,32.49996900558472,2.3257789716849837,1739502672.1978574,32.49996900558472,0.9494110838676438 +1739502672.218188,32.51996898651123,50.184485599229745,1739502672.2181916,32.51996898651123,7.085835106639463,1739502672.2181954,32.51996898651123,57.629937808390586,1739502672.218199,32.51996898651123,46.980557195136676,1739502672.218201,32.51996898651123,8.619236635398634,1739502672.2182028,32.51996898651123,2.695210786934836,1739502672.2182047,32.51996898651123,1.1906619539365078,1739502672.2182062,32.51996898651123,0.6108,1739502672.218208,32.51996898651123,0.9644099347213981,1739502672.21821,32.51996898651123,0.0,1739502672.218212,32.51996898651123,0.030900060930156063,1739502672.2182136,32.51996898651123,2.3533806606275305,1739502672.2182152,32.51996898651123,0.9477984155602814 +1739502672.2370727,32.539968967437744,50.184485599229745,1739502672.237075,32.539968967437744,7.085835106639463,1739502672.2370782,32.539968967437744,57.629937808390586,1739502672.2370808,32.539968967437744,46.980557195136676,1739502672.2370825,32.539968967437744,8.619236635398634,1739502672.2370842,32.539968967437744,2.695210786934836,1739502672.2370856,32.539968967437744,1.1906619539365078,1739502672.2370872,32.539968967437744,0.6108,1739502672.2370887,32.539968967437744,0.9644099347213981,1739502672.2370903,32.539968967437744,0.0,1739502672.2370915,32.539968967437744,0.016611519161116695,1739502672.2370932,32.539968967437744,2.3533806606275305,1739502672.2370946,32.539968967437744,0.9477984155602814 +1739502672.2569137,32.55996894836426,50.184485599229745,1739502672.2569163,32.55996894836426,7.085835106639463,1739502672.2569196,32.55996894836426,57.629937808390586,1739502672.2569227,32.55996894836426,46.980557195136676,1739502672.256924,32.55996894836426,8.619236635398634,1739502672.256926,32.55996894836426,2.695210786934836,1739502672.2569275,32.55996894836426,1.1906619539365078,1739502672.256929,32.55996894836426,0.6108,1739502672.2569304,32.55996894836426,0.9644099347213981,1739502672.256932,32.55996894836426,0.0,1739502672.2569335,32.55996894836426,0.016611519161116695,1739502672.256935,32.55996894836426,2.3533806606275305,1739502672.2569366,32.55996894836426,0.9477984155602814 +1739502672.2777698,32.57996892929077,50.184485599229745,1739502672.2777734,32.57996892929077,7.085835106639463,1739502672.2777772,32.57996892929077,57.629937808390586,1739502672.2777808,32.57996892929077,46.980557195136676,1739502672.2777824,32.57996892929077,8.619236635398634,1739502672.2777848,32.57996892929077,2.695210786934836,1739502672.2777867,32.57996892929077,1.1906619539365078,1739502672.2777882,32.57996892929077,0.6108,1739502672.27779,32.57996892929077,0.9644099347213981,1739502672.277792,32.57996892929077,0.0,1739502672.2777936,32.57996892929077,0.016611519161116695,1739502672.2777953,32.57996892929077,2.3533806606275305,1739502672.2777975,32.57996892929077,0.9477984155602814 +1739502672.2974176,32.599968910217285,50.184485599229745,1739502672.2974207,32.599968910217285,7.085835106639463,1739502672.2974243,32.599968910217285,57.629937808390586,1739502672.2974277,32.599968910217285,46.980557195136676,1739502672.2974296,32.599968910217285,8.619236635398634,1739502672.2974315,32.599968910217285,2.695210786934836,1739502672.2974331,32.599968910217285,1.1906619539365078,1739502672.2974348,32.599968910217285,0.6108,1739502672.2974365,32.599968910217285,0.9644099347213981,1739502672.2974381,32.599968910217285,0.0,1739502672.29744,32.599968910217285,0.016611519161116695,1739502672.2974417,32.599968910217285,2.3533806606275305,1739502672.2974436,32.599968910217285,0.9477984155602814 +1739502672.317526,32.6199688911438,50.184485599229745,1739502672.3175287,32.6199688911438,7.085835106639463,1739502672.3175323,32.6199688911438,57.629937808390586,1739502672.3175356,32.6199688911438,46.980557195136676,1739502672.3175375,32.6199688911438,8.619236635398634,1739502672.31754,32.6199688911438,2.695210786934836,1739502672.3175416,32.6199688911438,1.1906619539365078,1739502672.3175433,32.6199688911438,0.6108,1739502672.3175447,32.6199688911438,0.9644099347213981,1739502672.3175468,32.6199688911438,0.0,1739502672.3175483,32.6199688911438,0.016611519161116695,1739502672.3175502,32.6199688911438,2.3533806606275305,1739502672.3175516,32.6199688911438,0.9477984155602814 +1739502672.3368537,32.63996887207031,50.109967771378855,1739502672.3368556,32.63996887207031,7.1589156867473385,1739502672.3368583,32.63996887207031,57.729835452328516,1739502672.336861,32.63996887207031,46.87705552891564,1739502672.3368623,32.63996887207031,8.60804846052294,1739502672.3368638,32.63996887207031,2.720200168680172,1739502672.336865,32.63996887207031,1.178878170466792,1739502672.3368664,32.63996887207031,0.6108,1739502672.3368673,32.63996887207031,0.9735444409686831,1739502672.3368688,32.63996887207031,0.0,1739502672.33687,32.63996887207031,0.026836429147696926,1739502672.3368714,32.63996887207031,2.3809823495700773,1739502672.3368723,32.63996887207031,0.9499032982867855 +1739502672.3567522,32.659968852996826,50.109967771378855,1739502672.356767,32.659968852996826,7.1589156867473385,1739502672.35677,32.659968852996826,57.729835452328516,1739502672.3567724,32.659968852996826,46.87705552891564,1739502672.3567736,32.659968852996826,8.60804846052294,1739502672.3567755,32.659968852996826,2.720200168680172,1739502672.3567767,32.659968852996826,1.178878170466792,1739502672.356778,32.659968852996826,0.6108,1739502672.356779,32.659968852996826,0.9735444409686831,1739502672.3567805,32.659968852996826,0.0,1739502672.3567815,32.659968852996826,0.023641142681897542,1739502672.356783,32.659968852996826,2.3809823495700773,1739502672.3567843,32.659968852996826,0.9499032982867855 +1739502672.377022,32.67996883392334,50.109967771378855,1739502672.3770242,32.67996883392334,7.1589156867473385,1739502672.377027,32.67996883392334,57.729835452328516,1739502672.37703,32.67996883392334,46.87705552891564,1739502672.377031,32.67996883392334,8.60804846052294,1739502672.3770328,32.67996883392334,2.720200168680172,1739502672.377034,32.67996883392334,1.178878170466792,1739502672.3770356,32.67996883392334,0.6108,1739502672.3770368,32.67996883392334,0.9735444409686831,1739502672.3770382,32.67996883392334,0.0,1739502672.3770397,32.67996883392334,0.023641142681897542,1739502672.377041,32.67996883392334,2.3809823495700773,1739502672.3770425,32.67996883392334,0.9499032982867855 +1739502672.3976197,32.69996881484985,50.109967771378855,1739502672.397622,32.69996881484985,7.1589156867473385,1739502672.3976247,32.69996881484985,57.729835452328516,1739502672.3976274,32.69996881484985,46.87705552891564,1739502672.3976288,32.69996881484985,8.60804846052294,1739502672.3976305,32.69996881484985,2.720200168680172,1739502672.3976316,32.69996881484985,1.178878170466792,1739502672.3976333,32.69996881484985,0.6108,1739502672.3976345,32.69996881484985,0.9735444409686831,1739502672.3976362,32.69996881484985,0.0,1739502672.3976374,32.69996881484985,0.023641142681897542,1739502672.3976386,32.69996881484985,2.3809823495700773,1739502672.3976402,32.69996881484985,0.9499032982867855 +1739502672.4174185,32.71996879577637,50.109967771378855,1739502672.4174209,32.71996879577637,7.1589156867473385,1739502672.4174237,32.71996879577637,57.729835452328516,1739502672.417426,32.71996879577637,46.87705552891564,1739502672.4174275,32.71996879577637,8.60804846052294,1739502672.417429,32.71996879577637,2.720200168680172,1739502672.4174306,32.71996879577637,1.178878170466792,1739502672.4174318,32.71996879577637,0.6108,1739502672.417433,32.71996879577637,0.9735444409686831,1739502672.4174347,32.71996879577637,0.0,1739502672.417436,32.71996879577637,0.023641142681897542,1739502672.4174376,32.71996879577637,2.3809823495700773,1739502672.4174387,32.71996879577637,0.9499032982867855 +1739502672.4370081,32.73996877670288,50.03328445190242,1739502672.4370108,32.73996877670288,7.230075905866313,1739502672.437014,32.73996877670288,57.879136436451304,1739502672.4370167,32.73996877670288,46.72361250764034,1739502672.4370182,32.73996877670288,8.590343355397511,1739502672.4370198,32.73996877670288,2.751641627402783,1739502672.4370213,32.73996877670288,1.203627094592804,1739502672.4370224,32.73996877670288,0.6108,1739502672.437024,32.73996877670288,0.9544586634246156,1739502672.4370253,32.73996877670288,0.0,1739502672.4370265,32.73996877670288,-0.007878321849086092,1739502672.4370282,32.73996877670288,2.408584038512624,1739502672.4370296,32.73996877670288,0.9524871461497115 +1739502672.45728,32.759968757629395,50.03328445190242,1739502672.4572833,32.759968757629395,7.230075905866313,1739502672.4572868,32.759968757629395,57.879136436451304,1739502672.4572902,32.759968757629395,46.72361250764034,1739502672.457292,32.759968757629395,8.590343355397511,1739502672.4572942,32.759968757629395,2.751641627402783,1739502672.4572961,32.759968757629395,1.203627094592804,1739502672.4572976,32.759968757629395,0.6108,1739502672.4572992,32.759968757629395,0.9544586634246156,1739502672.4573011,32.759968757629395,0.0,1739502672.4573028,32.759968757629395,0.0019715172749040777,1739502672.4573047,32.759968757629395,2.408584038512624,1739502672.4573066,32.759968757629395,0.9524871461497115 +1739502672.4775612,32.77996873855591,50.03328445190242,1739502672.477564,32.77996873855591,7.230075905866313,1739502672.477568,32.77996873855591,57.879136436451304,1739502672.4775715,32.77996873855591,46.72361250764034,1739502672.4775734,32.77996873855591,8.590343355397511,1739502672.477576,32.77996873855591,2.751641627402783,1739502672.4775777,32.77996873855591,1.203627094592804,1739502672.4775796,32.77996873855591,0.6108,1739502672.477581,32.77996873855591,0.9544586634246156,1739502672.4775832,32.77996873855591,0.0,1739502672.4775848,32.77996873855591,0.0019715172749040777,1739502672.477587,32.77996873855591,2.408584038512624,1739502672.4775887,32.77996873855591,0.9524871461497115 +1739502672.4975464,32.79996871948242,50.03328445190242,1739502672.4975502,32.79996871948242,7.230075905866313,1739502672.4975553,32.79996871948242,57.879136436451304,1739502672.4975593,32.79996871948242,46.72361250764034,1739502672.4975615,32.79996871948242,8.590343355397511,1739502672.4975638,32.79996871948242,2.751641627402783,1739502672.497566,32.79996871948242,1.203627094592804,1739502672.497568,32.79996871948242,0.6108,1739502672.4975698,32.79996871948242,0.9544586634246156,1739502672.4975722,32.79996871948242,0.0,1739502672.497574,32.79996871948242,0.0019715172749040777,1739502672.4975762,32.79996871948242,2.408584038512624,1739502672.497578,32.79996871948242,0.9524871461497115 +1739502672.5176954,32.819968700408936,50.03328445190242,1739502672.5176983,32.819968700408936,7.230075905866313,1739502672.5177019,32.819968700408936,57.879136436451304,1739502672.5177057,32.819968700408936,46.72361250764034,1739502672.5177076,32.819968700408936,8.590343355397511,1739502672.5177095,32.819968700408936,2.751641627402783,1739502672.5177116,32.819968700408936,1.203627094592804,1739502672.5177133,32.819968700408936,0.6108,1739502672.517715,32.819968700408936,0.9544586634246156,1739502672.517717,32.819968700408936,0.0,1739502672.5177188,32.819968700408936,0.0019715172749040777,1739502672.517721,32.819968700408936,2.408584038512624,1739502672.5177228,32.819968700408936,0.9524871461497115 +1739502672.537538,32.83996868133545,50.03328445190242,1739502672.5375419,32.83996868133545,7.230075905866313,1739502672.5375473,32.83996868133545,57.879136436451304,1739502672.537551,32.83996868133545,46.72361250764034,1739502672.537553,32.83996868133545,8.590343355397511,1739502672.5375555,32.83996868133545,2.751641627402783,1739502672.5375574,32.83996868133545,1.203627094592804,1739502672.5375593,32.83996868133545,0.6108,1739502672.5375612,32.83996868133545,0.9544586634246156,1739502672.5375633,32.83996868133545,0.0,1739502672.5375652,32.83996868133545,0.0019715172749040777,1739502672.5375671,32.83996868133545,2.408584038512624,1739502672.537569,32.83996868133545,0.9524871461497115 +1739502672.5575962,32.85996866226196,49.95455537928009,1739502672.5576,32.85996866226196,7.299191055068736,1739502672.5576038,32.85996866226196,57.981188522717154,1739502672.5576074,32.85996866226196,46.62250563337788,1739502672.5576093,32.85996866226196,8.576320107809,1739502672.5576115,32.85996866226196,2.7755771369410476,1739502672.5576136,32.85996866226196,1.1879740681335,1739502672.5576153,32.85996866226196,0.6108,1739502672.5576172,32.85996866226196,0.9664859449703158,1739502672.557619,32.85996866226196,0.0,1739502672.557621,32.85996866226196,0.0194360609092306,1739502672.5576227,32.85996866226196,2.436185727455171,1739502672.5576246,32.85996866226196,0.9525075575251418 +1739502672.5776112,32.87996864318848,49.95455537928009,1739502672.5776153,32.87996864318848,7.299191055068736,1739502672.5776198,32.87996864318848,57.981188522717154,1739502672.5776258,32.87996864318848,46.62250563337788,1739502672.5776293,32.87996864318848,8.576320107809,1739502672.5776322,32.87996864318848,2.7755771369410476,1739502672.5776496,32.87996864318848,1.1879740681335,1739502672.5776534,32.87996864318848,0.6108,1739502672.5776567,32.87996864318848,0.9664859449703158,1739502672.577661,32.87996864318848,0.0,1739502672.5776641,32.87996864318848,0.01397838744517399,1739502672.5776734,32.87996864318848,2.436185727455171,1739502672.5776758,32.87996864318848,0.9525075575251418 +1739502672.5975301,32.89996862411499,49.95455537928009,1739502672.5975342,32.89996862411499,7.299191055068736,1739502672.5975385,32.89996862411499,57.981188522717154,1739502672.5975423,32.89996862411499,46.62250563337788,1739502672.5975444,32.89996862411499,8.576320107809,1739502672.5975468,32.89996862411499,2.7755771369410476,1739502672.5975492,32.89996862411499,1.1879740681335,1739502672.597551,32.89996862411499,0.6108,1739502672.597553,32.89996862411499,0.9664859449703158,1739502672.5975556,32.89996862411499,0.0,1739502672.5975575,32.89996862411499,0.01397838744517399,1739502672.5975597,32.89996862411499,2.436185727455171,1739502672.5975618,32.89996862411499,0.9525075575251418 +1739502672.6174634,32.919968605041504,49.95455537928009,1739502672.6174664,32.919968605041504,7.299191055068736,1739502672.6174703,32.919968605041504,57.981188522717154,1739502672.6174738,32.919968605041504,46.62250563337788,1739502672.6174755,32.919968605041504,8.576320107809,1739502672.617478,32.919968605041504,2.7755771369410476,1739502672.6174796,32.919968605041504,1.1879740681335,1739502672.6174815,32.919968605041504,0.6108,1739502672.617483,32.919968605041504,0.9664859449703158,1739502672.617485,32.919968605041504,0.0,1739502672.617487,32.919968605041504,0.01397838744517399,1739502672.6174886,32.919968605041504,2.436185727455171,1739502672.6174908,32.919968605041504,0.9525075575251418 +1739502672.637989,32.93996858596802,49.95455537928009,1739502672.6379926,32.93996858596802,7.299191055068736,1739502672.6379974,32.93996858596802,57.981188522717154,1739502672.6380012,32.93996858596802,46.62250563337788,1739502672.6380029,32.93996858596802,8.576320107809,1739502672.6380055,32.93996858596802,2.7755771369410476,1739502672.6380076,32.93996858596802,1.1879740681335,1739502672.6380095,32.93996858596802,0.6108,1739502672.6380115,32.93996858596802,0.9664859449703158,1739502672.6380134,32.93996858596802,0.0,1739502672.6380153,32.93996858596802,0.01397838744517399,1739502672.6380177,32.93996858596802,2.436185727455171,1739502672.6380198,32.93996858596802,0.9525075575251418 +1739502672.6581554,32.95996856689453,49.87388390242983,1739502672.6581585,32.95996856689453,7.366160517051526,1739502672.6581626,32.95996856689453,58.147717294344055,1739502672.6581662,32.95996856689453,46.45578726122637,1739502672.658168,32.95996856689453,8.54543523342846,1739502672.6581705,32.95996856689453,2.809370900071626,1739502672.6581721,32.95996856689453,1.2248397725191364,1739502672.658174,32.95996856689453,0.6108,1739502672.6581757,32.95996856689453,0.9383980251408895,1739502672.6581779,32.95996856689453,0.0,1739502672.6581795,32.95996856689453,-0.029089992426181828,1739502672.6581814,32.95996856689453,2.4637874163977176,1739502672.658183,32.95996856689453,0.9540291400329449 +1739502672.6782167,32.979968547821045,49.87388390242983,1739502672.6782198,32.979968547821045,7.366160517051526,1739502672.6782236,32.979968547821045,58.147717294344055,1739502672.6782272,32.979968547821045,46.45578726122637,1739502672.6782293,32.979968547821045,8.54543523342846,1739502672.6782315,32.979968547821045,2.809370900071626,1739502672.6782334,32.979968547821045,1.2248397725191364,1739502672.678235,32.979968547821045,0.6108,1739502672.6782367,32.979968547821045,0.9383980251408895,1739502672.6782389,32.979968547821045,0.0,1739502672.6782408,32.979968547821045,-0.015631114892055376,1739502672.6782424,32.979968547821045,2.4637874163977176,1739502672.6782448,32.979968547821045,0.9540291400329449 +1739502672.6982372,32.99996852874756,49.87388390242983,1739502672.6982408,32.99996852874756,7.366160517051526,1739502672.698245,32.99996852874756,58.147717294344055,1739502672.6982486,32.99996852874756,46.45578726122637,1739502672.6982505,32.99996852874756,8.54543523342846,1739502672.6982532,32.99996852874756,2.809370900071626,1739502672.698255,32.99996852874756,1.2248397725191364,1739502672.698257,32.99996852874756,0.6108,1739502672.6982586,32.99996852874756,0.9383980251408895,1739502672.6982608,32.99996852874756,0.0,1739502672.6982627,32.99996852874756,-0.015631114892055376,1739502672.6982648,32.99996852874756,2.4637874163977176,1739502672.6982665,32.99996852874756,0.9540291400329449 +1739502672.7176678,33.01996850967407,49.87388390242983,1739502672.7176712,33.01996850967407,7.366160517051526,1739502672.717675,33.01996850967407,58.147717294344055,1739502672.7176785,33.01996850967407,46.45578726122637,1739502672.7176805,33.01996850967407,8.54543523342846,1739502672.7176826,33.01996850967407,2.809370900071626,1739502672.7176847,33.01996850967407,1.2248397725191364,1739502672.7176864,33.01996850967407,0.6108,1739502672.717688,33.01996850967407,0.9383980251408895,1739502672.7176902,33.01996850967407,0.0,1739502672.717692,33.01996850967407,-0.015631114892055376,1739502672.7176938,33.01996850967407,2.4637874163977176,1739502672.7176955,33.01996850967407,0.9540291400329449 +1739502672.7374403,33.039968490600586,49.87388390242983,1739502672.7374427,33.039968490600586,7.366160517051526,1739502672.7374463,33.039968490600586,58.147717294344055,1739502672.7374494,33.039968490600586,46.45578726122637,1739502672.737451,33.039968490600586,8.54543523342846,1739502672.737453,33.039968490600586,2.809370900071626,1739502672.737455,33.039968490600586,1.2248397725191364,1739502672.7374563,33.039968490600586,0.6108,1739502672.7374578,33.039968490600586,0.9383980251408895,1739502672.7374597,33.039968490600586,0.0,1739502672.7374613,33.039968490600586,-0.015631114892055376,1739502672.7374628,33.039968490600586,2.4637874163977176,1739502672.7374647,33.039968490600586,0.9540291400329449 +1739502672.7571988,33.0599684715271,49.87388390242983,1739502672.7572021,33.0599684715271,7.366160517051526,1739502672.7572057,33.0599684715271,58.147717294344055,1739502672.757209,33.0599684715271,46.45578726122637,1739502672.7572107,33.0599684715271,8.54543523342846,1739502672.7572129,33.0599684715271,2.809370900071626,1739502672.7572148,33.0599684715271,1.2248397725191364,1739502672.7572162,33.0599684715271,0.6108,1739502672.7572181,33.0599684715271,0.9383980251408895,1739502672.7572198,33.0599684715271,0.0,1739502672.7572215,33.0599684715271,-0.015631114892055376,1739502672.7572231,33.0599684715271,2.4637874163977176,1739502672.757225,33.0599684715271,0.9540291400329449 +1739502672.7777224,33.07996845245361,49.791409557310125,1739502672.777725,33.07996845245361,7.4308677109018255,1739502672.7777283,33.07996845245361,58.23334973436541,1739502672.7777314,33.07996845245361,46.37595694294477,1739502672.7777328,33.07996845245361,8.528195743975141,1739502672.777735,33.07996845245361,2.8307260077495555,1739502672.7777364,33.07996845245361,1.1941090169909234,1739502672.777738,33.07996845245361,0.6108,1739502672.7777395,33.07996845245361,0.9617540928619662,1739502672.7777412,33.07996845245361,0.0,1739502672.7777429,33.07996845245361,0.02122268721138828,1739502672.7777445,33.07996845245361,2.4913891053402644,1739502672.7777462,33.07996845245361,0.9520482263589202 +1739502672.7972887,33.09996843338013,49.791409557310125,1739502672.797292,33.09996843338013,7.4308677109018255,1739502672.797296,33.09996843338013,58.23334973436541,1739502672.7972991,33.09996843338013,46.37595694294477,1739502672.797301,33.09996843338013,8.528195743975141,1739502672.797303,33.09996843338013,2.8307260077495555,1739502672.7973046,33.09996843338013,1.1941090169909234,1739502672.797306,33.09996843338013,0.6108,1739502672.797308,33.09996843338013,0.9617540928619662,1739502672.7973096,33.09996843338013,0.0,1739502672.7973113,33.09996843338013,0.009705866503046057,1739502672.797313,33.09996843338013,2.4913891053402644,1739502672.797315,33.09996843338013,0.9520482263589202 +1739502672.8172922,33.11996841430664,49.791409557310125,1739502672.8172948,33.11996841430664,7.4308677109018255,1739502672.8172984,33.11996841430664,58.23334973436541,1739502672.8173018,33.11996841430664,46.37595694294477,1739502672.8173032,33.11996841430664,8.528195743975141,1739502672.817305,33.11996841430664,2.8307260077495555,1739502672.817307,33.11996841430664,1.1941090169909234,1739502672.8173084,33.11996841430664,0.6108,1739502672.8173096,33.11996841430664,0.9617540928619662,1739502672.8173115,33.11996841430664,0.0,1739502672.817313,33.11996841430664,0.009705866503046057,1739502672.8173149,33.11996841430664,2.4913891053402644,1739502672.8173163,33.11996841430664,0.9520482263589202 +1739502672.837265,33.139968395233154,49.791409557310125,1739502672.8372686,33.139968395233154,7.4308677109018255,1739502672.837273,33.139968395233154,58.23334973436541,1739502672.8372765,33.139968395233154,46.37595694294477,1739502672.837278,33.139968395233154,8.528195743975141,1739502672.83728,33.139968395233154,2.8307260077495555,1739502672.8372817,33.139968395233154,1.1941090169909234,1739502672.8372834,33.139968395233154,0.6108,1739502672.8372848,33.139968395233154,0.9617540928619662,1739502672.837287,33.139968395233154,0.0,1739502672.8372884,33.139968395233154,0.009705866503046057,1739502672.8372905,33.139968395233154,2.4913891053402644,1739502672.8372922,33.139968395233154,0.9520482263589202 +1739502672.8573735,33.15996837615967,49.791409557310125,1739502672.857376,33.15996837615967,7.4308677109018255,1739502672.8573794,33.15996837615967,58.23334973436541,1739502672.8573823,33.15996837615967,46.37595694294477,1739502672.8573842,33.15996837615967,8.528195743975141,1739502672.8573864,33.15996837615967,2.8307260077495555,1739502672.8573878,33.15996837615967,1.1941090169909234,1739502672.8573895,33.15996837615967,0.6108,1739502672.8573909,33.15996837615967,0.9617540928619662,1739502672.8573928,33.15996837615967,0.0,1739502672.8573945,33.15996837615967,0.009705866503046057,1739502672.857396,33.15996837615967,2.4913891053402644,1739502672.8573976,33.15996837615967,0.9520482263589202 +1739502672.8775287,33.17996835708618,49.70722771610914,1739502672.8775313,33.17996835708618,7.4932384117797035,1739502672.8775349,33.17996835708618,58.235151987151006,1739502672.877538,33.17996835708618,46.37215848422261,1739502672.8775396,33.17996835708618,8.527367874766465,1739502672.8775415,33.17996835708618,2.8409164075496145,1739502672.8775432,33.17996835708618,1.104758776343148,1739502672.8775446,33.17996835708618,0.6108,1739502672.8775463,33.17996835708618,1.033017065984956,1739502672.877548,33.17996835708618,0.0,1739502672.8775496,33.17996835708618,0.11184449362408722,1739502672.8775513,33.17996835708618,2.518990794282811,1739502672.8775532,33.17996835708618,0.9530909142634899 +1739502672.8972032,33.199968338012695,49.70722771610914,1739502672.8972068,33.199968338012695,7.4932384117797035,1739502672.8972106,33.199968338012695,58.235151987151006,1739502672.897214,33.199968338012695,46.37215848422261,1739502672.8972158,33.199968338012695,8.527367874766465,1739502672.8972178,33.199968338012695,2.8409164075496145,1739502672.8972197,33.199968338012695,1.104758776343148,1739502672.8972213,33.199968338012695,0.6108,1739502672.8972232,33.199968338012695,1.033017065984956,1739502672.8972251,33.199968338012695,0.0,1739502672.8972268,33.199968338012695,0.07992615172146611,1739502672.8972285,33.199968338012695,2.518990794282811,1739502672.8972304,33.199968338012695,0.9530909142634899 +1739502672.917608,33.21996831893921,49.70722771610914,1739502672.9176111,33.21996831893921,7.4932384117797035,1739502672.917615,33.21996831893921,58.235151987151006,1739502672.9176188,33.21996831893921,46.37215848422261,1739502672.9176202,33.21996831893921,8.527367874766465,1739502672.9176226,33.21996831893921,2.8409164075496145,1739502672.9176242,33.21996831893921,1.104758776343148,1739502672.917626,33.21996831893921,0.6108,1739502672.9176276,33.21996831893921,1.033017065984956,1739502672.9176297,33.21996831893921,0.0,1739502672.9176314,33.21996831893921,0.07992615172146611,1739502672.9176333,33.21996831893921,2.518990794282811,1739502672.917635,33.21996831893921,0.9530909142634899 +1739502672.9422762,33.23996829986572,49.70722771610914,1739502672.9422843,33.23996829986572,7.4932384117797035,1739502672.9422946,33.23996829986572,58.235151987151006,1739502672.9423048,33.23996829986572,46.37215848422261,1739502672.9423096,33.23996829986572,8.527367874766465,1739502672.9423158,33.23996829986572,2.8409164075496145,1739502672.9423208,33.23996829986572,1.104758776343148,1739502672.9423256,33.23996829986572,0.6108,1739502672.9423301,33.23996829986572,1.033017065984956,1739502672.9423358,33.23996829986572,0.0,1739502672.9423406,33.23996829986572,0.07992615172146611,1739502672.942346,33.23996829986572,2.518990794282811,1739502672.942351,33.23996829986572,0.9530909142634899 +1739502672.9628696,33.259968280792236,49.70722771610914,1739502672.9628782,33.259968280792236,7.4932384117797035,1739502672.9628887,33.259968280792236,58.235151987151006,1739502672.9628987,33.259968280792236,46.37215848422261,1739502672.9629035,33.259968280792236,8.527367874766465,1739502672.96291,33.259968280792236,2.8409164075496145,1739502672.9629147,33.259968280792236,1.104758776343148,1739502672.9629197,33.259968280792236,0.6108,1739502672.9629242,33.259968280792236,1.033017065984956,1739502672.9629307,33.259968280792236,0.0,1739502672.9629354,33.259968280792236,0.07992615172146611,1739502672.962941,33.259968280792236,2.518990794282811,1739502672.9629464,33.259968280792236,0.9530909142634899 +1739502672.9885037,33.27996826171875,49.70722771610914,1739502672.9885101,33.27996826171875,7.4932384117797035,1739502672.988518,33.27996826171875,58.235151987151006,1739502672.988525,33.27996826171875,46.37215848422261,1739502672.988528,33.27996826171875,8.527367874766465,1739502672.9885325,33.27996826171875,2.8409164075496145,1739502672.9885364,33.27996826171875,1.104758776343148,1739502672.98854,33.27996826171875,0.6108,1739502672.9885433,33.27996826171875,1.033017065984956,1739502672.9885473,33.27996826171875,0.0,1739502672.988551,33.27996826171875,0.07992615172146611,1739502672.9885547,33.27996826171875,2.518990794282811,1739502672.9885583,33.27996826171875,0.9530909142634899 +1739502673.010143,33.299968242645264,49.620891441693324,1739502673.01015,33.299968242645264,7.553584794028998,1739502673.0101576,33.299968242645264,58.466503115877835,1739502673.0101645,33.299968242645264,46.13026902774672,1739502673.0101683,33.299968242645264,8.464185690493544,1739502673.010173,33.299968242645264,2.886409258454766,1739502673.0101767,33.299968242645264,1.2024122356530884,1739502673.01018,33.299968242645264,0.6108,1739502673.010184,33.299968242645264,0.9553867404565152,1739502673.0101879,33.299968242645264,0.0,1739502673.010192,33.299968242645264,-0.0466572553886889,1739502673.0101957,33.299968242645264,2.546592483225358,1739502673.0102005,33.299968242645264,0.962486655187467 +1739502673.0443764,33.33996820449829,49.620891441693324,1739502673.0443852,33.33996820449829,7.553584794028998,1739502673.0443974,33.33996820449829,58.466503115877835,1739502673.0444112,33.33996820449829,46.13026902774672,1739502673.0444188,33.33996820449829,8.464185690493544,1739502673.0444286,33.33996820449829,2.886409258454766,1739502673.0444374,33.33996820449829,1.2024122356530884,1739502673.0444462,33.33996820449829,0.6108,1739502673.0444548,33.33996820449829,0.9553867404565152,1739502673.0444639,33.33996820449829,0.0,1739502673.044473,33.33996820449829,-0.0070999147309518396,1739502673.0444815,33.33996820449829,2.546592483225358,1739502673.0444906,33.33996820449829,0.962486655187467 +1739502673.060589,33.359968185424805,49.620891441693324,1739502673.0605955,33.359968185424805,7.553584794028998,1739502673.060603,33.359968185424805,58.466503115877835,1739502673.0606098,33.359968185424805,46.13026902774672,1739502673.0606132,33.359968185424805,8.464185690493544,1739502673.0606172,33.359968185424805,2.886409258454766,1739502673.0606205,33.359968185424805,1.2024122356530884,1739502673.060624,33.359968185424805,0.6108,1739502673.0606272,33.359968185424805,0.9553867404565152,1739502673.0606313,33.359968185424805,0.0,1739502673.0606349,33.359968185424805,-0.0070999147309518396,1739502673.0606384,33.359968185424805,2.546592483225358,1739502673.0606418,33.359968185424805,0.962486655187467 +1739502673.0819025,33.37996816635132,49.620891441693324,1739502673.081906,33.37996816635132,7.553584794028998,1739502673.0819106,33.37996816635132,58.466503115877835,1739502673.081915,33.37996816635132,46.13026902774672,1739502673.0819168,33.37996816635132,8.464185690493544,1739502673.08192,33.37996816635132,2.886409258454766,1739502673.081922,33.37996816635132,1.2024122356530884,1739502673.0819244,33.37996816635132,0.6108,1739502673.081926,33.37996816635132,0.9553867404565152,1739502673.081929,33.37996816635132,0.0,1739502673.081931,33.37996816635132,-0.0070999147309518396,1739502673.081933,33.37996816635132,2.546592483225358,1739502673.0819356,33.37996816635132,0.962486655187467 +1739502673.1020458,33.39996814727783,49.53244290289095,1739502673.1020494,33.39996814727783,7.611844561047773,1739502673.1020539,33.39996814727783,58.587434304384054,1739502673.1020582,33.39996814727783,46.016498198787,1739502673.1020603,33.39996814727783,8.424648310216758,1739502673.1020632,33.39996814727783,2.9144071743539848,1739502673.102065,33.39996814727783,1.2041703190894681,1739502673.1020672,33.39996814727783,0.6108,1739502673.1020691,33.39996814727783,0.9540439652791985,1739502673.1020715,33.39996814727783,0.0,1739502673.1020737,33.39996814727783,-0.008699475058054549,1739502673.1020758,33.39996814727783,2.5741941721679047,1739502673.1020782,33.39996814727783,0.9622435774072978 +1739502673.1225264,33.419968128204346,49.53244290289095,1739502673.1225295,33.419968128204346,7.611844561047773,1739502673.1225336,33.419968128204346,58.587434304384054,1739502673.1225386,33.419968128204346,46.016498198787,1739502673.1225414,33.419968128204346,8.424648310216758,1739502673.122545,33.419968128204346,2.9144071743539848,1739502673.1225479,33.419968128204346,1.2041703190894681,1739502673.122551,33.419968128204346,0.6108,1739502673.122554,33.419968128204346,0.9540439652791985,1739502673.1225574,33.419968128204346,0.0,1739502673.1225605,33.419968128204346,-0.008199612128099276,1739502673.1225636,33.419968128204346,2.5741941721679047,1739502673.122567,33.419968128204346,0.9622435774072978 +1739502673.1425483,33.43996810913086,49.53244290289095,1739502673.1425512,33.43996810913086,7.611844561047773,1739502673.1425557,33.43996810913086,58.587434304384054,1739502673.1425602,33.43996810913086,46.016498198787,1739502673.1425629,33.43996810913086,8.424648310216758,1739502673.1425664,33.43996810913086,2.9144071743539848,1739502673.1425695,33.43996810913086,1.2041703190894681,1739502673.1425726,33.43996810913086,0.6108,1739502673.1425753,33.43996810913086,0.9540439652791985,1739502673.1425788,33.43996810913086,0.0,1739502673.142582,33.43996810913086,-0.008199612128099276,1739502673.142585,33.43996810913086,2.5741941721679047,1739502673.1425881,33.43996810913086,0.9622435774072978 +1739502673.1637604,33.45996809005737,49.53244290289095,1739502673.163764,33.45996809005737,7.611844561047773,1739502673.1637685,33.45996809005737,58.587434304384054,1739502673.1637738,33.45996809005737,46.016498198787,1739502673.1637764,33.45996809005737,8.424648310216758,1739502673.1637802,33.45996809005737,2.9144071743539848,1739502673.1637833,33.45996809005737,1.2041703190894681,1739502673.1637866,33.45996809005737,0.6108,1739502673.16379,33.45996809005737,0.9540439652791985,1739502673.1637933,33.45996809005737,0.0,1739502673.1637967,33.45996809005737,-0.008199612128099276,1739502673.1638002,33.45996809005737,2.5741941721679047,1739502673.1638038,33.45996809005737,0.9622435774072978 +1739502673.181152,33.47996807098389,49.53244290289095,1739502673.181154,33.47996807098389,7.611844561047773,1739502673.1811569,33.47996807098389,58.587434304384054,1739502673.1811597,33.47996807098389,46.016498198787,1739502673.1811607,33.47996807098389,8.424648310216758,1739502673.1811626,33.47996807098389,2.9144071743539848,1739502673.1811638,33.47996807098389,1.2041703190894681,1739502673.181165,33.47996807098389,0.6108,1739502673.1811664,33.47996807098389,0.9540439652791985,1739502673.181168,33.47996807098389,0.0,1739502673.1811695,33.47996807098389,-0.008199612128099276,1739502673.181171,33.47996807098389,2.5741941721679047,1739502673.1811724,33.47996807098389,0.9622435774072978 +1739502673.2008822,33.4999680519104,49.53244290289095,1739502673.2008846,33.4999680519104,7.611844561047773,1739502673.2008874,33.4999680519104,58.587434304384054,1739502673.20089,33.4999680519104,46.016498198787,1739502673.2008915,33.4999680519104,8.424648310216758,1739502673.2008932,33.4999680519104,2.9144071743539848,1739502673.2008944,33.4999680519104,1.2041703190894681,1739502673.2008958,33.4999680519104,0.6108,1739502673.200897,33.4999680519104,0.9540439652791985,1739502673.2008986,33.4999680519104,0.0,1739502673.2008998,33.4999680519104,-0.008199612128099276,1739502673.2009013,33.4999680519104,2.5741941721679047,1739502673.2009027,33.4999680519104,0.9622435774072978 +1739502673.220819,33.519968032836914,49.44251743559071,1739502673.2208219,33.519968032836914,7.667580759088082,1739502673.2208247,33.519968032836914,58.67767337091755,1739502673.2208276,33.519968032836914,45.934362656498784,1739502673.220829,33.519968032836914,8.391958533370458,1739502673.2208307,33.519968032836914,2.937970338854154,1739502673.2208323,33.519968032836914,1.181676379604376,1739502673.2208338,33.519968032836914,0.6108,1739502673.220835,33.519968032836914,0.9713675336940375,1739502673.2208366,33.519968032836914,0.0,1739502673.220838,33.519968032836914,0.018320165062830504,1739502673.2208395,33.519968032836914,2.6017958611104515,1739502673.220841,33.519968032836914,0.9613348044370389 +1739502673.2406285,33.53996801376343,49.44251743559071,1739502673.2406309,33.53996801376343,7.667580759088082,1739502673.2406335,33.53996801376343,58.67767337091755,1739502673.2406368,33.53996801376343,45.934362656498784,1739502673.2406383,33.53996801376343,8.391958533370458,1739502673.24064,33.53996801376343,2.937970338854154,1739502673.2406416,33.53996801376343,1.181676379604376,1739502673.240643,33.53996801376343,0.6108,1739502673.240644,33.53996801376343,0.9713675336940375,1739502673.240646,33.53996801376343,0.0,1739502673.240647,33.53996801376343,0.010032729256998607,1739502673.2406485,33.53996801376343,2.6017958611104515,1739502673.24065,33.53996801376343,0.9613348044370389 +1739502673.2620258,33.55996799468994,49.44251743559071,1739502673.2620282,33.55996799468994,7.667580759088082,1739502673.262031,33.55996799468994,58.67767337091755,1739502673.2620342,33.55996799468994,45.934362656498784,1739502673.2620354,33.55996799468994,8.391958533370458,1739502673.262037,33.55996799468994,2.937970338854154,1739502673.2620385,33.55996799468994,1.181676379604376,1739502673.26204,33.55996799468994,0.6108,1739502673.262041,33.55996799468994,0.9713675336940375,1739502673.2620425,33.55996799468994,0.0,1739502673.262044,33.55996799468994,0.010032729256998607,1739502673.2620454,33.55996799468994,2.6017958611104515,1739502673.2620468,33.55996799468994,0.9613348044370389 +1739502673.281208,33.579967975616455,49.44251743559071,1739502673.2812104,33.579967975616455,7.667580759088082,1739502673.2812133,33.579967975616455,58.67767337091755,1739502673.2812157,33.579967975616455,45.934362656498784,1739502673.2812173,33.579967975616455,8.391958533370458,1739502673.281219,33.579967975616455,2.937970338854154,1739502673.2812204,33.579967975616455,1.181676379604376,1739502673.2812216,33.579967975616455,0.6108,1739502673.2812228,33.579967975616455,0.9713675336940375,1739502673.2812245,33.579967975616455,0.0,1739502673.281226,33.579967975616455,0.010032729256998607,1739502673.2812274,33.579967975616455,2.6017958611104515,1739502673.2812285,33.579967975616455,0.9613348044370389 +1739502673.3055263,33.59996795654297,49.44251743559071,1739502673.305536,33.59996795654297,7.667580759088082,1739502673.3055465,33.59996795654297,58.67767337091755,1739502673.3055563,33.59996795654297,45.934362656498784,1739502673.3055613,33.59996795654297,8.391958533370458,1739502673.3055677,33.59996795654297,2.937970338854154,1739502673.3055735,33.59996795654297,1.181676379604376,1739502673.3055785,33.59996795654297,0.6108,1739502673.305583,33.59996795654297,0.9713675336940375,1739502673.3055887,33.59996795654297,0.0,1739502673.305594,33.59996795654297,0.010032729256998607,1739502673.3055992,33.59996795654297,2.6017958611104515,1739502673.3056045,33.59996795654297,0.9613348044370389 +1739502673.3272,33.609967947006226,49.44251743559071,1739502673.3272073,33.609967947006226,7.667580759088082,1739502673.3272169,33.609967947006226,58.67767337091755,1739502673.3272247,33.609967947006226,45.934362656498784,1739502673.3272283,33.609967947006226,8.391958533370458,1739502673.3272328,33.609967947006226,2.937970338854154,1739502673.3272367,33.609967947006226,1.181676379604376,1739502673.32724,33.609967947006226,0.6108,1739502673.3272433,33.609967947006226,0.9713675336940375,1739502673.3272476,33.609967947006226,0.0,1739502673.3272512,33.609967947006226,0.010032729256998607,1739502673.327255,33.609967947006226,2.6017958611104515,1739502673.3272586,33.609967947006226,0.9613348044370389 +1739502673.3449242,33.639967918395996,49.3510903398005,1739502673.3449278,33.639967918395996,7.7208119802899695,1739502673.3449326,33.639967918395996,58.8471830290107,1739502673.3449373,33.639967918395996,45.776489178972774,1739502673.3449395,33.639967918395996,8.32452092416762,1739502673.344942,33.639967918395996,2.9742829972812634,1739502673.3449445,33.639967918395996,1.2256473760326947,1739502673.3449464,33.639967918395996,0.6108,1739502673.3449485,33.639967918395996,0.9377919381193998,1739502673.3449512,33.639967918395996,0.0,1739502673.344953,33.639967918395996,-0.0403814225586671,1739502673.3449554,33.639967918395996,2.6293975500529982,1739502673.344958,33.639967918395996,0.9624189279062603 +1739502673.3638005,33.65996789932251,49.3510903398005,1739502673.3638039,33.65996789932251,7.7208119802899695,1739502673.3638077,33.65996789932251,58.8471830290107,1739502673.3638113,33.65996789932251,45.776489178972774,1739502673.3638132,33.65996789932251,8.32452092416762,1739502673.3638153,33.65996789932251,2.9742829972812634,1739502673.3638172,33.65996789932251,1.2256473760326947,1739502673.3638191,33.65996789932251,0.6108,1739502673.3638206,33.65996789932251,0.9377919381193998,1739502673.3638227,33.65996789932251,0.0,1739502673.3638244,33.65996789932251,-0.02462698978686051,1739502673.3638263,33.65996789932251,2.6293975500529982,1739502673.363828,33.65996789932251,0.9624189279062603 +1739502673.3827584,33.67996788024902,49.3510903398005,1739502673.382761,33.67996788024902,7.7208119802899695,1739502673.3827639,33.67996788024902,58.8471830290107,1739502673.3827665,33.67996788024902,45.776489178972774,1739502673.382768,33.67996788024902,8.32452092416762,1739502673.3827696,33.67996788024902,2.9742829972812634,1739502673.3827713,33.67996788024902,1.2256473760326947,1739502673.3827724,33.67996788024902,0.6108,1739502673.382774,33.67996788024902,0.9377919381193998,1739502673.3827755,33.67996788024902,0.0,1739502673.3827767,33.67996788024902,-0.02462698978686051,1739502673.3827784,33.67996788024902,2.6293975500529982,1739502673.3827798,33.67996788024902,0.9624189279062603 +1739502673.4170053,33.68996787071228,49.3510903398005,1739502673.4170148,33.68996787071228,7.7208119802899695,1739502673.4170256,33.68996787071228,58.8471830290107,1739502673.417036,33.68996787071228,45.776489178972774,1739502673.4170418,33.68996787071228,8.32452092416762,1739502673.4170487,33.68996787071228,2.9742829972812634,1739502673.4170542,33.68996787071228,1.2256473760326947,1739502673.4170592,33.68996787071228,0.6108,1739502673.417064,33.68996787071228,0.9377919381193998,1739502673.41707,33.68996787071228,0.0,1739502673.4170747,33.68996787071228,-0.02462698978686051,1739502673.4170806,33.68996787071228,2.6293975500529982,1739502673.4170856,33.68996787071228,0.9624189279062603 +1739502673.4352207,33.71996784210205,49.3510903398005,1739502673.4352305,33.71996784210205,7.7208119802899695,1739502673.4352412,33.71996784210205,58.8471830290107,1739502673.4352512,33.71996784210205,45.776489178972774,1739502673.4352562,33.71996784210205,8.32452092416762,1739502673.4352627,33.71996784210205,2.9742829972812634,1739502673.4352682,33.71996784210205,1.2256473760326947,1739502673.4352732,33.71996784210205,0.6108,1739502673.435278,33.71996784210205,0.9377919381193998,1739502673.4352834,33.71996784210205,0.0,1739502673.435289,33.71996784210205,-0.02462698978686051,1739502673.4352942,33.71996784210205,2.6293975500529982,1739502673.4352994,33.71996784210205,0.9624189279062603 +1739502673.4498887,33.739967823028564,49.258251367101124,1739502673.4498968,33.739967823028564,7.771488575810691,1739502673.4499028,33.739967823028564,58.93767931563759,1739502673.4499073,33.739967823028564,45.69885896412622,1739502673.4499106,33.739967823028564,8.287880561954523,1739502673.4499185,33.739967823028564,2.997519163371843,1739502673.4499254,33.739967823028564,1.201201156548607,1739502673.449929,33.739967823028564,0.6108,1739502673.449932,33.739967823028564,0.9563128281447041,1739502673.4499357,33.739967823028564,0.0,1739502673.4499388,33.739967823028564,0.0056956373400582246,1739502673.449942,33.739967823028564,2.656999238995545,1739502673.4499454,33.739967823028564,0.9600930179946444 +1739502673.4685175,33.75996780395508,49.258251367101124,1739502673.4685225,33.75996780395508,7.771488575810691,1739502673.468528,33.75996780395508,58.93767931563759,1739502673.4685338,33.75996780395508,45.69885896412622,1739502673.4685361,33.75996780395508,8.287880561954523,1739502673.4685397,33.75996780395508,2.997519163371843,1739502673.4685426,33.75996780395508,1.201201156548607,1739502673.468545,33.75996780395508,0.6108,1739502673.4685476,33.75996780395508,0.9563128281447041,1739502673.468551,33.75996780395508,0.0,1739502673.4685535,33.75996780395508,-0.0037801898499403297,1739502673.468556,33.75996780395508,2.656999238995545,1739502673.468559,33.75996780395508,0.9600930179946444 +1739502673.4882658,33.77996778488159,49.258251367101124,1739502673.4882693,33.77996778488159,7.771488575810691,1739502673.4882734,33.77996778488159,58.93767931563759,1739502673.488277,33.77996778488159,45.69885896412622,1739502673.4882789,33.77996778488159,8.287880561954523,1739502673.488281,33.77996778488159,2.997519163371843,1739502673.488283,33.77996778488159,1.201201156548607,1739502673.4882846,33.77996778488159,0.6108,1739502673.4882865,33.77996778488159,0.9563128281447041,1739502673.4882884,33.77996778488159,0.0,1739502673.48829,33.77996778488159,-0.0037801898499403297,1739502673.4882925,33.77996778488159,2.656999238995545,1739502673.4882944,33.77996778488159,0.9600930179946444 +1739502673.5075545,33.799967765808105,49.258251367101124,1739502673.5075576,33.799967765808105,7.771488575810691,1739502673.5075614,33.799967765808105,58.93767931563759,1739502673.5075648,33.799967765808105,45.69885896412622,1739502673.5075665,33.799967765808105,8.287880561954523,1739502673.5075684,33.799967765808105,2.997519163371843,1739502673.5075703,33.799967765808105,1.201201156548607,1739502673.507572,33.799967765808105,0.6108,1739502673.5075736,33.799967765808105,0.9563128281447041,1739502673.5075755,33.799967765808105,0.0,1739502673.507577,33.799967765808105,-0.0037801898499403297,1739502673.5075786,33.799967765808105,2.656999238995545,1739502673.50758,33.799967765808105,0.9600930179946444 +1739502673.5275993,33.81996774673462,49.258251367101124,1739502673.5276017,33.81996774673462,7.771488575810691,1739502673.5276048,33.81996774673462,58.93767931563759,1739502673.527608,33.81996774673462,45.69885896412622,1739502673.5276093,33.81996774673462,8.287880561954523,1739502673.5276115,33.81996774673462,2.997519163371843,1739502673.527613,33.81996774673462,1.201201156548607,1739502673.5276144,33.81996774673462,0.6108,1739502673.527616,33.81996774673462,0.9563128281447041,1739502673.5276175,33.81996774673462,0.0,1739502673.5276191,33.81996774673462,-0.0037801898499403297,1739502673.5276208,33.81996774673462,2.656999238995545,1739502673.5276225,33.81996774673462,0.9600930179946444 +1739502673.548177,33.83996772766113,49.16421627874305,1739502673.5481799,33.83996772766113,7.8194977166542134,1739502673.548183,33.83996772766113,59.028459879047354,1739502673.548186,33.83996772766113,45.61822517627131,1739502673.5481877,33.83996772766113,8.248089833985288,1739502673.5481896,33.83996772766113,3.021309453551576,1739502673.5481913,33.83996772766113,1.1800587641498521,1739502673.5481932,33.83996772766113,0.6108,1739502673.5481946,33.83996772766113,0.9726253867151118,1739502673.5481963,33.83996772766113,0.0,1739502673.548198,33.83996772766113,0.020574682704034414,1739502673.5481994,33.83996772766113,2.684600927938092,1739502673.5482013,33.83996772766113,0.9596616066742911 +1739502673.568067,33.85996770858765,49.16421627874305,1739502673.56807,33.85996770858765,7.8194977166542134,1739502673.5680733,33.85996770858765,59.028459879047354,1739502673.5680764,33.85996770858765,45.61822517627131,1739502673.5680778,33.85996770858765,8.248089833985288,1739502673.56808,33.85996770858765,3.021309453551576,1739502673.5680814,33.85996770858765,1.1800587641498521,1739502673.5680833,33.85996770858765,0.6108,1739502673.5680845,33.85996770858765,0.9726253867151118,1739502673.5680864,33.85996770858765,0.0,1739502673.5680878,33.85996770858765,0.01296378004082066,1739502673.5680892,33.85996770858765,2.684600927938092,1739502673.568091,33.85996770858765,0.9596616066742911 +1739502673.5878174,33.87996768951416,49.16421627874305,1739502673.5878205,33.87996768951416,7.8194977166542134,1739502673.587824,33.87996768951416,59.028459879047354,1739502673.5878274,33.87996768951416,45.61822517627131,1739502673.5878294,33.87996768951416,8.248089833985288,1739502673.5878315,33.87996768951416,3.021309453551576,1739502673.5878332,33.87996768951416,1.1800587641498521,1739502673.5878348,33.87996768951416,0.6108,1739502673.5878367,33.87996768951416,0.9726253867151118,1739502673.5878384,33.87996768951416,0.0,1739502673.58784,33.87996768951416,0.01296378004082066,1739502673.5878417,33.87996768951416,2.684600927938092,1739502673.5878437,33.87996768951416,0.9596616066742911 +1739502673.6075637,33.899967670440674,49.16421627874305,1739502673.6075673,33.899967670440674,7.8194977166542134,1739502673.607571,33.899967670440674,59.028459879047354,1739502673.6075742,33.899967670440674,45.61822517627131,1739502673.6075761,33.899967670440674,8.248089833985288,1739502673.607578,33.899967670440674,3.021309453551576,1739502673.6075797,33.899967670440674,1.1800587641498521,1739502673.6075811,33.899967670440674,0.6108,1739502673.6075828,33.899967670440674,0.9726253867151118,1739502673.6075845,33.899967670440674,0.0,1739502673.6075864,33.899967670440674,0.01296378004082066,1739502673.607588,33.899967670440674,2.684600927938092,1739502673.6075897,33.899967670440674,0.9596616066742911 +1739502673.6277254,33.91996765136719,49.16421627874305,1739502673.6277282,33.91996765136719,7.8194977166542134,1739502673.6277318,33.91996765136719,59.028459879047354,1739502673.627735,33.91996765136719,45.61822517627131,1739502673.6277366,33.91996765136719,8.248089833985288,1739502673.6277385,33.91996765136719,3.021309453551576,1739502673.6277401,33.91996765136719,1.1800587641498521,1739502673.6277418,33.91996765136719,0.6108,1739502673.6277432,33.91996765136719,0.9726253867151118,1739502673.627745,33.91996765136719,0.0,1739502673.6277466,33.91996765136719,0.01296378004082066,1739502673.6277483,33.91996765136719,2.684600927938092,1739502673.62775,33.91996765136719,0.9596616066742911 +1739502673.647812,33.9399676322937,49.16421627874305,1739502673.6478152,33.9399676322937,7.8194977166542134,1739502673.6478188,33.9399676322937,59.028459879047354,1739502673.6478221,33.9399676322937,45.61822517627131,1739502673.6478236,33.9399676322937,8.248089833985288,1739502673.6478255,33.9399676322937,3.021309453551576,1739502673.6478271,33.9399676322937,1.1800587641498521,1739502673.6478288,33.9399676322937,0.6108,1739502673.6478302,33.9399676322937,0.9726253867151118,1739502673.6478322,33.9399676322937,0.0,1739502673.6478336,33.9399676322937,0.01296378004082066,1739502673.6478355,33.9399676322937,2.684600927938092,1739502673.647837,33.9399676322937,0.9596616066742911 +1739502673.6677623,33.959967613220215,49.06883458893053,1739502673.6677656,33.959967613220215,7.864920221186871,1739502673.6677685,33.959967613220215,59.11209727173639,1739502673.6677718,33.959967613220215,45.54101588932011,1739502673.6677735,33.959967613220215,8.208469098185846,1739502673.6677754,33.959967613220215,3.0445159501037513,1739502673.667777,33.959967613220215,1.1563269292715181,1739502673.6677785,33.959967613220215,0.6108,1739502673.6677802,33.959967613220215,0.9912675398184108,1739502673.6677818,33.959967613220215,0.0,1739502673.6677835,33.959967613220215,0.03779264717229028,1739502673.6677852,33.959967613220215,2.7122026168806386,1739502673.6677868,33.959967613220215,0.9612339187119187 +1739502673.6878107,33.97996759414673,49.06883458893053,1739502673.687814,33.97996759414673,7.864920221186871,1739502673.6878176,33.97996759414673,59.11209727173639,1739502673.6878211,33.97996759414673,45.54101588932011,1739502673.6878228,33.97996759414673,8.208469098185846,1739502673.6878252,33.97996759414673,3.0445159501037513,1739502673.687827,33.97996759414673,1.1563269292715181,1739502673.687829,33.97996759414673,0.6108,1739502673.6878307,33.97996759414673,0.9912675398184108,1739502673.6878326,33.97996759414673,0.0,1739502673.6878343,33.97996759414673,0.030033621106492103,1739502673.6878362,33.97996759414673,2.7122026168806386,1739502673.6878378,33.97996759414673,0.9612339187119187 +1739502673.7082384,33.99996757507324,49.06883458893053,1739502673.7082422,33.99996757507324,7.864920221186871,1739502673.7082462,33.99996757507324,59.11209727173639,1739502673.70825,33.99996757507324,45.54101588932011,1739502673.7082522,33.99996757507324,8.208469098185846,1739502673.7082548,33.99996757507324,3.0445159501037513,1739502673.7082567,33.99996757507324,1.1563269292715181,1739502673.7082589,33.99996757507324,0.6108,1739502673.7082605,33.99996757507324,0.9912675398184108,1739502673.708263,33.99996757507324,0.0,1739502673.708265,33.99996757507324,0.030033621106492103,1739502673.708267,33.99996757507324,2.7122026168806386,1739502673.7082691,33.99996757507324,0.9612339187119187 +1739502673.729521,34.019967555999756,49.06883458893053,1739502673.7295275,34.019967555999756,7.864920221186871,1739502673.7295349,34.019967555999756,59.11209727173639,1739502673.7295432,34.019967555999756,45.54101588932011,1739502673.729547,34.019967555999756,8.208469098185846,1739502673.7295518,34.019967555999756,3.0445159501037513,1739502673.7295566,34.019967555999756,1.1563269292715181,1739502673.7295609,34.019967555999756,0.6108,1739502673.7295647,34.019967555999756,0.9912675398184108,1739502673.7295694,34.019967555999756,0.0,1739502673.7295737,34.019967555999756,0.030033621106492103,1739502673.7295783,34.019967555999756,2.7122026168806386,1739502673.7295825,34.019967555999756,0.9612339187119187 +1739502673.7490566,34.03996753692627,49.06883458893053,1739502673.7490609,34.03996753692627,7.864920221186871,1739502673.7490656,34.03996753692627,59.11209727173639,1739502673.7490704,34.03996753692627,45.54101588932011,1739502673.7490726,34.03996753692627,8.208469098185846,1739502673.7490754,34.03996753692627,3.0445159501037513,1739502673.7490776,34.03996753692627,1.1563269292715181,1739502673.7490797,34.03996753692627,0.6108,1739502673.749082,34.03996753692627,0.9912675398184108,1739502673.749085,34.03996753692627,0.0,1739502673.7490869,34.03996753692627,0.030033621106492103,1739502673.7490895,34.03996753692627,2.7122026168806386,1739502673.7490919,34.03996753692627,0.9612339187119187 +1739502673.769018,34.05996751785278,48.972008473061955,1739502673.769022,34.05996751785278,7.907793149671118,1739502673.7690268,34.05996751785278,59.113946600089676,1739502673.7690315,34.05996751785278,45.533621972400155,1739502673.7690337,34.05996751785278,8.204480274584293,1739502673.7690365,34.05996751785278,3.055519119185671,1739502673.7690392,34.05996751785278,1.0715723757627358,1739502673.7690418,34.05996751785278,0.6108,1739502673.7690437,34.05996751785278,1.0608100679038035,1739502673.7690465,34.05996751785278,0.0,1739502673.769049,34.05996751785278,0.1264213961691917,1739502673.769051,34.05996751785278,2.7398043058231853,1739502673.7690537,34.05996751785278,0.9645098711907027 +1739502673.7888253,34.0799674987793,48.972008473061955,1739502673.7888293,34.0799674987793,7.907793149671118,1739502673.7888343,34.0799674987793,59.113946600089676,1739502673.7888389,34.0799674987793,45.533621972400155,1739502673.7888415,34.0799674987793,8.204480274584293,1739502673.788844,34.0799674987793,3.055519119185671,1739502673.7888463,34.0799674987793,1.0715723757627358,1739502673.7888486,34.0799674987793,0.6108,1739502673.788851,34.0799674987793,1.0608100679038035,1739502673.7888534,34.0799674987793,0.0,1739502673.7888556,34.0799674987793,0.09630019671310075,1739502673.788858,34.0799674987793,2.7398043058231853,1739502673.7888603,34.0799674987793,0.9645098711907027 +1739502673.808032,34.09996747970581,48.972008473061955,1739502673.8080356,34.09996747970581,7.907793149671118,1739502673.8080397,34.09996747970581,59.113946600089676,1739502673.8080435,34.09996747970581,45.533621972400155,1739502673.8080454,34.09996747970581,8.204480274584293,1739502673.8080478,34.09996747970581,3.055519119185671,1739502673.8080497,34.09996747970581,1.0715723757627358,1739502673.8080513,34.09996747970581,0.6108,1739502673.8080533,34.09996747970581,1.0608100679038035,1739502673.8080556,34.09996747970581,0.0,1739502673.8080573,34.09996747970581,0.09630019671310075,1739502673.8080595,34.09996747970581,2.7398043058231853,1739502673.8080614,34.09996747970581,0.9645098711907027 +1739502673.8278112,34.119967460632324,48.972008473061955,1739502673.8278143,34.119967460632324,7.907793149671118,1739502673.827818,34.119967460632324,59.113946600089676,1739502673.8278213,34.119967460632324,45.533621972400155,1739502673.8278232,34.119967460632324,8.204480274584293,1739502673.8278253,34.119967460632324,3.055519119185671,1739502673.827827,34.119967460632324,1.0715723757627358,1739502673.8278286,34.119967460632324,0.6108,1739502673.8278303,34.119967460632324,1.0608100679038035,1739502673.8278322,34.119967460632324,0.0,1739502673.8278341,34.119967460632324,0.09630019671310075,1739502673.8278358,34.119967460632324,2.7398043058231853,1739502673.8278375,34.119967460632324,0.9645098711907027 +1739502673.8474288,34.13996744155884,48.972008473061955,1739502673.8474321,34.13996744155884,7.907793149671118,1739502673.8474355,34.13996744155884,59.113946600089676,1739502673.8474383,34.13996744155884,45.533621972400155,1739502673.8474398,34.13996744155884,8.204480274584293,1739502673.8474417,34.13996744155884,3.055519119185671,1739502673.847443,34.13996744155884,1.0715723757627358,1739502673.8474445,34.13996744155884,0.6108,1739502673.847446,34.13996744155884,1.0608100679038035,1739502673.8474479,34.13996744155884,0.0,1739502673.847449,34.13996744155884,0.09630019671310075,1739502673.8474507,34.13996744155884,2.7398043058231853,1739502673.8474522,34.13996744155884,0.9645098711907027 +1739502673.8674314,34.15996742248535,48.972008473061955,1739502673.8674345,34.15996742248535,7.907793149671118,1739502673.8674376,34.15996742248535,59.113946600089676,1739502673.8674405,34.15996742248535,45.533621972400155,1739502673.867442,34.15996742248535,8.204480274584293,1739502673.8674438,34.15996742248535,3.055519119185671,1739502673.8674452,34.15996742248535,1.0715723757627358,1739502673.8674464,34.15996742248535,0.6108,1739502673.8674479,34.15996742248535,1.0608100679038035,1739502673.8674495,34.15996742248535,0.0,1739502673.867451,34.15996742248535,0.09630019671310075,1739502673.8674524,34.15996742248535,2.7398043058231853,1739502673.867454,34.15996742248535,0.9645098711907027 +1739502673.8877072,34.179967403411865,48.873308955288536,1739502673.8877096,34.179967403411865,7.948273680785173,1739502673.887713,34.179967403411865,59.376620922421154,1739502673.8877158,34.179967403411865,45.28670483427115,1739502673.8877175,34.179967403411865,8.062288622117984,1739502673.8877192,34.179967403411865,3.1098142484672584,1739502673.8877206,34.179967403411865,1.2048340113095657,1739502673.8877223,34.179967403411865,0.6108,1739502673.8877237,34.179967403411865,0.953537546487671,1739502673.8877254,34.179967403411865,0.0,1739502673.8877268,34.179967403411865,-0.07595781492392806,1739502673.8877285,34.179967403411865,2.767405994765732,1739502673.8877304,34.179967403411865,0.9756646974808939 +1739502673.9074302,34.19996738433838,48.873308955288536,1739502673.907433,34.19996738433838,7.948273680785173,1739502673.9074361,34.19996738433838,59.376620922421154,1739502673.9074388,34.19996738433838,45.28670483427115,1739502673.9074402,34.19996738433838,8.062288622117984,1739502673.907442,34.19996738433838,3.1098142484672584,1739502673.9074435,34.19996738433838,1.2048340113095657,1739502673.907445,34.19996738433838,0.6108,1739502673.9074469,34.19996738433838,0.953537546487671,1739502673.9074485,34.19996738433838,0.0,1739502673.90745,34.19996738433838,-0.022127150993222933,1739502673.9074516,34.19996738433838,2.767405994765732,1739502673.9074533,34.19996738433838,0.9756646974808939 +1739502673.9274716,34.21996736526489,48.873308955288536,1739502673.9274743,34.21996736526489,7.948273680785173,1739502673.9274778,34.21996736526489,59.376620922421154,1739502673.927481,34.21996736526489,45.28670483427115,1739502673.9274824,34.21996736526489,8.062288622117984,1739502673.9274843,34.21996736526489,3.1098142484672584,1739502673.9274857,34.21996736526489,1.2048340113095657,1739502673.9274871,34.21996736526489,0.6108,1739502673.9274886,34.21996736526489,0.953537546487671,1739502673.9274902,34.21996736526489,0.0,1739502673.9274917,34.21996736526489,-0.022127150993222933,1739502673.927493,34.21996736526489,2.767405994765732,1739502673.9274948,34.21996736526489,0.9756646974808939 +1739502673.947413,34.239967346191406,48.873308955288536,1739502673.9474158,34.239967346191406,7.948273680785173,1739502673.947419,34.239967346191406,59.376620922421154,1739502673.947422,34.239967346191406,45.28670483427115,1739502673.9474232,34.239967346191406,8.062288622117984,1739502673.9474251,34.239967346191406,3.1098142484672584,1739502673.9474266,34.239967346191406,1.2048340113095657,1739502673.9474277,34.239967346191406,0.6108,1739502673.9474294,34.239967346191406,0.953537546487671,1739502673.9474308,34.239967346191406,0.0,1739502673.9474325,34.239967346191406,-0.022127150993222933,1739502673.9474342,34.239967346191406,2.767405994765732,1739502673.9474356,34.239967346191406,0.9756646974808939 +1739502673.9674525,34.25996732711792,48.873308955288536,1739502673.967455,34.25996732711792,7.948273680785173,1739502673.967458,34.25996732711792,59.376620922421154,1739502673.9674609,34.25996732711792,45.28670483427115,1739502673.9674625,34.25996732711792,8.062288622117984,1739502673.9674647,34.25996732711792,3.1098142484672584,1739502673.9674664,34.25996732711792,1.2048340113095657,1739502673.9674675,34.25996732711792,0.6108,1739502673.967469,34.25996732711792,0.953537546487671,1739502673.967471,34.25996732711792,0.0,1739502673.967472,34.25996732711792,-0.022127150993222933,1739502673.9674735,34.25996732711792,2.767405994765732,1739502673.967475,34.25996732711792,0.9756646974808939 +1739502673.9877105,34.279967308044434,48.77302042804887,1739502673.9877133,34.279967308044434,7.986211307105339,1739502673.9877164,34.279967308044434,59.54467062647438,1739502673.9877195,34.279967308044434,45.14922949016388,1739502673.9877207,34.279967308044434,7.974048582611208,1739502673.9877224,34.279967308044434,-3.138236312390359,1739502673.9877243,34.279967308044434,1.2423971805682101,1739502673.9877255,34.279967308044434,0.6108,1739502673.987727,34.279967308044434,0.9253094909865531,1739502673.9877286,34.279967308044434,0.0,1739502673.98773,34.279967308044434,-0.059800790711290165,1739502673.9877317,34.279967308044434,2.795007683708279,1739502673.9877336,34.279967308044434,0.9733372615669538 +1739502674.007467,34.29996728897095,48.77302042804887,1739502674.0074697,34.29996728897095,7.986211307105339,1739502674.0074732,34.29996728897095,59.54467062647438,1739502674.0074759,34.29996728897095,45.14922949016388,1739502674.0074775,34.29996728897095,7.974048582611208,1739502674.0074792,34.29996728897095,-3.138236312390359,1739502674.0074809,34.29996728897095,1.2423971805682101,1739502674.007482,34.29996728897095,0.6108,1739502674.0074835,34.29996728897095,0.9253094909865531,1739502674.0074852,34.29996728897095,0.0,1739502674.0074866,34.29996728897095,-0.04802777058040064,1739502674.007488,34.29996728897095,2.795007683708279,1739502674.0074894,34.29996728897095,0.9733372615669538 +1739502674.0274432,34.31996726989746,48.77302042804887,1739502674.0274458,34.31996726989746,7.986211307105339,1739502674.0274491,34.31996726989746,59.54467062647438,1739502674.0274522,34.31996726989746,45.14922949016388,1739502674.0274537,34.31996726989746,7.974048582611208,1739502674.0274553,34.31996726989746,-3.138236312390359,1739502674.0274568,34.31996726989746,1.2423971805682101,1739502674.0274582,34.31996726989746,0.6108,1739502674.0274596,34.31996726989746,0.9253094909865531,1739502674.0274615,34.31996726989746,0.0,1739502674.0274632,34.31996726989746,-0.04802777058040064,1739502674.0274646,34.31996726989746,2.795007683708279,1739502674.0274663,34.31996726989746,0.9733372615669538 +1739502674.0475159,34.339967250823975,48.77302042804887,1739502674.0475187,34.339967250823975,7.986211307105339,1739502674.0475225,34.339967250823975,59.54467062647438,1739502674.047526,34.339967250823975,45.14922949016388,1739502674.0475273,34.339967250823975,7.974048582611208,1739502674.0475295,34.339967250823975,-3.138236312390359,1739502674.047531,34.339967250823975,1.2423971805682101,1739502674.0475323,34.339967250823975,0.6108,1739502674.0475338,34.339967250823975,0.9253094909865531,1739502674.0475357,34.339967250823975,0.0,1739502674.0475368,34.339967250823975,-0.04802777058040064,1739502674.0475385,34.339967250823975,2.795007683708279,1739502674.0475402,34.339967250823975,0.9733372615669538 +1739502674.067664,34.35996723175049,48.77302042804887,1739502674.0676668,34.35996723175049,7.986211307105339,1739502674.0676703,34.35996723175049,59.54467062647438,1739502674.0676732,34.35996723175049,45.14922949016388,1739502674.0676746,34.35996723175049,7.974048582611208,1739502674.0676763,34.35996723175049,-3.138236312390359,1739502674.0676777,34.35996723175049,1.2423971805682101,1739502674.0676792,34.35996723175049,0.6108,1739502674.0676806,34.35996723175049,0.9253094909865531,1739502674.0676823,34.35996723175049,0.0,1739502674.0676837,34.35996723175049,-0.04802777058040064,1739502674.0676851,34.35996723175049,2.795007683708279,1739502674.0676868,34.35996723175049,0.9733372615669538 +1739502674.087407,34.379967212677,48.77302042804887,1739502674.0874097,34.379967212677,7.986211307105339,1739502674.0874128,34.379967212677,59.54467062647438,1739502674.0874157,34.379967212677,45.14922949016388,1739502674.0874174,34.379967212677,7.974048582611208,1739502674.087419,34.379967212677,-3.138236312390359,1739502674.0874207,34.379967212677,1.2423971805682101,1739502674.0874221,34.379967212677,0.6108,1739502674.0874238,34.379967212677,0.9253094909865531,1739502674.0874252,34.379967212677,0.0,1739502674.087427,34.379967212677,-0.04802777058040064,1739502674.0874283,34.379967212677,2.795007683708279,1739502674.08743,34.379967212677,0.9733372615669538 +1739502674.1077273,34.399967193603516,48.67214509170796,1739502674.1077302,34.399967193603516,8.02122090225478,1739502674.1077335,34.399967193603516,59.63138109725967,1739502674.1077363,34.399967193603516,45.0868051068259,1739502674.1077378,34.399967193603516,7.93120942368796,1739502674.1077397,34.399967193603516,-3.116492502637753,1739502674.107741,34.399967193603516,1.2098380804601072,1739502674.1077425,34.399967193603516,0.6108,1739502674.1077437,34.399967193603516,0.9497279227674427,1739502674.1077456,34.399967193603516,0.0,1739502674.1077468,34.399967193603516,-0.004511981446326571,1739502674.1077483,34.399967193603516,2.8226093726508257,1739502674.10775,34.399967193603516,0.9678385972341653 +1739502674.1274152,34.41996717453003,48.67214509170796,1739502674.127418,34.41996717453003,8.02122090225478,1739502674.1274211,34.41996717453003,59.63138109725967,1739502674.1274242,34.41996717453003,45.0868051068259,1739502674.127426,34.41996717453003,7.93120942368796,1739502674.1274276,34.41996717453003,-3.116492502637753,1739502674.127429,34.41996717453003,1.2098380804601072,1739502674.1274307,34.41996717453003,0.6108,1739502674.1274319,34.41996717453003,0.9497279227674427,1739502674.1274338,34.41996717453003,0.0,1739502674.127435,34.41996717453003,-0.018110674466722654,1739502674.1274369,34.41996717453003,2.8226093726508257,1739502674.1274383,34.41996717453003,0.9678385972341653 +1739502674.1476388,34.43996715545654,48.67214509170796,1739502674.1476417,34.43996715545654,8.02122090225478,1739502674.147645,34.43996715545654,59.63138109725967,1739502674.147648,34.43996715545654,45.0868051068259,1739502674.1476495,34.43996715545654,7.93120942368796,1739502674.1476514,34.43996715545654,-3.116492502637753,1739502674.1476529,34.43996715545654,1.2098380804601072,1739502674.147654,34.43996715545654,0.6108,1739502674.1476557,34.43996715545654,0.9497279227674427,1739502674.1476572,34.43996715545654,0.0,1739502674.1476588,34.43996715545654,-0.018110674466722654,1739502674.1476603,34.43996715545654,2.8226093726508257,1739502674.1476622,34.43996715545654,0.9678385972341653 +1739502674.1674552,34.45996713638306,48.67214509170796,1739502674.167458,34.45996713638306,8.02122090225478,1739502674.1674614,34.45996713638306,59.63138109725967,1739502674.1674645,34.45996713638306,45.0868051068259,1739502674.167466,34.45996713638306,7.93120942368796,1739502674.1674678,34.45996713638306,-3.116492502637753,1739502674.1674693,34.45996713638306,1.2098380804601072,1739502674.1674707,34.45996713638306,0.6108,1739502674.167472,34.45996713638306,0.9497279227674427,1739502674.167474,34.45996713638306,0.0,1739502674.1674752,34.45996713638306,-0.018110674466722654,1739502674.1674767,34.45996713638306,2.8226093726508257,1739502674.1674783,34.45996713638306,0.9678385972341653 +1739502674.1874762,34.47996711730957,48.67214509170796,1739502674.1874788,34.47996711730957,8.02122090225478,1739502674.187482,34.47996711730957,59.63138109725967,1739502674.187485,34.47996711730957,45.0868051068259,1739502674.1874866,34.47996711730957,7.93120942368796,1739502674.1874886,34.47996711730957,-3.116492502637753,1739502674.18749,34.47996711730957,1.2098380804601072,1739502674.1874917,34.47996711730957,0.6108,1739502674.187493,34.47996711730957,0.9497279227674427,1739502674.187495,34.47996711730957,0.0,1739502674.1874964,34.47996711730957,-0.018110674466722654,1739502674.187498,34.47996711730957,2.8226093726508257,1739502674.1874995,34.47996711730957,0.9678385972341653 +1739502674.2074895,34.499967098236084,48.57074664210171,1739502674.2074924,34.499967098236084,8.05330420610513,1739502674.2074957,34.499967098236084,59.79509464196052,1739502674.2074986,34.499967098236084,44.95800420270389,1739502674.2075,34.499967098236084,7.836821429362095,1739502674.2075021,34.499967098236084,-3.081742212338896,1739502674.2075036,34.499967098236084,1.2452112402950306,1739502674.207505,34.499967098236084,0.6108,1739502674.2075064,34.499967098236084,0.9232287330774159,1739502674.2075083,34.499967098236084,0.0,1739502674.2075098,34.499967098236084,-0.053733915447561766,1739502674.2075112,34.499967098236084,2.8502110615933725,1739502674.2075129,34.499967098236084,0.9658303784195804 +1739502674.2278042,34.5199670791626,48.57074664210171,1739502674.227807,34.5199670791626,8.05330420610513,1739502674.2278101,34.5199670791626,59.79509464196052,1739502674.227813,34.5199670791626,44.95800420270389,1739502674.2278144,34.5199670791626,7.836821429362095,1739502674.227816,34.5199670791626,-3.081742212338896,1739502674.2278178,34.5199670791626,1.2452112402950306,1739502674.2278194,34.5199670791626,0.6108,1739502674.2278209,34.5199670791626,0.9232287330774159,1739502674.2278225,34.5199670791626,0.0,1739502674.2278242,34.5199670791626,-0.042601645342164485,1739502674.2278256,34.5199670791626,2.8502110615933725,1739502674.2278273,34.5199670791626,0.9658303784195804 +1739502674.2474713,34.53996706008911,48.57074664210171,1739502674.247474,34.53996706008911,8.05330420610513,1739502674.247477,34.53996706008911,59.79509464196052,1739502674.2474802,34.53996706008911,44.95800420270389,1739502674.2474813,34.53996706008911,7.836821429362095,1739502674.2474835,34.53996706008911,-3.081742212338896,1739502674.2474847,34.53996706008911,1.2452112402950306,1739502674.247486,34.53996706008911,0.6108,1739502674.2474878,34.53996706008911,0.9232287330774159,1739502674.2474892,34.53996706008911,0.0,1739502674.247491,34.53996706008911,-0.042601645342164485,1739502674.2474923,34.53996706008911,2.8502110615933725,1739502674.2474937,34.53996706008911,0.9658303784195804 +1739502674.2674317,34.559967041015625,48.57074664210171,1739502674.2674344,34.559967041015625,8.05330420610513,1739502674.2674375,34.559967041015625,59.79509464196052,1739502674.2674403,34.559967041015625,44.95800420270389,1739502674.267442,34.559967041015625,7.836821429362095,1739502674.2674437,34.559967041015625,-3.081742212338896,1739502674.2674453,34.559967041015625,1.2452112402950306,1739502674.2674468,34.559967041015625,0.6108,1739502674.267448,34.559967041015625,0.9232287330774159,1739502674.2674496,34.559967041015625,0.0,1739502674.267451,34.559967041015625,-0.042601645342164485,1739502674.2674527,34.559967041015625,2.8502110615933725,1739502674.2674541,34.559967041015625,0.9658303784195804 +1739502674.287479,34.57996702194214,48.57074664210171,1739502674.2874818,34.57996702194214,8.05330420610513,1739502674.2874851,34.57996702194214,59.79509464196052,1739502674.287488,34.57996702194214,44.95800420270389,1739502674.2874897,34.57996702194214,7.836821429362095,1739502674.2874913,34.57996702194214,-3.081742212338896,1739502674.2874925,34.57996702194214,1.2452112402950306,1739502674.2874942,34.57996702194214,0.6108,1739502674.2874956,34.57996702194214,0.9232287330774159,1739502674.2874973,34.57996702194214,0.0,1739502674.2874987,34.57996702194214,-0.042601645342164485,1739502674.2875004,34.57996702194214,2.8502110615933725,1739502674.2875018,34.57996702194214,0.9658303784195804 +1739502674.3075156,34.59996700286865,48.57074664210171,1739502674.3075185,34.59996700286865,8.05330420610513,1739502674.307522,34.59996700286865,59.79509464196052,1739502674.3075252,34.59996700286865,44.95800420270389,1739502674.3075264,34.59996700286865,7.836821429362095,1739502674.3075283,34.59996700286865,-3.081742212338896,1739502674.3075297,34.59996700286865,1.2452112402950306,1739502674.3075314,34.59996700286865,0.6108,1739502674.3075325,34.59996700286865,0.9232287330774159,1739502674.307534,34.59996700286865,0.0,1739502674.3075356,34.59996700286865,-0.042601645342164485,1739502674.307537,34.59996700286865,2.8502110615933725,1739502674.3075387,34.59996700286865,0.9658303784195804 +1739502674.3279204,34.619966983795166,48.468857305370676,1739502674.3279233,34.619966983795166,8.082475752761193,1739502674.327927,34.619966983795166,59.88063087380595,1739502674.3279302,34.619966983795166,44.89808679674463,1739502674.3279316,34.619966983795166,7.790469437395704,1739502674.3279338,34.619966983795166,-3.0599973821769377,1739502674.3279352,34.619966983795166,1.212918797791644,1739502674.3279366,34.619966983795166,0.6108,1739502674.3279383,34.619966983795166,0.9473901301645239,1739502674.3279405,34.619966983795166,0.0,1739502674.327942,34.619966983795166,-0.00034336089574516643,1739502674.3279436,34.619966983795166,2.8778127505359192,1739502674.3279452,34.619966983795166,0.9609392136081215 +1739502674.3476558,34.63996696472168,48.468857305370676,1739502674.3476586,34.63996696472168,8.082475752761193,1739502674.347662,34.63996696472168,59.88063087380595,1739502674.347665,34.63996696472168,44.89808679674463,1739502674.347667,34.63996696472168,7.790469437395704,1739502674.347669,34.63996696472168,-3.0599973821769377,1739502674.3476706,34.63996696472168,1.212918797791644,1739502674.347672,34.63996696472168,0.6108,1739502674.3476737,34.63996696472168,0.9473901301645239,1739502674.3476756,34.63996696472168,0.0,1739502674.3476772,34.63996696472168,-0.01354908344359762,1739502674.347679,34.63996696472168,2.8778127505359192,1739502674.3476806,34.63996696472168,0.9609392136081215 +1739502674.3676543,34.65996694564819,48.468857305370676,1739502674.3676574,34.65996694564819,8.082475752761193,1739502674.3676608,34.65996694564819,59.88063087380595,1739502674.3676639,34.65996694564819,44.89808679674463,1739502674.3676653,34.65996694564819,7.790469437395704,1739502674.3676674,34.65996694564819,-3.0599973821769377,1739502674.3676693,34.65996694564819,1.212918797791644,1739502674.367671,34.65996694564819,0.6108,1739502674.3676727,34.65996694564819,0.9473901301645239,1739502674.3676744,34.65996694564819,0.0,1739502674.367676,34.65996694564819,-0.01354908344359762,1739502674.3676777,34.65996694564819,2.8778127505359192,1739502674.3676796,34.65996694564819,0.9609392136081215 +1739502674.387977,34.67996692657471,48.468857305370676,1739502674.38798,34.67996692657471,8.082475752761193,1739502674.3879833,34.67996692657471,59.88063087380595,1739502674.3879867,34.67996692657471,44.89808679674463,1739502674.3879883,34.67996692657471,7.790469437395704,1739502674.38799,34.67996692657471,-3.0599973821769377,1739502674.387992,34.67996692657471,1.212918797791644,1739502674.3879933,34.67996692657471,0.6108,1739502674.3879948,34.67996692657471,0.9473901301645239,1739502674.3879967,34.67996692657471,0.0,1739502674.387998,34.67996692657471,-0.01354908344359762,1739502674.3879998,34.67996692657471,2.8778127505359192,1739502674.3880014,34.67996692657471,0.9609392136081215 +1739502674.4077404,34.69996690750122,48.468857305370676,1739502674.4077437,34.69996690750122,8.082475752761193,1739502674.407747,34.69996690750122,59.88063087380595,1739502674.4077501,34.69996690750122,44.89808679674463,1739502674.4077518,34.69996690750122,7.790469437395704,1739502674.4077537,34.69996690750122,-3.0599973821769377,1739502674.4077554,34.69996690750122,1.212918797791644,1739502674.407757,34.69996690750122,0.6108,1739502674.4077585,34.69996690750122,0.9473901301645239,1739502674.4077604,34.69996690750122,0.0,1739502674.4077618,34.69996690750122,-0.01354908344359762,1739502674.4077637,34.69996690750122,2.8778127505359192,1739502674.4077654,34.69996690750122,0.9609392136081215 +1739502674.427767,34.719966888427734,48.366553765706286,1739502674.4277701,34.719966888427734,8.108732966422554,1739502674.4277735,34.719966888427734,59.985002199791175,1739502674.4277766,34.719966888427734,44.81916094225737,1739502674.4277782,34.719966888427734,7.726883280306881,1739502674.4277804,34.719966888427734,-3.0343631869860843,1739502674.4277818,34.719966888427734,1.2012989531218177,1739502674.4277835,34.719966888427734,0.6108,1739502674.427785,34.719966888427734,0.9562380117774478,1739502674.427787,34.719966888427734,0.0,1739502674.4277885,34.719966888427734,0.00151379491705115,1739502674.4277902,34.719966888427734,2.905414439478466,1739502674.4277916,34.719966888427734,0.9594313694343491 +1739502674.4477599,34.73996686935425,48.366553765706286,1739502674.447763,34.73996686935425,8.108732966422554,1739502674.447766,34.73996686935425,59.985002199791175,1739502674.4477694,34.73996686935425,44.81916094225737,1739502674.4477708,34.73996686935425,7.726883280306881,1739502674.447773,34.73996686935425,-3.0343631869860843,1739502674.4477744,34.73996686935425,1.2012989531218177,1739502674.4477763,34.73996686935425,0.6108,1739502674.4477777,34.73996686935425,0.9562380117774478,1739502674.44778,34.73996686935425,0.0,1739502674.4477813,34.73996686935425,-0.003193357656901319,1739502674.4477832,34.73996686935425,2.905414439478466,1739502674.4477847,34.73996686935425,0.9594313694343491 +1739502674.4680116,34.75996685028076,48.366553765706286,1739502674.4680142,34.75996685028076,8.108732966422554,1739502674.4680178,34.75996685028076,59.985002199791175,1739502674.4680212,34.75996685028076,44.81916094225737,1739502674.4680228,34.75996685028076,7.726883280306881,1739502674.4680247,34.75996685028076,-3.0343631869860843,1739502674.4680264,34.75996685028076,1.2012989531218177,1739502674.4680278,34.75996685028076,0.6108,1739502674.4680295,34.75996685028076,0.9562380117774478,1739502674.4680312,34.75996685028076,0.0,1739502674.4680326,34.75996685028076,-0.003193357656901319,1739502674.4680343,34.75996685028076,2.905414439478466,1739502674.4680362,34.75996685028076,0.9594313694343491 +1739502674.487731,34.779966831207275,48.366553765706286,1739502674.4877343,34.779966831207275,8.108732966422554,1739502674.487738,34.779966831207275,59.985002199791175,1739502674.4877412,34.779966831207275,44.81916094225737,1739502674.4877427,34.779966831207275,7.726883280306881,1739502674.4877448,34.779966831207275,-3.0343631869860843,1739502674.4877462,34.779966831207275,1.2012989531218177,1739502674.487748,34.779966831207275,0.6108,1739502674.4877496,34.779966831207275,0.9562380117774478,1739502674.4877515,34.779966831207275,0.0,1739502674.487753,34.779966831207275,-0.003193357656901319,1739502674.4877553,34.779966831207275,2.905414439478466,1739502674.4877567,34.779966831207275,0.9594313694343491 +1739502674.5079203,34.79996681213379,48.366553765706286,1739502674.5079234,34.79996681213379,8.108732966422554,1739502674.507927,34.79996681213379,59.985002199791175,1739502674.5079303,34.79996681213379,44.81916094225737,1739502674.507932,34.79996681213379,7.726883280306881,1739502674.5079339,34.79996681213379,-3.0343631869860843,1739502674.5079355,34.79996681213379,1.2012989531218177,1739502674.507937,34.79996681213379,0.6108,1739502674.5079386,34.79996681213379,0.9562380117774478,1739502674.5079405,34.79996681213379,0.0,1739502674.5079422,34.79996681213379,-0.003193357656901319,1739502674.5079439,34.79996681213379,2.905414439478466,1739502674.5079455,34.79996681213379,0.9594313694343491 +1739502674.5277774,34.8199667930603,48.366553765706286,1739502674.5277805,34.8199667930603,8.108732966422554,1739502674.5277839,34.8199667930603,59.985002199791175,1739502674.5277874,34.8199667930603,44.81916094225737,1739502674.527789,34.8199667930603,7.726883280306881,1739502674.5277913,34.8199667930603,-3.0343631869860843,1739502674.527793,34.8199667930603,1.2012989531218177,1739502674.5277946,34.8199667930603,0.6108,1739502674.5277965,34.8199667930603,0.9562380117774478,1739502674.5277982,34.8199667930603,0.0,1739502674.5277998,34.8199667930603,-0.003193357656901319,1739502674.5278015,34.8199667930603,2.905414439478466,1739502674.5278032,34.8199667930603,0.9594313694343491 +1739502674.5531566,34.839966773986816,48.263656016463656,1739502674.5531647,34.839966773986816,8.132135707689947,1739502674.553175,34.839966773986816,60.12773542068641,1739502674.553185,34.839966773986816,44.71181593902724,1739502674.55319,34.839966773986816,7.633637322073743,1739502674.5531962,34.839966773986816,-3.002154110909515,1739502674.5532014,34.839966773986816,1.22316485928183,1739502674.5532062,34.839966773986816,0.6108,1739502674.5532112,34.839966773986816,0.9396562561430767,1739502674.5532165,34.839966773986816,0.0,1739502674.5532215,34.839966773986816,-0.026939146594976503,1739502674.5532265,34.839966773986816,2.933016128421013,1739502674.5532317,34.839966773986816,0.9591748388296039 +1739502674.5729864,34.85996675491333,48.263656016463656,1739502674.5729961,34.85996675491333,8.132135707689947,1739502674.5730066,34.85996675491333,60.12773542068641,1739502674.5730171,34.85996675491333,44.71181593902724,1739502674.5730221,34.85996675491333,7.633637322073743,1739502674.5730283,34.85996675491333,-3.002154110909515,1739502674.5730336,34.85996675491333,1.22316485928183,1739502674.5730383,34.85996675491333,0.6108,1739502674.5730429,34.85996675491333,0.9396562561430767,1739502674.5730488,34.85996675491333,0.0,1739502674.5730536,34.85996675491333,-0.019518582686527175,1739502674.573059,34.85996675491333,2.933016128421013,1739502674.573064,34.85996675491333,0.9591748388296039 +1739502674.5954545,34.86996674537659,48.263656016463656,1739502674.5954635,34.86996674537659,8.132135707689947,1739502674.5954745,34.86996674537659,60.12773542068641,1739502674.5954847,34.86996674537659,44.71181593902724,1739502674.5954893,34.86996674537659,7.633637322073743,1739502674.5954955,34.86996674537659,-3.002154110909515,1739502674.5955002,34.86996674537659,1.22316485928183,1739502674.5955052,34.86996674537659,0.6108,1739502674.5955098,34.86996674537659,0.9396562561430767,1739502674.5955155,34.86996674537659,0.0,1739502674.5955205,34.86996674537659,-0.019518582686527175,1739502674.5955257,34.86996674537659,2.933016128421013,1739502674.5955307,34.86996674537659,0.9591748388296039 +1739502674.6120071,34.89996671676636,48.263656016463656,1739502674.6120136,34.89996671676636,8.132135707689947,1739502674.612021,34.89996671676636,60.12773542068641,1739502674.612028,34.89996671676636,44.71181593902724,1739502674.6120312,34.89996671676636,7.633637322073743,1739502674.6120355,34.89996671676636,-3.002154110909515,1739502674.6120389,34.89996671676636,1.22316485928183,1739502674.6120422,34.89996671676636,0.6108,1739502674.6120455,34.89996671676636,0.9396562561430767,1739502674.6120496,34.89996671676636,0.0,1739502674.612053,34.89996671676636,-0.019518582686527175,1739502674.6120567,34.89996671676636,2.933016128421013,1739502674.6120608,34.89996671676636,0.9591748388296039 +1739502674.6415868,34.91996669769287,48.263656016463656,1739502674.6415915,34.91996669769287,8.132135707689947,1739502674.6415977,34.91996669769287,60.12773542068641,1739502674.6416032,34.91996669769287,44.71181593902724,1739502674.6416059,34.91996669769287,7.633637322073743,1739502674.6416097,34.91996669769287,-3.002154110909515,1739502674.6416123,34.91996669769287,1.22316485928183,1739502674.641615,34.91996669769287,0.6108,1739502674.6416173,34.91996669769287,0.9396562561430767,1739502674.6416204,34.91996669769287,0.0,1739502674.641623,34.91996669769287,-0.019518582686527175,1739502674.641626,34.91996669769287,2.933016128421013,1739502674.6416285,34.91996669769287,0.9591748388296039 +1739502674.661347,34.94996666908264,48.16027235060678,1739502674.6613505,34.94996666908264,8.152666256340236,1739502674.6613548,34.94996666908264,60.21167224869451,1739502674.6613584,34.94996666908264,44.65253598207883,1739502674.6613605,34.94996666908264,7.5804722851490975,1739502674.6613626,34.94996666908264,-2.979893422651204,1739502674.6613646,34.94996666908264,1.1942017695872635,1739502674.6613665,34.94996666908264,0.6108,1739502674.6613681,34.94996666908264,0.961682731358262,1739502674.6613703,34.94996666908264,0.0,1739502674.6613722,34.94996666908264,0.015610660275922214,1739502674.661374,34.94996666908264,2.9606178173635596,1739502674.6613762,34.94996666908264,0.9570499667057745 +1739502674.6808217,34.969966650009155,48.16027235060678,1739502674.680825,34.969966650009155,8.152666256340236,1739502674.6808293,34.969966650009155,60.21167224869451,1739502674.680833,34.969966650009155,44.65253598207883,1739502674.6808348,34.969966650009155,7.5804722851490975,1739502674.6808372,34.969966650009155,-2.979893422651204,1739502674.6808388,34.969966650009155,1.1942017695872635,1739502674.6808407,34.969966650009155,0.6108,1739502674.6808424,34.969966650009155,0.961682731358262,1739502674.6808445,34.969966650009155,0.0,1739502674.6808467,34.969966650009155,0.00463276465248752,1739502674.6808484,34.969966650009155,2.9606178173635596,1739502674.6808505,34.969966650009155,0.9570499667057745 +1739502674.7006917,34.98996663093567,48.16027235060678,1739502674.7006962,34.98996663093567,8.152666256340236,1739502674.7007008,34.98996663093567,60.21167224869451,1739502674.7007046,34.98996663093567,44.65253598207883,1739502674.7007065,34.98996663093567,7.5804722851490975,1739502674.7007089,34.98996663093567,-2.979893422651204,1739502674.700711,34.98996663093567,1.1942017695872635,1739502674.7007132,34.98996663093567,0.6108,1739502674.7007158,34.98996663093567,0.961682731358262,1739502674.7007184,34.98996663093567,0.0,1739502674.7007205,34.98996663093567,0.00463276465248752,1739502674.700723,34.98996663093567,2.9606178173635596,1739502674.7007253,34.98996663093567,0.9570499667057745 +1739502674.7205093,35.00996661186218,48.16027235060678,1739502674.7205126,35.00996661186218,8.152666256340236,1739502674.7205162,35.00996661186218,60.21167224869451,1739502674.7205198,35.00996661186218,44.65253598207883,1739502674.7205215,35.00996661186218,7.5804722851490975,1739502674.7205236,35.00996661186218,-2.979893422651204,1739502674.7205255,35.00996661186218,1.1942017695872635,1739502674.7205274,35.00996661186218,0.6108,1739502674.7205288,35.00996661186218,0.961682731358262,1739502674.720531,35.00996661186218,0.0,1739502674.7205327,35.00996661186218,0.00463276465248752,1739502674.7205348,35.00996661186218,2.9606178173635596,1739502674.720537,35.00996661186218,0.9570499667057745 +1739502674.7408059,35.029966592788696,48.16027235060678,1739502674.7408097,35.029966592788696,8.152666256340236,1739502674.7408137,35.029966592788696,60.21167224869451,1739502674.740818,35.029966592788696,44.65253598207883,1739502674.7408197,35.029966592788696,7.5804722851490975,1739502674.7408223,35.029966592788696,-2.979893422651204,1739502674.740824,35.029966592788696,1.1942017695872635,1739502674.7408266,35.029966592788696,0.6108,1739502674.7408288,35.029966592788696,0.961682731358262,1739502674.740831,35.029966592788696,0.0,1739502674.7408328,35.029966592788696,0.00463276465248752,1739502674.7408347,35.029966592788696,2.9606178173635596,1739502674.7408369,35.029966592788696,0.9570499667057745 +1739502674.7598615,35.04996657371521,48.05646998058152,1739502674.759864,35.04996657371521,8.170316609022036,1739502674.759867,35.04996657371521,60.34235599064908,1739502674.75987,35.04996657371521,44.555975267828096,1739502674.7598715,35.04996657371521,7.490975267828095,1739502674.7598734,35.04996657371521,-2.949905373140618,1739502674.7598748,35.04996657371521,1.2061463003710087,1739502674.759876,35.04996657371521,0.6108,1739502674.7598774,35.04996657371521,0.9525370182589201,1739502674.7598794,35.04996657371521,0.0,1739502674.759881,35.04996657371521,-0.009379516838764824,1739502674.7598822,35.04996657371521,2.9882195063061063,1739502674.7598839,35.04996657371521,0.9575376942606768 +1739502674.785214,35.069966554641724,48.05646998058152,1739502674.7852187,35.069966554641724,8.170316609022036,1739502674.7852247,35.069966554641724,60.34235599064908,1739502674.7852304,35.069966554641724,44.555975267828096,1739502674.7852328,35.069966554641724,7.490975267828095,1739502674.7852366,35.069966554641724,-2.949905373140618,1739502674.7852392,35.069966554641724,1.2061463003710087,1739502674.7852418,35.069966554641724,0.6108,1739502674.7852447,35.069966554641724,0.9525370182589201,1739502674.7852478,35.069966554641724,0.0,1739502674.7852507,35.069966554641724,-0.005000676001756688,1739502674.7852535,35.069966554641724,2.9882195063061063,1739502674.7852564,35.069966554641724,0.9575376942606768 +1739502674.8048081,35.08996653556824,48.05646998058152,1739502674.8048131,35.08996653556824,8.170316609022036,1739502674.8048193,35.08996653556824,60.34235599064908,1739502674.8048253,35.08996653556824,44.555975267828096,1739502674.8048282,35.08996653556824,7.490975267828095,1739502674.8048315,35.08996653556824,-2.949905373140618,1739502674.8048344,35.08996653556824,1.2061463003710087,1739502674.8048372,35.08996653556824,0.6108,1739502674.8048396,35.08996653556824,0.9525370182589201,1739502674.804843,35.08996653556824,0.0,1739502674.8048458,35.08996653556824,-0.005000676001756688,1739502674.8048494,35.08996653556824,2.9882195063061063,1739502674.804859,35.08996653556824,0.9575376942606768 +1739502674.824313,35.10996651649475,48.05646998058152,1739502674.8243172,35.10996651649475,8.170316609022036,1739502674.8243232,35.10996651649475,60.34235599064908,1739502674.824329,35.10996651649475,44.555975267828096,1739502674.8243318,35.10996651649475,7.490975267828095,1739502674.824335,35.10996651649475,-2.949905373140618,1739502674.824338,35.10996651649475,1.2061463003710087,1739502674.8243408,35.10996651649475,0.6108,1739502674.8243432,35.10996651649475,0.9525370182589201,1739502674.8243465,35.10996651649475,0.0,1739502674.8243494,35.10996651649475,-0.005000676001756688,1739502674.8243525,35.10996651649475,2.9882195063061063,1739502674.8243554,35.10996651649475,0.9575376942606768 +1739502674.8401694,35.129966497421265,48.05646998058152,1739502674.8401725,35.129966497421265,8.170316609022036,1739502674.840176,35.129966497421265,60.34235599064908,1739502674.8401794,35.129966497421265,44.555975267828096,1739502674.8401814,35.129966497421265,7.490975267828095,1739502674.8401833,35.129966497421265,-2.949905373140618,1739502674.8401852,35.129966497421265,1.2061463003710087,1739502674.8401866,35.129966497421265,0.6108,1739502674.8401883,35.129966497421265,0.9525370182589201,1739502674.8401902,35.129966497421265,0.0,1739502674.840192,35.129966497421265,-0.005000676001756688,1739502674.8401935,35.129966497421265,2.9882195063061063,1739502674.8401954,35.129966497421265,0.9575376942606768 +1739502674.8596005,35.14996647834778,48.05646998058152,1739502674.8596027,35.14996647834778,8.170316609022036,1739502674.8596053,35.14996647834778,60.34235599064908,1739502674.8596082,35.14996647834778,44.555975267828096,1739502674.8596091,35.14996647834778,7.490975267828095,1739502674.8596106,35.14996647834778,-2.949905373140618,1739502674.859612,35.14996647834778,1.2061463003710087,1739502674.8596132,35.14996647834778,0.6108,1739502674.8596141,35.14996647834778,0.9525370182589201,1739502674.8596158,35.14996647834778,0.0,1739502674.859617,35.14996647834778,-0.005000676001756688,1739502674.8596182,35.14996647834778,2.9882195063061063,1739502674.8596196,35.14996647834778,0.9575376942606768 +1739502674.8844733,35.16996645927429,47.95222225641988,1739502674.8844814,35.16996645927429,8.185095477477912,1739502674.8844914,35.16996645927429,60.4545270300111,1739502674.8845015,35.16996645927429,44.47756878507157,1739502674.8845067,35.16996645927429,7.412544828686652,1739502674.8845131,35.16996645927429,-2.9228125184434903,1739502674.8845181,35.16996645927429,1.2023094203127922,1739502674.884523,35.16996645927429,0.6108,1739502674.884528,35.16996645927429,0.9554653264186754,1739502674.8845332,35.16996645927429,0.0,1739502674.8845382,35.16996645927429,0.0001825806656386656,1739502674.8845432,35.16996645927429,3.015821195248653,1739502674.8845482,35.16996645927429,0.956902514523601 +1739502674.905717,35.189966440200806,47.95222225641988,1739502674.9057255,35.189966440200806,8.185095477477912,1739502674.905736,35.189966440200806,60.4545270300111,1739502674.905746,35.189966440200806,44.47756878507157,1739502674.905751,35.189966440200806,7.412544828686652,1739502674.9057572,35.189966440200806,-2.9228125184434903,1739502674.9057627,35.189966440200806,1.2023094203127922,1739502674.9057674,35.189966440200806,0.6108,1739502674.905772,35.189966440200806,0.9554653264186754,1739502674.905778,35.189966440200806,0.0,1739502674.9057827,35.189966440200806,-0.0014371881049255464,1739502674.9057877,35.189966440200806,3.015821195248653,1739502674.9057927,35.189966440200806,0.956902514523601 +1739502674.9219055,35.20996642112732,47.95222225641988,1739502674.9219096,35.20996642112732,8.185095477477912,1739502674.9219139,35.20996642112732,60.4545270300111,1739502674.9219182,35.20996642112732,44.47756878507157,1739502674.9219205,35.20996642112732,7.412544828686652,1739502674.9219234,35.20996642112732,-2.9228125184434903,1739502674.9219255,35.20996642112732,1.2023094203127922,1739502674.921928,35.20996642112732,0.6108,1739502674.92193,35.20996642112732,0.9554653264186754,1739502674.9219325,35.20996642112732,0.0,1739502674.9219348,35.20996642112732,-0.0014371881049255464,1739502674.9219377,35.20996642112732,3.015821195248653,1739502674.9219398,35.20996642112732,0.956902514523601 +1739502674.9406183,35.22996640205383,47.95222225641988,1739502674.9406216,35.22996640205383,8.185095477477912,1739502674.9406254,35.22996640205383,60.4545270300111,1739502674.9406295,35.22996640205383,44.47756878507157,1739502674.9406314,35.22996640205383,7.412544828686652,1739502674.9406333,35.22996640205383,-2.9228125184434903,1739502674.9406354,35.22996640205383,1.2023094203127922,1739502674.940637,35.22996640205383,0.6108,1739502674.940639,35.22996640205383,0.9554653264186754,1739502674.940641,35.22996640205383,0.0,1739502674.9406428,35.22996640205383,-0.0014371881049255464,1739502674.940645,35.22996640205383,3.015821195248653,1739502674.9406466,35.22996640205383,0.956902514523601 +1739502674.9595745,35.24996638298035,47.95222225641988,1739502674.9595766,35.24996638298035,8.185095477477912,1739502674.9595795,35.24996638298035,60.4545270300111,1739502674.9595819,35.24996638298035,44.47756878507157,1739502674.9595833,35.24996638298035,7.412544828686652,1739502674.9595847,35.24996638298035,-2.9228125184434903,1739502674.9595861,35.24996638298035,1.2023094203127922,1739502674.9595873,35.24996638298035,0.6108,1739502674.9595885,35.24996638298035,0.9554653264186754,1739502674.95959,35.24996638298035,0.0,1739502674.9595912,35.24996638298035,-0.0014371881049255464,1739502674.9595923,35.24996638298035,3.015821195248653,1739502674.9595938,35.24996638298035,0.956902514523601 +1739502674.9800668,35.26996636390686,47.84764886002732,1739502674.9800692,35.26996636390686,8.19698671900107,1739502674.9800725,35.26996636390686,60.613232684098435,1739502674.9800751,35.26996636390686,44.36928303757347,1739502674.980076,35.26996636390686,7.296963394935049,1739502674.9800777,35.26996636390686,-2.888396834217152,1739502674.9800794,35.26996636390686,1.2366120662252422,1739502674.980081,35.26996636390686,0.6108,1739502674.9800825,35.26996636390686,0.9296018329670557,1739502674.980084,35.26996636390686,0.0,1739502674.9800851,35.26996636390686,-0.038823672712319506,1739502674.9800868,35.26996636390686,3.0434228841912,1739502674.980088,35.26996636390686,0.9567422215794066 +1739502675.0000725,35.289966344833374,47.84764886002732,1739502675.000075,35.289966344833374,8.19698671900107,1739502675.000078,35.289966344833374,60.613232684098435,1739502675.0000806,35.289966344833374,44.36928303757347,1739502675.0000818,35.289966344833374,7.296963394935049,1739502675.0000834,35.289966344833374,-2.888396834217152,1739502675.0000844,35.289966344833374,1.2366120662252422,1739502675.0000858,35.289966344833374,0.6108,1739502675.000087,35.289966344833374,0.9296018329670557,1739502675.0000887,35.289966344833374,0.0,1739502675.0000896,35.289966344833374,-0.027140388612350907,1739502675.0000908,35.289966344833374,3.0434228841912,1739502675.0000923,35.289966344833374,0.9567422215794066 +1739502675.0199323,35.30996632575989,47.84764886002732,1739502675.019935,35.30996632575989,8.19698671900107,1739502675.0199385,35.30996632575989,60.613232684098435,1739502675.019941,35.30996632575989,44.36928303757347,1739502675.0199423,35.30996632575989,7.296963394935049,1739502675.019944,35.30996632575989,-2.888396834217152,1739502675.0199456,35.30996632575989,1.2366120662252422,1739502675.019947,35.30996632575989,0.6108,1739502675.0199485,35.30996632575989,0.9296018329670557,1739502675.0199502,35.30996632575989,0.0,1739502675.019951,35.30996632575989,-0.027140388612350907,1739502675.0199525,35.30996632575989,3.0434228841912,1739502675.0199542,35.30996632575989,0.9567422215794066 +1739502675.0400455,35.3299663066864,47.84764886002732,1739502675.040048,35.3299663066864,8.19698671900107,1739502675.0400505,35.3299663066864,60.613232684098435,1739502675.0400531,35.3299663066864,44.36928303757347,1739502675.0400546,35.3299663066864,7.296963394935049,1739502675.040056,35.3299663066864,-2.888396834217152,1739502675.0400574,35.3299663066864,1.2366120662252422,1739502675.0400586,35.3299663066864,0.6108,1739502675.0400598,35.3299663066864,0.9296018329670557,1739502675.0400617,35.3299663066864,0.0,1739502675.040063,35.3299663066864,-0.027140388612350907,1739502675.0400643,35.3299663066864,3.0434228841912,1739502675.0400655,35.3299663066864,0.9567422215794066 +1739502675.059642,35.349966287612915,47.84764886002732,1739502675.0596442,35.349966287612915,8.19698671900107,1739502675.059647,35.349966287612915,60.613232684098435,1739502675.0596492,35.349966287612915,44.36928303757347,1739502675.059651,35.349966287612915,7.296963394935049,1739502675.059652,35.349966287612915,-2.888396834217152,1739502675.0596535,35.349966287612915,1.2366120662252422,1739502675.059655,35.349966287612915,0.6108,1739502675.059656,35.349966287612915,0.9296018329670557,1739502675.0596576,35.349966287612915,0.0,1739502675.0596588,35.349966287612915,-0.027140388612350907,1739502675.05966,35.349966287612915,3.0434228841912,1739502675.0596614,35.349966287612915,0.9567422215794066 +1739502675.0796413,35.36996626853943,47.84764886002732,1739502675.079644,35.36996626853943,8.19698671900107,1739502675.079647,35.36996626853943,60.613232684098435,1739502675.0796494,35.36996626853943,44.36928303757347,1739502675.0796509,35.36996626853943,7.296963394935049,1739502675.0796525,35.36996626853943,-2.888396834217152,1739502675.079654,35.36996626853943,1.2366120662252422,1739502675.0796554,35.36996626853943,0.6108,1739502675.0796564,35.36996626853943,0.9296018329670557,1739502675.0796583,35.36996626853943,0.0,1739502675.0796592,35.36996626853943,-0.027140388612350907,1739502675.079661,35.36996626853943,3.0434228841912,1739502675.0796626,35.36996626853943,0.9567422215794066 +1739502675.1017232,35.38996624946594,47.7429665961659,1739502675.1017263,35.38996624946594,8.205972744901963,1739502675.1017308,35.38996624946594,60.69637088795051,1739502675.1017356,35.38996624946594,44.31821659531423,1739502675.1017385,35.38996624946594,7.239705357718887,1739502675.1017423,35.38996624946594,-2.866598355927956,1739502675.1017456,35.38996624946594,1.2053399468591346,1739502675.101749,35.38996624946594,0.6108,1739502675.101752,35.38996624946594,0.9531516817479208,1739502675.1017554,35.38996624946594,0.0,1739502675.1017587,35.38996624946594,0.011779087824704805,1739502675.101762,35.38996624946594,3.0710245731337467,1739502675.1017656,35.38996624946594,0.9535349382840502 +1739502675.1196387,35.409966230392456,47.7429665961659,1739502675.119641,35.409966230392456,8.205972744901963,1739502675.119644,35.409966230392456,60.69637088795051,1739502675.1196465,35.409966230392456,44.31821659531423,1739502675.1196477,35.409966230392456,7.239705357718887,1739502675.1196496,35.409966230392456,-2.866598355927956,1739502675.1196508,35.409966230392456,1.2053399468591346,1739502675.119652,35.409966230392456,0.6108,1739502675.1196535,35.409966230392456,0.9531516817479208,1739502675.1196547,35.409966230392456,0.0,1739502675.1196558,35.409966230392456,-0.00038325653612947264,1739502675.1196573,35.409966230392456,3.0710245731337467,1739502675.1196587,35.409966230392456,0.9535349382840502 +1739502675.1398005,35.42996621131897,47.7429665961659,1739502675.1398032,35.42996621131897,8.205972744901963,1739502675.139806,35.42996621131897,60.69637088795051,1739502675.1398087,35.42996621131897,44.31821659531423,1739502675.13981,35.42996621131897,7.239705357718887,1739502675.1398115,35.42996621131897,-2.866598355927956,1739502675.1398132,35.42996621131897,1.2053399468591346,1739502675.1398144,35.42996621131897,0.6108,1739502675.1398156,35.42996621131897,0.9531516817479208,1739502675.1398175,35.42996621131897,0.0,1739502675.1398187,35.42996621131897,-0.00038325653612947264,1739502675.1398203,35.42996621131897,3.0710245731337467,1739502675.1398215,35.42996621131897,0.9535349382840502 +1739502675.159809,35.44996619224548,47.7429665961659,1739502675.1598115,35.44996619224548,8.205972744901963,1739502675.1598146,35.44996619224548,60.69637088795051,1739502675.1598175,35.44996619224548,44.31821659531423,1739502675.1598186,35.44996619224548,7.239705357718887,1739502675.1598206,35.44996619224548,-2.866598355927956,1739502675.1598217,35.44996619224548,1.2053399468591346,1739502675.1598234,35.44996619224548,0.6108,1739502675.1598248,35.44996619224548,0.9531516817479208,1739502675.1598265,35.44996619224548,0.0,1739502675.159828,35.44996619224548,-0.00038325653612947264,1739502675.1598291,35.44996619224548,3.0710245731337467,1739502675.1598308,35.44996619224548,0.9535349382840502 +1739502675.1813867,35.469966173172,47.7429665961659,1739502675.1813903,35.469966173172,8.205972744901963,1739502675.1813943,35.469966173172,60.69637088795051,1739502675.1813996,35.469966173172,44.31821659531423,1739502675.1814015,35.469966173172,7.239705357718887,1739502675.181405,35.469966173172,-2.866598355927956,1739502675.1814075,35.469966173172,1.2053399468591346,1739502675.1814103,35.469966173172,0.6108,1739502675.1814144,35.469966173172,0.9531516817479208,1739502675.1814184,35.469966173172,0.0,1739502675.181421,35.469966173172,-0.00038325653612947264,1739502675.1814246,35.469966173172,3.0710245731337467,1739502675.181427,35.469966173172,0.9535349382840502 +1739502675.2009966,35.48996615409851,47.63826547554641,1739502675.2010007,35.48996615409851,8.212054504465192,1739502675.201005,35.48996615409851,60.79765229866976,1739502675.2010098,35.48996615409851,44.25274368166663,1739502675.201012,35.48996615409851,7.162599792959142,1739502675.201015,35.48996615409851,-2.8410023559160833,1739502675.2010176,35.48996615409851,1.1939050576869943,1739502675.2010202,35.48996615409851,0.6108,1739502675.2010226,35.48996615409851,0.9619110326216127,1739502675.2010252,35.48996615409851,0.0,1739502675.2010279,35.48996615409851,0.012450302459234772,1739502675.2010305,35.48996615409851,3.0986262620762934,1739502675.2010329,35.48996615409851,0.9534712199779113 +1739502675.2213798,35.509966135025024,47.63826547554641,1739502675.221384,35.509966135025024,8.212054504465192,1739502675.2213886,35.509966135025024,60.79765229866976,1739502675.2213929,35.509966135025024,44.25274368166663,1739502675.2213953,35.509966135025024,7.162599792959142,1739502675.2213984,35.509966135025024,-2.8410023559160833,1739502675.221401,35.509966135025024,1.1939050576869943,1739502675.2214034,35.509966135025024,0.6108,1739502675.2214057,35.509966135025024,0.9619110326216127,1739502675.2214086,35.509966135025024,0.0,1739502675.2214108,35.509966135025024,0.008439812643701416,1739502675.2214134,35.509966135025024,3.0986262620762934,1739502675.221416,35.509966135025024,0.9534712199779113 +1739502675.2410252,35.52996611595154,47.63826547554641,1739502675.241029,35.52996611595154,8.212054504465192,1739502675.2410338,35.52996611595154,60.79765229866976,1739502675.2410388,35.52996611595154,44.25274368166663,1739502675.2410417,35.52996611595154,7.162599792959142,1739502675.241046,35.52996611595154,-2.8410023559160833,1739502675.2410493,35.52996611595154,1.1939050576869943,1739502675.2410529,35.52996611595154,0.6108,1739502675.2410562,35.52996611595154,0.9619110326216127,1739502675.2410595,35.52996611595154,0.0,1739502675.241063,35.52996611595154,0.008439812643701416,1739502675.2410667,35.52996611595154,3.0986262620762934,1739502675.2410703,35.52996611595154,0.9534712199779113 +1739502675.2611964,35.54996609687805,47.63826547554641,1739502675.2612004,35.54996609687805,8.212054504465192,1739502675.261205,35.54996609687805,60.79765229866976,1739502675.2612092,35.54996609687805,44.25274368166663,1739502675.2612119,35.54996609687805,7.162599792959142,1739502675.2612147,35.54996609687805,-2.8410023559160833,1739502675.2612176,35.54996609687805,1.1939050576869943,1739502675.26122,35.54996609687805,0.6108,1739502675.2612224,35.54996609687805,0.9619110326216127,1739502675.2612252,35.54996609687805,0.0,1739502675.2612278,35.54996609687805,0.008439812643701416,1739502675.2612302,35.54996609687805,3.0986262620762934,1739502675.261233,35.54996609687805,0.9534712199779113 +1739502675.2800815,35.569966077804565,47.63826547554641,1739502675.2800834,35.569966077804565,8.212054504465192,1739502675.2800858,35.569966077804565,60.79765229866976,1739502675.2800884,35.569966077804565,44.25274368166663,1739502675.2800896,35.569966077804565,7.162599792959142,1739502675.2800908,35.569966077804565,-2.8410023559160833,1739502675.2800922,35.569966077804565,1.1939050576869943,1739502675.2800934,35.569966077804565,0.6108,1739502675.2800944,35.569966077804565,0.9619110326216127,1739502675.2800963,35.569966077804565,0.0,1739502675.2800972,35.569966077804565,0.008439812643701416,1739502675.2800987,35.569966077804565,3.0986262620762934,1739502675.2800999,35.569966077804565,0.9534712199779113 +1739502675.2999644,35.58996605873108,47.63826547554641,1739502675.2999666,35.58996605873108,8.212054504465192,1739502675.2999694,35.58996605873108,60.79765229866976,1739502675.299972,35.58996605873108,44.25274368166663,1739502675.2999735,35.58996605873108,7.162599792959142,1739502675.2999752,35.58996605873108,-2.8410023559160833,1739502675.2999763,35.58996605873108,1.1939050576869943,1739502675.299978,35.58996605873108,0.6108,1739502675.2999792,35.58996605873108,0.9619110326216127,1739502675.2999809,35.58996605873108,0.0,1739502675.299982,35.58996605873108,0.008439812643701416,1739502675.2999835,35.58996605873108,3.0986262620762934,1739502675.299985,35.58996605873108,0.9534712199779113 +1739502675.3203726,35.60996603965759,47.53338156468397,1739502675.3203745,35.60996603965759,8.215245829038127,1739502675.320377,35.60996603965759,60.933631721254116,1739502675.3203797,35.60996603965759,44.165525456379235,1739502675.320381,35.60996603965759,7.055711049617977,1739502675.3203824,35.60996603965759,-2.8100095814651826,1739502675.3203838,35.60996603965759,1.2111419855006904,1739502675.320385,35.60996603965759,0.6108,1739502675.320386,35.60996603965759,0.9487377552704396,1739502675.3203876,35.60996603965759,0.0,1739502675.3203886,35.60996603965759,-0.012182945403676503,1739502675.32039,35.60996603965759,3.12622795101884,1739502675.3203914,35.60996603965759,0.9544760845588909 +1739502675.3399017,35.629966020584106,47.53338156468397,1739502675.3399045,35.629966020584106,8.215245829038127,1739502675.3399086,35.629966020584106,60.933631721254116,1739502675.3399117,35.629966020584106,44.165525456379235,1739502675.339913,35.629966020584106,7.055711049617977,1739502675.3399148,35.629966020584106,-2.8100095814651826,1739502675.339916,35.629966020584106,1.2111419855006904,1739502675.3399177,35.629966020584106,0.6108,1739502675.3399189,35.629966020584106,0.9487377552704396,1739502675.3399203,35.629966020584106,0.0,1739502675.339922,35.629966020584106,-0.005738329288451305,1739502675.3399234,35.629966020584106,3.12622795101884,1739502675.339925,35.629966020584106,0.9544760845588909 +1739502675.3598201,35.64996600151062,47.53338156468397,1739502675.3598228,35.64996600151062,8.215245829038127,1739502675.3598256,35.64996600151062,60.933631721254116,1739502675.3598285,35.64996600151062,44.165525456379235,1739502675.35983,35.64996600151062,7.055711049617977,1739502675.3598316,35.64996600151062,-2.8100095814651826,1739502675.359833,35.64996600151062,1.2111419855006904,1739502675.3598344,35.64996600151062,0.6108,1739502675.3598356,35.64996600151062,0.9487377552704396,1739502675.3598375,35.64996600151062,0.0,1739502675.3598387,35.64996600151062,-0.005738329288451305,1739502675.35984,35.64996600151062,3.12622795101884,1739502675.3598416,35.64996600151062,0.9544760845588909 +1739502675.3798156,35.669965982437134,47.53338156468397,1739502675.3798184,35.669965982437134,8.215245829038127,1739502675.3798225,35.669965982437134,60.933631721254116,1739502675.3798254,35.669965982437134,44.165525456379235,1739502675.3798268,35.669965982437134,7.055711049617977,1739502675.3798285,35.669965982437134,-2.8100095814651826,1739502675.3798301,35.669965982437134,1.2111419855006904,1739502675.3798316,35.669965982437134,0.6108,1739502675.3798327,35.669965982437134,0.9487377552704396,1739502675.3798344,35.669965982437134,0.0,1739502675.3798358,35.669965982437134,-0.005738329288451305,1739502675.3798375,35.669965982437134,3.12622795101884,1739502675.379839,35.669965982437134,0.9544760845588909 +1739502675.3998275,35.68996596336365,47.53338156468397,1739502675.3998303,35.68996596336365,8.215245829038127,1739502675.3998337,35.68996596336365,60.933631721254116,1739502675.3998363,35.68996596336365,44.165525456379235,1739502675.3998377,35.68996596336365,7.055711049617977,1739502675.3998394,35.68996596336365,-2.8100095814651826,1739502675.3998408,35.68996596336365,1.2111419855006904,1739502675.3998423,35.68996596336365,0.6108,1739502675.3998437,35.68996596336365,0.9487377552704396,1739502675.3998451,35.68996596336365,0.0,1739502675.3998466,35.68996596336365,-0.005738329288451305,1739502675.399848,35.68996596336365,3.12622795101884,1739502675.3998492,35.68996596336365,0.9544760845588909 +1739502675.4198072,35.70996594429016,47.42842127512275,1739502675.4198098,35.70996594429016,8.215541832539603,1739502675.4198127,35.70996594429016,61.015490826147015,1739502675.4198155,35.70996594429016,44.11705235069397,1739502675.419817,35.70996594429016,6.991284769909709,1739502675.4198184,35.70996594429016,-2.787464953545998,1739502675.41982,35.70996594429016,1.183645236191911,1739502675.4198215,35.70996594429016,0.6108,1739502675.419823,35.70996594429016,0.9698387512973119,1739502675.4198244,35.70996594429016,0.0,1739502675.4198256,35.70996594429016,0.02585158294586669,1739502675.419827,35.70996594429016,3.153829639961387,1739502675.4198284,35.70996594429016,0.9538590223971615 +1739502675.4399621,35.729965925216675,47.42842127512275,1739502675.439965,35.729965925216675,8.215541832539603,1739502675.4399683,35.729965925216675,61.015490826147015,1739502675.439971,35.729965925216675,44.11705235069397,1739502675.4399726,35.729965925216675,6.991284769909709,1739502675.4399743,35.729965925216675,-2.787464953545998,1739502675.4399757,35.729965925216675,1.183645236191911,1739502675.4399772,35.729965925216675,0.6108,1739502675.4399786,35.729965925216675,0.9698387512973119,1739502675.4399803,35.729965925216675,0.0,1739502675.439982,35.729965925216675,0.015979728900150425,1739502675.4399831,35.729965925216675,3.153829639961387,1739502675.4399846,35.729965925216675,0.9538590223971615 +1739502675.4598355,35.74996590614319,47.42842127512275,1739502675.4598382,35.74996590614319,8.215541832539603,1739502675.4598417,35.74996590614319,61.015490826147015,1739502675.4598444,35.74996590614319,44.11705235069397,1739502675.4598458,35.74996590614319,6.991284769909709,1739502675.4598477,35.74996590614319,-2.787464953545998,1739502675.4598489,35.74996590614319,1.183645236191911,1739502675.4598505,35.74996590614319,0.6108,1739502675.4598517,35.74996590614319,0.9698387512973119,1739502675.4598534,35.74996590614319,0.0,1739502675.4598546,35.74996590614319,0.015979728900150425,1739502675.459856,35.74996590614319,3.153829639961387,1739502675.4598575,35.74996590614319,0.9538590223971615 +1739502675.4801157,35.7699658870697,47.42842127512275,1739502675.4801178,35.7699658870697,8.215541832539603,1739502675.4801204,35.7699658870697,61.015490826147015,1739502675.480123,35.7699658870697,44.11705235069397,1739502675.4801245,35.7699658870697,6.991284769909709,1739502675.480126,35.7699658870697,-2.787464953545998,1739502675.4801273,35.7699658870697,1.183645236191911,1739502675.4801288,35.7699658870697,0.6108,1739502675.4801297,35.7699658870697,0.9698387512973119,1739502675.4801314,35.7699658870697,0.0,1739502675.4801326,35.7699658870697,0.015979728900150425,1739502675.4801338,35.7699658870697,3.153829639961387,1739502675.4801352,35.7699658870697,0.9538590223971615 +1739502675.49984,35.789965867996216,47.42842127512275,1739502675.4998431,35.789965867996216,8.215541832539603,1739502675.499846,35.789965867996216,61.015490826147015,1739502675.4998486,35.789965867996216,44.11705235069397,1739502675.4998503,35.789965867996216,6.991284769909709,1739502675.4998517,35.789965867996216,-2.787464953545998,1739502675.4998531,35.789965867996216,1.183645236191911,1739502675.4998546,35.789965867996216,0.6108,1739502675.4998555,35.789965867996216,0.9698387512973119,1739502675.4998572,35.789965867996216,0.0,1739502675.4998584,35.789965867996216,0.015979728900150425,1739502675.49986,35.789965867996216,3.153829639961387,1739502675.4998612,35.789965867996216,0.9538590223971615 +1739502675.5197535,35.80996584892273,47.42842127512275,1739502675.519756,35.80996584892273,8.215541832539603,1739502675.5197592,35.80996584892273,61.015490826147015,1739502675.5197623,35.80996584892273,44.11705235069397,1739502675.5197635,35.80996584892273,6.991284769909709,1739502675.5197651,35.80996584892273,-2.787464953545998,1739502675.5197668,35.80996584892273,1.183645236191911,1739502675.519768,35.80996584892273,0.6108,1739502675.5197694,35.80996584892273,0.9698387512973119,1739502675.5197709,35.80996584892273,0.0,1739502675.519772,35.80996584892273,0.015979728900150425,1739502675.519774,35.80996584892273,3.153829639961387,1739502675.5197754,35.80996584892273,0.9538590223971615 +1739502675.5398757,35.82996582984924,47.32342594553087,1739502675.5398786,35.82996582984924,8.21293870433291,1739502675.5398822,35.82996582984924,61.168374994439546,1739502675.5398853,35.82996582984924,44.025137618603495,1739502675.539887,35.82996582984924,6.864288559466817,1739502675.5398884,35.82996582984924,-2.7534426688569815,1739502675.5398898,35.82996582984924,1.216215368838034,1739502675.5398915,35.82996582984924,0.6108,1739502675.5398927,35.82996582984924,0.9448949107797397,1739502675.5398946,35.82996582984924,0.0,1739502675.5398958,35.82996582984924,-0.023135477023609394,1739502675.5398977,35.82996582984924,3.1814313289039338,1739502675.5398989,35.82996582984924,0.9558068779378166 +1739502675.5599067,35.84996581077576,47.32342594553087,1739502675.5599096,35.84996581077576,8.21293870433291,1739502675.5599124,35.84996581077576,61.168374994439546,1739502675.5599153,35.84996581077576,44.025137618603495,1739502675.5599165,35.84996581077576,6.864288559466817,1739502675.5599184,35.84996581077576,-2.7534426688569815,1739502675.5599196,35.84996581077576,1.216215368838034,1739502675.5599213,35.84996581077576,0.6108,1739502675.5599225,35.84996581077576,0.9448949107797397,1739502675.559924,35.84996581077576,0.0,1739502675.5599253,35.84996581077576,-0.010911967158076852,1739502675.5599265,35.84996581077576,3.1814313289039338,1739502675.5599282,35.84996581077576,0.9558068779378166 +1739502675.5797951,35.86996579170227,47.32342594553087,1739502675.579798,35.86996579170227,8.21293870433291,1739502675.5798013,35.86996579170227,61.168374994439546,1739502675.5798044,35.86996579170227,44.025137618603495,1739502675.5798056,35.86996579170227,6.864288559466817,1739502675.5798075,35.86996579170227,-2.7534426688569815,1739502675.5798087,35.86996579170227,1.216215368838034,1739502675.5798104,35.86996579170227,0.6108,1739502675.579812,35.86996579170227,0.9448949107797397,1739502675.5798137,35.86996579170227,0.0,1739502675.5798151,35.86996579170227,-0.010911967158076852,1739502675.5798168,35.86996579170227,3.1814313289039338,1739502675.5798182,35.86996579170227,0.9558068779378166 +1739502675.599827,35.889965772628784,47.32342594553087,1739502675.59983,35.889965772628784,8.21293870433291,1739502675.599833,35.889965772628784,61.168374994439546,1739502675.5998359,35.889965772628784,44.025137618603495,1739502675.5998373,35.889965772628784,6.864288559466817,1739502675.599839,35.889965772628784,-2.7534426688569815,1739502675.5998402,35.889965772628784,1.216215368838034,1739502675.5998416,35.889965772628784,0.6108,1739502675.5998428,35.889965772628784,0.9448949107797397,1739502675.5998445,35.889965772628784,0.0,1739502675.5998456,35.889965772628784,-0.010911967158076852,1739502675.599847,35.889965772628784,3.1814313289039338,1739502675.5998485,35.889965772628784,0.9558068779378166 +1739502675.6198413,35.9099657535553,47.32342594553087,1739502675.6198437,35.9099657535553,8.21293870433291,1739502675.6198466,35.9099657535553,61.168374994439546,1739502675.6198494,35.9099657535553,44.025137618603495,1739502675.6198506,35.9099657535553,6.864288559466817,1739502675.6198525,35.9099657535553,-2.7534426688569815,1739502675.619854,35.9099657535553,1.216215368838034,1739502675.6198556,35.9099657535553,0.6108,1739502675.6198568,35.9099657535553,0.9448949107797397,1739502675.6198585,35.9099657535553,0.0,1739502675.6198597,35.9099657535553,-0.010911967158076852,1739502675.6198614,35.9099657535553,3.1814313289039338,1739502675.6198626,35.9099657535553,0.9558068779378166 +1739502675.6399014,35.92996573448181,47.21848857152962,1739502675.639904,35.92996573448181,8.207436868498162,1739502675.639907,35.92996573448181,61.249371876358836,1739502675.63991,35.92996573448181,43.98077788508968,1739502675.6399114,35.92996573448181,6.799356287699769,1739502675.6399128,35.92996573448181,-2.731366536351358,1739502675.6399143,35.92996573448181,1.1866927690997955,1739502675.6399157,35.92996573448181,0.6108,1739502675.6399171,35.92996573448181,0.9674771388957593,1739502675.6399186,35.92996573448181,0.0,1739502675.6399198,35.92996573448181,0.023641811437908902,1739502675.6399214,35.92996573448181,3.2090330178464805,1739502675.639923,35.92996573448181,0.9546333903488576 +1739502675.6598556,35.949965715408325,47.21848857152962,1739502675.6598582,35.949965715408325,8.207436868498162,1739502675.6598613,35.949965715408325,61.249371876358836,1739502675.659864,35.949965715408325,43.98077788508968,1739502675.6598656,35.949965715408325,6.799356287699769,1739502675.659867,35.949965715408325,-2.731366536351358,1739502675.6598687,35.949965715408325,1.1866927690997955,1739502675.65987,35.949965715408325,0.6108,1739502675.6598713,35.949965715408325,0.9674771388957593,1739502675.6598728,35.949965715408325,0.0,1739502675.659874,35.949965715408325,0.012843748546901623,1739502675.6598756,35.949965715408325,3.2090330178464805,1739502675.659877,35.949965715408325,0.9546333903488576 +1739502675.6798182,35.96996569633484,47.21848857152962,1739502675.6798208,35.96996569633484,8.207436868498162,1739502675.6798239,35.96996569633484,61.249371876358836,1739502675.6798265,35.96996569633484,43.98077788508968,1739502675.679828,35.96996569633484,6.799356287699769,1739502675.6798296,35.96996569633484,-2.731366536351358,1739502675.6798308,35.96996569633484,1.1866927690997955,1739502675.6798322,35.96996569633484,0.6108,1739502675.6798334,35.96996569633484,0.9674771388957593,1739502675.679835,35.96996569633484,0.0,1739502675.6798365,35.96996569633484,0.012843748546901623,1739502675.6798377,35.96996569633484,3.2090330178464805,1739502675.6798394,35.96996569633484,0.9546333903488576 +1739502675.6998887,35.98996567726135,47.21848857152962,1739502675.6998918,35.98996567726135,8.207436868498162,1739502675.6998954,35.98996567726135,61.249371876358836,1739502675.6998987,35.98996567726135,43.98077788508968,1739502675.6999002,35.98996567726135,6.799356287699769,1739502675.6999023,35.98996567726135,-2.731366536351358,1739502675.6999035,35.98996567726135,1.1866927690997955,1739502675.699905,35.98996567726135,0.6108,1739502675.6999066,35.98996567726135,0.9674771388957593,1739502675.699908,35.98996567726135,0.0,1739502675.6999097,35.98996567726135,0.012843748546901623,1739502675.6999109,35.98996567726135,3.2090330178464805,1739502675.6999125,35.98996567726135,0.9546333903488576 +1739502675.7199495,36.009965658187866,47.21848857152962,1739502675.719952,36.009965658187866,8.207436868498162,1739502675.7199552,36.009965658187866,61.249371876358836,1739502675.7199578,36.009965658187866,43.98077788508968,1739502675.7199593,36.009965658187866,6.799356287699769,1739502675.719961,36.009965658187866,-2.731366536351358,1739502675.7199624,36.009965658187866,1.1866927690997955,1739502675.7199636,36.009965658187866,0.6108,1739502675.719965,36.009965658187866,0.9674771388957593,1739502675.7199667,36.009965658187866,0.0,1739502675.7199678,36.009965658187866,0.012843748546901623,1739502675.7199693,36.009965658187866,3.2090330178464805,1739502675.7199705,36.009965658187866,0.9546333903488576 +1739502675.7403517,36.02996563911438,47.21848857152962,1739502675.7403538,36.02996563911438,8.207436868498162,1739502675.7403567,36.02996563911438,61.249371876358836,1739502675.7403593,36.02996563911438,43.98077788508968,1739502675.740361,36.02996563911438,6.799356287699769,1739502675.7403624,36.02996563911438,-2.731366536351358,1739502675.7403638,36.02996563911438,1.1866927690997955,1739502675.740365,36.02996563911438,0.6108,1739502675.7403662,36.02996563911438,0.9674771388957593,1739502675.740368,36.02996563911438,0.0,1739502675.7403693,36.02996563911438,0.012843748546901623,1739502675.7403708,36.02996563911438,3.2090330178464805,1739502675.7403722,36.02996563911438,0.9546333903488576 +1739502675.7598553,36.049965620040894,47.11372730746967,1739502675.7598581,36.049965620040894,8.19903906426047,1739502675.7598615,36.049965620040894,61.40287772249783,1739502675.7598643,36.049965620040894,43.897096629478646,1739502675.7598655,36.049965620040894,6.666827402741698,1739502675.7598674,36.049965620040894,-2.697051108157709,1739502675.7598689,36.049965620040894,1.2200415033486023,1739502675.7598703,36.049965620040894,0.6108,1739502675.7598715,36.049965620040894,0.9420070966789182,1739502675.7598734,36.049965620040894,0.0,1739502675.7598746,36.049965620040894,-0.02656358077687858,1739502675.7598758,36.049965620040894,3.2366347067890273,1739502675.7598772,36.049965620040894,0.9562558789679044 +1739502675.7798898,36.06996560096741,47.11372730746967,1739502675.7798924,36.06996560096741,8.19903906426047,1739502675.7798958,36.06996560096741,61.40287772249783,1739502675.779899,36.06996560096741,43.897096629478646,1739502675.7799003,36.06996560096741,6.666827402741698,1739502675.779902,36.06996560096741,-2.697051108157709,1739502675.7799037,36.06996560096741,1.2200415033486023,1739502675.7799053,36.06996560096741,0.6108,1739502675.7799063,36.06996560096741,0.9420070966789182,1739502675.7799082,36.06996560096741,0.0,1739502675.7799096,36.06996560096741,-0.014248782288986184,1739502675.7799113,36.06996560096741,3.2366347067890273,1739502675.7799127,36.06996560096741,0.9562558789679044 +1739502675.7998729,36.08996558189392,47.11372730746967,1739502675.7998753,36.08996558189392,8.19903906426047,1739502675.7998784,36.08996558189392,61.40287772249783,1739502675.7998812,36.08996558189392,43.897096629478646,1739502675.7998827,36.08996558189392,6.666827402741698,1739502675.7998846,36.08996558189392,-2.697051108157709,1739502675.799886,36.08996558189392,1.2200415033486023,1739502675.7998874,36.08996558189392,0.6108,1739502675.7998886,36.08996558189392,0.9420070966789182,1739502675.7998903,36.08996558189392,0.0,1739502675.799892,36.08996558189392,-0.014248782288986184,1739502675.7998931,36.08996558189392,3.2366347067890273,1739502675.7998948,36.08996558189392,0.9562558789679044 +1739502675.8198974,36.109965562820435,47.11372730746967,1739502675.8199005,36.109965562820435,8.19903906426047,1739502675.8199034,36.109965562820435,61.40287772249783,1739502675.8199062,36.109965562820435,43.897096629478646,1739502675.8199077,36.109965562820435,6.666827402741698,1739502675.819909,36.109965562820435,-2.697051108157709,1739502675.8199108,36.109965562820435,1.2200415033486023,1739502675.819912,36.109965562820435,0.6108,1739502675.8199131,36.109965562820435,0.9420070966789182,1739502675.819915,36.109965562820435,0.0,1739502675.8199193,36.109965562820435,-0.014248782288986184,1739502675.8199224,36.109965562820435,3.2366347067890273,1739502675.8199246,36.109965562820435,0.9562558789679044 +1739502675.8397663,36.12996554374695,47.11372730746967,1739502675.839769,36.12996554374695,8.19903906426047,1739502675.8397722,36.12996554374695,61.40287772249783,1739502675.8397753,36.12996554374695,43.897096629478646,1739502675.8397765,36.12996554374695,6.666827402741698,1739502675.8397782,36.12996554374695,-2.697051108157709,1739502675.8397799,36.12996554374695,1.2200415033486023,1739502675.8397813,36.12996554374695,0.6108,1739502675.8397827,36.12996554374695,0.9420070966789182,1739502675.8397841,36.12996554374695,0.0,1739502675.8397858,36.12996554374695,-0.014248782288986184,1739502675.8397872,36.12996554374695,3.2366347067890273,1739502675.8397884,36.12996554374695,0.9562558789679044 +1739502675.8598993,36.14996552467346,47.00922238001774,1739502675.8599024,36.14996552467346,8.187752401124227,1739502675.8599055,36.14996552467346,61.483724833739466,1739502675.859908,36.14996552467346,43.85764147991003,1739502675.8599095,36.14996552467346,6.599813965560053,1739502675.8599114,36.14996552467346,-2.674866146397036,1739502675.8599126,36.14996552467346,1.1904574924831264,1739502675.8599143,36.14996552467346,0.6108,1739502675.8599155,36.14996552467346,0.9645676953489601,1739502675.8599174,36.14996552467346,0.0,1739502675.8599186,36.14996552467346,0.020804998705974763,1739502675.8599198,36.14996552467346,3.264236395731574,1739502675.8599215,36.14996552467346,0.9547170103861184 +1739502675.8813334,36.169965505599976,47.00922238001774,1739502675.881336,36.169965505599976,8.187752401124227,1739502675.881339,36.169965505599976,61.483724833739466,1739502675.881342,36.169965505599976,43.85764147991003,1739502675.8813436,36.169965505599976,6.599813965560053,1739502675.881345,36.169965505599976,-2.674866146397036,1739502675.8813465,36.169965505599976,1.1904574924831264,1739502675.881348,36.169965505599976,0.6108,1739502675.8813493,36.169965505599976,0.9645676953489601,1739502675.8813512,36.169965505599976,0.0,1739502675.8813524,36.169965505599976,0.009850684962841694,1739502675.881354,36.169965505599976,3.264236395731574,1739502675.8813558,36.169965505599976,0.9547170103861184 +1739502675.8998635,36.18996548652649,47.00922238001774,1739502675.8998663,36.18996548652649,8.187752401124227,1739502675.8998692,36.18996548652649,61.483724833739466,1739502675.899872,36.18996548652649,43.85764147991003,1739502675.8998733,36.18996548652649,6.599813965560053,1739502675.8998752,36.18996548652649,-2.674866146397036,1739502675.8998764,36.18996548652649,1.1904574924831264,1739502675.8998778,36.18996548652649,0.6108,1739502675.899879,36.18996548652649,0.9645676953489601,1739502675.8998806,36.18996548652649,0.0,1739502675.899882,36.18996548652649,0.009850684962841694,1739502675.8998835,36.18996548652649,3.264236395731574,1739502675.8998847,36.18996548652649,0.9547170103861184 +1739502675.9198587,36.209965467453,47.00922238001774,1739502675.9198616,36.209965467453,8.187752401124227,1739502675.9198647,36.209965467453,61.483724833739466,1739502675.9198673,36.209965467453,43.85764147991003,1739502675.9198687,36.209965467453,6.599813965560053,1739502675.9198704,36.209965467453,-2.674866146397036,1739502675.9198718,36.209965467453,1.1904574924831264,1739502675.919873,36.209965467453,0.6108,1739502675.9198747,36.209965467453,0.9645676953489601,1739502675.919876,36.209965467453,0.0,1739502675.9198773,36.209965467453,0.009850684962841694,1739502675.919879,36.209965467453,3.264236395731574,1739502675.9198802,36.209965467453,0.9547170103861184 +1739502675.9399645,36.22996544837952,47.00922238001774,1739502675.9399672,36.22996544837952,8.187752401124227,1739502675.939971,36.22996544837952,61.483724833739466,1739502675.9399743,36.22996544837952,43.85764147991003,1739502675.9399757,36.22996544837952,6.599813965560053,1739502675.9399776,36.22996544837952,-2.674866146397036,1739502675.9399793,36.22996544837952,1.1904574924831264,1739502675.9399807,36.22996544837952,0.6108,1739502675.9399822,36.22996544837952,0.9645676953489601,1739502675.939984,36.22996544837952,0.0,1739502675.9399858,36.22996544837952,0.009850684962841694,1739502675.9399874,36.22996544837952,3.264236395731574,1739502675.9399889,36.22996544837952,0.9547170103861184 +1739502675.959969,36.24996542930603,47.00922238001774,1739502675.959972,36.24996542930603,8.187752401124227,1739502675.959975,36.24996542930603,61.483724833739466,1739502675.9599779,36.24996542930603,43.85764147991003,1739502675.9599793,36.24996542930603,6.599813965560053,1739502675.9599812,36.24996542930603,-2.674866146397036,1739502675.9599829,36.24996542930603,1.1904574924831264,1739502675.9599843,36.24996542930603,0.6108,1739502675.959986,36.24996542930603,0.9645676953489601,1739502675.9599876,36.24996542930603,0.0,1739502675.959989,36.24996542930603,0.009850684962841694,1739502675.9599907,36.24996542930603,3.264236395731574,1739502675.9599924,36.24996542930603,0.9547170103861184 +1739502675.9802523,36.269965410232544,46.90509091163594,1739502675.9802547,36.269965410232544,8.173588166149909,1739502675.9802577,36.269965410232544,61.558844750807026,1739502675.9802608,36.269965410232544,43.81893420614589,1739502675.9802625,36.269965410232544,6.532425829356154,1739502675.9802642,36.269965410232544,-2.652843953449913,1739502675.9802654,36.269965410232544,1.160735197167348,1739502675.980267,36.269965410232544,0.6108,1739502675.9802685,36.269965410232544,0.9877778784824018,1739502675.9802704,36.269965410232544,0.0,1739502675.9802716,36.269965410232544,0.04172370057680495,1739502675.9802732,36.269965410232544,3.291838084674121,1739502675.9802747,36.269965410232544,0.9560145018154577 +1739502675.999868,36.28996539115906,46.90509091163594,1739502675.9998705,36.28996539115906,8.173588166149909,1739502675.9998736,36.28996539115906,61.558844750807026,1739502675.9998763,36.28996539115906,43.81893420614589,1739502675.999878,36.28996539115906,6.532425829356154,1739502675.9998796,36.28996539115906,-2.652843953449913,1739502675.9998813,36.28996539115906,1.160735197167348,1739502675.999883,36.28996539115906,0.6108,1739502675.9998846,36.28996539115906,0.9877778784824018,1739502675.999886,36.28996539115906,0.0,1739502675.9998877,36.28996539115906,0.031763376666944176,1739502675.9998891,36.28996539115906,3.291838084674121,1739502675.9998908,36.28996539115906,0.9560145018154577 +1739502676.0197716,36.30996537208557,46.90509091163594,1739502676.019774,36.30996537208557,8.173588166149909,1739502676.019777,36.30996537208557,61.558844750807026,1739502676.01978,36.30996537208557,43.81893420614589,1739502676.019781,36.30996537208557,6.532425829356154,1739502676.0197833,36.30996537208557,-2.652843953449913,1739502676.0197845,36.30996537208557,1.160735197167348,1739502676.019786,36.30996537208557,0.6108,1739502676.0197873,36.30996537208557,0.9877778784824018,1739502676.019789,36.30996537208557,0.0,1739502676.0197906,36.30996537208557,0.031763376666944176,1739502676.019792,36.30996537208557,3.291838084674121,1739502676.0197935,36.30996537208557,0.9560145018154577 +1739502676.039995,36.329965353012085,46.90509091163594,1739502676.0399976,36.329965353012085,8.173588166149909,1739502676.040001,36.329965353012085,61.558844750807026,1739502676.040004,36.329965353012085,43.81893420614589,1739502676.0400057,36.329965353012085,6.532425829356154,1739502676.0400074,36.329965353012085,-2.652843953449913,1739502676.040009,36.329965353012085,1.160735197167348,1739502676.0400105,36.329965353012085,0.6108,1739502676.040012,36.329965353012085,0.9877778784824018,1739502676.0400136,36.329965353012085,0.0,1739502676.0400152,36.329965353012085,0.031763376666944176,1739502676.0400167,36.329965353012085,3.291838084674121,1739502676.0400178,36.329965353012085,0.9560145018154577 +1739502676.0597534,36.3499653339386,46.90509091163594,1739502676.059756,36.3499653339386,8.173588166149909,1739502676.0597594,36.3499653339386,61.558844750807026,1739502676.0597625,36.3499653339386,43.81893420614589,1739502676.059764,36.3499653339386,6.532425829356154,1739502676.0597663,36.3499653339386,-2.652843953449913,1739502676.059768,36.3499653339386,1.160735197167348,1739502676.0597694,36.3499653339386,0.6108,1739502676.0597708,36.3499653339386,0.9877778784824018,1739502676.0597727,36.3499653339386,0.0,1739502676.059774,36.3499653339386,0.031763376666944176,1739502676.0597758,36.3499653339386,3.291838084674121,1739502676.0597773,36.3499653339386,0.9560145018154577 +1739502676.079968,36.36996531486511,46.80115605675843,1739502676.0799706,36.36996531486511,8.156516462806595,1739502676.079974,36.36996531486511,61.56054185189175,1739502676.0799768,36.36996531486511,43.81478006687004,1739502676.0799782,36.36996531486511,6.524872848854623,1739502676.0799801,36.36996531486511,-2.641546499194468,1739502676.0799816,36.36996531486511,1.0775844906351746,1739502676.079983,36.36996531486511,0.6108,1739502676.0799847,36.36996531486511,1.0557201485989085,1739502676.0799863,36.36996531486511,0.0,1739502676.079988,36.36996531486511,0.12555368973732925,1739502676.0799897,36.36996531486511,3.3194397736166676,1739502676.079991,36.36996531486511,0.9594759509128751 +1739502676.099766,36.389965295791626,46.80115605675843,1739502676.0997686,36.389965295791626,8.156516462806595,1739502676.0997717,36.389965295791626,61.56054185189175,1739502676.0997748,36.389965295791626,43.81478006687004,1739502676.0997763,36.389965295791626,6.524872848854623,1739502676.099778,36.389965295791626,-2.641546499194468,1739502676.0997798,36.389965295791626,1.0775844906351746,1739502676.0997813,36.389965295791626,0.6108,1739502676.099783,36.389965295791626,1.0557201485989085,1739502676.0997844,36.389965295791626,0.0,1739502676.099786,36.389965295791626,0.09624419768603343,1739502676.0997877,36.389965295791626,3.3194397736166676,1739502676.0997894,36.389965295791626,0.9594759509128751 +1739502676.1196325,36.40996527671814,46.80115605675843,1739502676.1196344,36.40996527671814,8.156516462806595,1739502676.1196375,36.40996527671814,61.56054185189175,1739502676.1196404,36.40996527671814,43.81478006687004,1739502676.1196415,36.40996527671814,6.524872848854623,1739502676.1196434,36.40996527671814,-2.641546499194468,1739502676.1196449,36.40996527671814,1.0775844906351746,1739502676.1196465,36.40996527671814,0.6108,1739502676.119648,36.40996527671814,1.0557201485989085,1739502676.1196496,36.40996527671814,0.0,1739502676.1196508,36.40996527671814,0.09624419768603343,1739502676.1196523,36.40996527671814,3.3194397736166676,1739502676.119654,36.40996527671814,0.9594759509128751 +1739502676.1403165,36.42996525764465,46.80115605675843,1739502676.14032,36.42996525764465,8.156516462806595,1739502676.140324,36.42996525764465,61.56054185189175,1739502676.1403277,36.42996525764465,43.81478006687004,1739502676.1403298,36.42996525764465,6.524872848854623,1739502676.140332,36.42996525764465,-2.641546499194468,1739502676.140334,36.42996525764465,1.0775844906351746,1739502676.1403356,36.42996525764465,0.6108,1739502676.1403375,36.42996525764465,1.0557201485989085,1739502676.1403394,36.42996525764465,0.0,1739502676.1403413,36.42996525764465,0.09624419768603343,1739502676.1403437,36.42996525764465,3.3194397736166676,1739502676.1403453,36.42996525764465,0.9594759509128751 +1739502676.1601727,36.44996523857117,46.80115605675843,1739502676.1601758,36.44996523857117,8.156516462806595,1739502676.1601796,36.44996523857117,61.56054185189175,1739502676.1601832,36.44996523857117,43.81478006687004,1739502676.1601849,36.44996523857117,6.524872848854623,1739502676.1601872,36.44996523857117,-2.641546499194468,1739502676.160189,36.44996523857117,1.0775844906351746,1739502676.1601908,36.44996523857117,0.6108,1739502676.1601923,36.44996523857117,1.0557201485989085,1739502676.1601946,36.44996523857117,0.0,1739502676.160196,36.44996523857117,0.09624419768603343,1739502676.1601982,36.44996523857117,3.3194397736166676,1739502676.1601996,36.44996523857117,0.9594759509128751 +1739502676.1802726,36.46996521949768,46.80115605675843,1739502676.1802766,36.46996521949768,8.156516462806595,1739502676.1802807,36.46996521949768,61.56054185189175,1739502676.180285,36.46996521949768,43.81478006687004,1739502676.1802866,36.46996521949768,6.524872848854623,1739502676.180289,36.46996521949768,-2.641546499194468,1739502676.1802907,36.46996521949768,1.0775844906351746,1739502676.1802926,36.46996521949768,0.6108,1739502676.180294,36.46996521949768,1.0557201485989085,1739502676.1802962,36.46996521949768,0.0,1739502676.180298,36.46996521949768,0.09624419768603343,1739502676.1803002,36.46996521949768,3.3194397736166676,1739502676.1803021,36.46996521949768,0.9594759509128751 +1739502676.2002182,36.489965200424194,46.69695144645333,1739502676.2002213,36.489965200424194,8.136430541024437,1739502676.2002249,36.489965200424194,61.562249297500195,1739502676.2002285,36.489965200424194,43.80322718118541,1739502676.2002301,36.489965200424194,6.503867602155292,1739502676.2002323,36.489965200424194,-2.6279327354969975,1739502676.2002342,36.489965200424194,1.0078906556283422,1739502676.200236,36.489965200424194,0.6108,1739502676.2002375,36.489965200424194,1.1162537440906268,1739502676.2002397,36.489965200424194,0.0,1739502676.2002413,36.489965200424194,0.1681001849501392,1739502676.2002432,36.489965200424194,3.3470414625592144,1739502676.200245,36.489965200424194,0.970608569883173 +1739502676.2203023,36.50996518135071,46.69695144645333,1739502676.2203054,36.50996518135071,8.136430541024437,1739502676.220309,36.50996518135071,61.562249297500195,1739502676.2203126,36.50996518135071,43.80322718118541,1739502676.2203143,36.50996518135071,6.503867602155292,1739502676.2203166,36.50996518135071,-2.6279327354969975,1739502676.2203186,36.50996518135071,1.0078906556283422,1739502676.2203202,36.50996518135071,0.6108,1739502676.220322,36.50996518135071,1.1162537440906268,1739502676.2203238,36.50996518135071,0.0,1739502676.220326,36.50996518135071,0.14564517420745382,1739502676.2203276,36.50996518135071,3.3470414625592144,1739502676.2203295,36.50996518135071,0.970608569883173 +1739502676.240314,36.52996516227722,46.69695144645333,1739502676.2403176,36.52996516227722,8.136430541024437,1739502676.2403219,36.52996516227722,61.562249297500195,1739502676.2403257,36.52996516227722,43.80322718118541,1739502676.2403274,36.52996516227722,6.503867602155292,1739502676.2403295,36.52996516227722,-2.6279327354969975,1739502676.2403312,36.52996516227722,1.0078906556283422,1739502676.240333,36.52996516227722,0.6108,1739502676.2403345,36.52996516227722,1.1162537440906268,1739502676.240337,36.52996516227722,0.0,1739502676.240339,36.52996516227722,0.14564517420745382,1739502676.2403407,36.52996516227722,3.3470414625592144,1739502676.2403426,36.52996516227722,0.970608569883173 +1739502676.2602322,36.549965143203735,46.69695144645333,1739502676.2602355,36.549965143203735,8.136430541024437,1739502676.2602394,36.549965143203735,61.562249297500195,1739502676.260243,36.549965143203735,43.80322718118541,1739502676.2602448,36.549965143203735,6.503867602155292,1739502676.260247,36.549965143203735,-2.6279327354969975,1739502676.260249,36.549965143203735,1.0078906556283422,1739502676.2602506,36.549965143203735,0.6108,1739502676.2602522,36.549965143203735,1.1162537440906268,1739502676.2602541,36.549965143203735,0.0,1739502676.2602558,36.549965143203735,0.14564517420745382,1739502676.2602577,36.549965143203735,3.3470414625592144,1739502676.2602596,36.549965143203735,0.970608569883173 +1739502676.28029,36.56996512413025,46.69695144645333,1739502676.2802935,36.56996512413025,8.136430541024437,1739502676.2802982,36.56996512413025,61.562249297500195,1739502676.2803016,36.56996512413025,43.80322718118541,1739502676.2803035,36.56996512413025,6.503867602155292,1739502676.2803056,36.56996512413025,-2.6279327354969975,1739502676.280308,36.56996512413025,1.0078906556283422,1739502676.2803097,36.56996512413025,0.6108,1739502676.2803116,36.56996512413025,1.1162537440906268,1739502676.2803135,36.56996512413025,0.0,1739502676.2803154,36.56996512413025,0.14564517420745382,1739502676.280317,36.56996512413025,3.3470414625592144,1739502676.2803192,36.56996512413025,0.970608569883173 +1739502676.3002527,36.58996510505676,46.591946735567966,1739502676.300256,36.58996510505676,8.113166246956236,1739502676.3002596,36.58996510505676,61.95760351995722,1739502676.3002632,36.58996510505676,43.61371537293339,1739502676.300265,36.58996510505676,6.121199010716805,1739502676.300267,36.58996510505676,-2.552085326171029,1739502676.300269,36.58996510505676,1.250304749179066,1739502676.3002706,36.58996510505676,0.6108,1739502676.3002725,36.58996510505676,0.919474408343578,1739502676.3002744,36.58996510505676,0.0,1739502676.3002763,36.58996510505676,-0.16372647042330712,1739502676.300278,36.58996510505676,3.374643151501761,1739502676.30028,36.58996510505676,0.9865221764322755 +1739502676.320241,36.609965085983276,46.591946735567966,1739502676.320244,36.609965085983276,8.113166246956236,1739502676.3202481,36.609965085983276,61.95760351995722,1739502676.3202517,36.609965085983276,43.61371537293339,1739502676.3202531,36.609965085983276,6.121199010716805,1739502676.3202555,36.609965085983276,-2.552085326171029,1739502676.3202574,36.609965085983276,1.250304749179066,1739502676.3202593,36.609965085983276,0.6108,1739502676.3202608,36.609965085983276,0.919474408343578,1739502676.3202631,36.609965085983276,0.0,1739502676.320265,36.609965085983276,-0.0670477680886975,1739502676.3202667,36.609965085983276,3.374643151501761,1739502676.3202684,36.609965085983276,0.9865221764322755 +1739502676.3403246,36.62996506690979,46.591946735567966,1739502676.340328,36.62996506690979,8.113166246956236,1739502676.3403323,36.62996506690979,61.95760351995722,1739502676.340336,36.62996506690979,43.61371537293339,1739502676.3403382,36.62996506690979,6.121199010716805,1739502676.3403401,36.62996506690979,-2.552085326171029,1739502676.340342,36.62996506690979,1.250304749179066,1739502676.3403437,36.62996506690979,0.6108,1739502676.3403456,36.62996506690979,0.919474408343578,1739502676.340348,36.62996506690979,0.0,1739502676.34035,36.62996506690979,-0.0670477680886975,1739502676.3403525,36.62996506690979,3.374643151501761,1739502676.3403542,36.62996506690979,0.9865221764322755 +1739502676.3602319,36.649965047836304,46.591946735567966,1739502676.3602355,36.649965047836304,8.113166246956236,1739502676.360239,36.649965047836304,61.95760351995722,1739502676.3602426,36.649965047836304,43.61371537293339,1739502676.3602445,36.649965047836304,6.121199010716805,1739502676.360247,36.649965047836304,-2.552085326171029,1739502676.3602486,36.649965047836304,1.250304749179066,1739502676.3602505,36.649965047836304,0.6108,1739502676.3602521,36.649965047836304,0.919474408343578,1739502676.3602543,36.649965047836304,0.0,1739502676.360256,36.649965047836304,-0.0670477680886975,1739502676.3602579,36.649965047836304,3.374643151501761,1739502676.3602595,36.649965047836304,0.9865221764322755 +1739502676.3803108,36.66996502876282,46.591946735567966,1739502676.3803139,36.66996502876282,8.113166246956236,1739502676.380318,36.66996502876282,61.95760351995722,1739502676.3803215,36.66996502876282,43.61371537293339,1739502676.3803234,36.66996502876282,6.121199010716805,1739502676.3803258,36.66996502876282,-2.552085326171029,1739502676.3803277,36.66996502876282,1.250304749179066,1739502676.3803294,36.66996502876282,0.6108,1739502676.380331,36.66996502876282,0.919474408343578,1739502676.3803334,36.66996502876282,0.0,1739502676.3803349,36.66996502876282,-0.0670477680886975,1739502676.380337,36.66996502876282,3.374643151501761,1739502676.3803387,36.66996502876282,0.9865221764322755 +1739502676.4002166,36.68996500968933,46.591946735567966,1739502676.4002197,36.68996500968933,8.113166246956236,1739502676.4002237,36.68996500968933,61.95760351995722,1739502676.400227,36.68996500968933,43.61371537293339,1739502676.400229,36.68996500968933,6.121199010716805,1739502676.400231,36.68996500968933,-2.552085326171029,1739502676.4002328,36.68996500968933,1.250304749179066,1739502676.4002345,36.68996500968933,0.6108,1739502676.4002361,36.68996500968933,0.919474408343578,1739502676.400238,36.68996500968933,0.0,1739502676.4002397,36.68996500968933,-0.0670477680886975,1739502676.4002416,36.68996500968933,3.374643151501761,1739502676.4002435,36.68996500968933,0.9865221764322755 +1739502676.4204345,36.709964990615845,46.487398099349186,1739502676.4204392,36.709964990615845,8.086963012010914,1739502676.4204457,36.709964990615845,62.11549524019325,1739502676.4204526,36.709964990615845,43.56224857574762,1739502676.4204564,36.709964990615845,5.995789948591922,1739502676.4204614,36.709964990615845,-2.520940223706909,1739502676.4204657,36.709964990615845,1.2666951270831008,1739502676.4204702,36.709964990615845,0.6108,1739502676.4204745,36.709964990615845,0.9074966813246742,1739502676.4204793,36.709964990615845,0.0,1739502676.4204836,36.709964990615845,-0.06823064234150641,1739502676.420488,36.709964990615845,3.402244840444308,1739502676.4204931,36.709964990615845,0.9753576752198174 +1739502676.4418557,36.72996497154236,46.487398099349186,1739502676.4418588,36.72996497154236,8.086963012010914,1739502676.4418623,36.72996497154236,62.11549524019325,1739502676.441866,36.72996497154236,43.56224857574762,1739502676.4418676,36.72996497154236,5.995789948591922,1739502676.4418695,36.72996497154236,-2.520940223706909,1739502676.4418714,36.72996497154236,1.2666951270831008,1739502676.441873,36.72996497154236,0.6108,1739502676.4418747,36.72996497154236,0.9074966813246742,1739502676.4418764,36.72996497154236,0.0,1739502676.441878,36.72996497154236,-0.06786099389514322,1739502676.44188,36.72996497154236,3.402244840444308,1739502676.441882,36.72996497154236,0.9753576752198174 +1739502676.460308,36.74996495246887,46.487398099349186,1739502676.4603114,36.74996495246887,8.086963012010914,1739502676.460315,36.74996495246887,62.11549524019325,1739502676.4603186,36.74996495246887,43.56224857574762,1739502676.4603205,36.74996495246887,5.995789948591922,1739502676.4603226,36.74996495246887,-2.520940223706909,1739502676.4603243,36.74996495246887,1.2666951270831008,1739502676.4603262,36.74996495246887,0.6108,1739502676.4603279,36.74996495246887,0.9074966813246742,1739502676.4603302,36.74996495246887,0.0,1739502676.460332,36.74996495246887,-0.06786099389514322,1739502676.4603338,36.74996495246887,3.402244840444308,1739502676.4603353,36.74996495246887,0.9753576752198174 +1739502676.480434,36.769964933395386,46.487398099349186,1739502676.4804375,36.769964933395386,8.086963012010914,1739502676.4804423,36.769964933395386,62.11549524019325,1739502676.480446,36.769964933395386,43.56224857574762,1739502676.480448,36.769964933395386,5.995789948591922,1739502676.4804504,36.769964933395386,-2.520940223706909,1739502676.4804525,36.769964933395386,1.2666951270831008,1739502676.4804544,36.769964933395386,0.6108,1739502676.480456,36.769964933395386,0.9074966813246742,1739502676.4804583,36.769964933395386,0.0,1739502676.48046,36.769964933395386,-0.06786099389514322,1739502676.4804618,36.769964933395386,3.402244840444308,1739502676.4804635,36.769964933395386,0.9753576752198174 +1739502676.500207,36.7899649143219,46.487398099349186,1739502676.5002096,36.7899649143219,8.086963012010914,1739502676.5002139,36.7899649143219,62.11549524019325,1739502676.5002177,36.7899649143219,43.56224857574762,1739502676.5002193,36.7899649143219,5.995789948591922,1739502676.5002217,36.7899649143219,-2.520940223706909,1739502676.5002234,36.7899649143219,1.2666951270831008,1739502676.5002253,36.7899649143219,0.6108,1739502676.500227,36.7899649143219,0.9074966813246742,1739502676.5002291,36.7899649143219,0.0,1739502676.5002313,36.7899649143219,-0.06786099389514322,1739502676.500233,36.7899649143219,3.402244840444308,1739502676.5002348,36.7899649143219,0.9753576752198174 +1739502676.5202446,36.80996489524841,46.38444827017854,1739502676.5202482,36.80996489524841,8.058117936436949,1739502676.520252,36.80996489524841,62.1987829627189,1739502676.5202553,36.80996489524841,43.53743209081478,1739502676.520257,36.80996489524841,5.9320299607829785,1739502676.5202594,36.80996489524841,-2.5001570578252843,1739502676.520261,36.80996489524841,1.2290235393050624,1739502676.520263,36.80996489524841,0.6108,1739502676.5202644,36.80996489524841,0.9352624446913691,1739502676.5202665,36.80996489524841,0.0,1739502676.520268,36.80996489524841,-0.01666656919056655,1739502676.52027,36.80996489524841,3.4298465293868547,1739502676.5202718,36.80996489524841,0.9679272820913979 +1739502676.5403638,36.82996487617493,46.38444827017854,1739502676.5403671,36.82996487617493,8.058117936436949,1739502676.5403736,36.82996487617493,62.1987829627189,1739502676.5403774,36.82996487617493,43.53743209081478,1739502676.540379,36.82996487617493,5.9320299607829785,1739502676.5403817,36.82996487617493,-2.5001570578252843,1739502676.5403838,36.82996487617493,1.2290235393050624,1739502676.5403855,36.82996487617493,0.6108,1739502676.5403876,36.82996487617493,0.9352624446913691,1739502676.5403895,36.82996487617493,0.0,1739502676.540392,36.82996487617493,-0.03266483740002879,1739502676.540394,36.82996487617493,3.4298465293868547,1739502676.5403957,36.82996487617493,0.9679272820913979 +1739502676.5603824,36.84996485710144,46.38444827017854,1739502676.560386,36.84996485710144,8.058117936436949,1739502676.5603895,36.84996485710144,62.1987829627189,1739502676.5603938,36.84996485710144,43.53743209081478,1739502676.5603955,36.84996485710144,5.9320299607829785,1739502676.5603976,36.84996485710144,-2.5001570578252843,1739502676.5603993,36.84996485710144,1.2290235393050624,1739502676.5604014,36.84996485710144,0.6108,1739502676.5604029,36.84996485710144,0.9352624446913691,1739502676.560405,36.84996485710144,0.0,1739502676.5604067,36.84996485710144,-0.03266483740002879,1739502676.5604086,36.84996485710144,3.4298465293868547,1739502676.5604107,36.84996485710144,0.9679272820913979 +1739502676.5804985,36.869964838027954,46.38444827017854,1739502676.580502,36.869964838027954,8.058117936436949,1739502676.5805058,36.869964838027954,62.1987829627189,1739502676.5805094,36.869964838027954,43.53743209081478,1739502676.580511,36.869964838027954,5.9320299607829785,1739502676.580513,36.869964838027954,-2.5001570578252843,1739502676.5805151,36.869964838027954,1.2290235393050624,1739502676.580517,36.869964838027954,0.6108,1739502676.580519,36.869964838027954,0.9352624446913691,1739502676.5805209,36.869964838027954,0.0,1739502676.5805228,36.869964838027954,-0.03266483740002879,1739502676.5805247,36.869964838027954,3.4298465293868547,1739502676.5805266,36.869964838027954,0.9679272820913979 +1739502676.600218,36.88996481895447,46.38444827017854,1739502676.6002216,36.88996481895447,8.058117936436949,1739502676.6002252,36.88996481895447,62.1987829627189,1739502676.6002285,36.88996481895447,43.53743209081478,1739502676.6002305,36.88996481895447,5.9320299607829785,1739502676.6002324,36.88996481895447,-2.5001570578252843,1739502676.6002343,36.88996481895447,1.2290235393050624,1739502676.600236,36.88996481895447,0.6108,1739502676.6002376,36.88996481895447,0.9352624446913691,1739502676.6002395,36.88996481895447,0.0,1739502676.6002414,36.88996481895447,-0.03266483740002879,1739502676.6002436,36.88996481895447,3.4298465293868547,1739502676.6002452,36.88996481895447,0.9679272820913979 +1739502676.6202211,36.90996479988098,46.38444827017854,1739502676.6202254,36.90996479988098,8.058117936436949,1739502676.6202304,36.90996479988098,62.1987829627189,1739502676.6202352,36.90996479988098,43.53743209081478,1739502676.620239,36.90996479988098,5.9320299607829785,1739502676.620242,36.90996479988098,-2.5001570578252843,1739502676.6202447,36.90996479988098,1.2290235393050624,1739502676.6202476,36.90996479988098,0.6108,1739502676.6202497,36.90996479988098,0.9352624446913691,1739502676.6202524,36.90996479988098,0.0,1739502676.6202548,36.90996479988098,-0.03266483740002879,1739502676.6202576,36.90996479988098,3.4298465293868547,1739502676.62026,36.90996479988098,0.9679272820913979 +1739502676.640393,36.929964780807495,46.28290212407345,1739502676.6403968,36.929964780807495,8.026617871857878,1739502676.6404011,36.929964780807495,62.37632748007546,1739502676.6404052,36.929964780807495,43.479100465975264,1739502676.6404073,36.929964780807495,5.77128465359659,1739502676.6404097,36.929964780807495,-2.464184245953796,1739502676.6404116,36.929964780807495,1.27281963558515,1739502676.6404135,36.929964780807495,0.6108,1739502676.640415,36.929964780807495,0.9030611793933786,1739502676.6404173,36.929964780807495,0.0,1739502676.6404197,36.929964780807495,-0.07475710926469913,1739502676.6404219,36.929964780807495,3.4574482183294015,1739502676.640424,36.929964780807495,0.9646644450760363 +1739502676.6603975,36.94996476173401,46.28290212407345,1739502676.6604009,36.94996476173401,8.026617871857878,1739502676.660405,36.94996476173401,62.37632748007546,1739502676.6604083,36.94996476173401,43.479100465975264,1739502676.6604102,36.94996476173401,5.77128465359659,1739502676.6604128,36.94996476173401,-2.464184245953796,1739502676.6604145,36.94996476173401,1.27281963558515,1739502676.6604164,36.94996476173401,0.6108,1739502676.660418,36.94996476173401,0.9030611793933786,1739502676.66042,36.94996476173401,0.0,1739502676.6604218,36.94996476173401,-0.061603265682657726,1739502676.660424,36.94996476173401,3.4574482183294015,1739502676.6604257,36.94996476173401,0.9646644450760363 +1739502676.6803155,36.96996474266052,46.28290212407345,1739502676.6803184,36.96996474266052,8.026617871857878,1739502676.6803224,36.96996474266052,62.37632748007546,1739502676.680326,36.96996474266052,43.479100465975264,1739502676.6803277,36.96996474266052,5.77128465359659,1739502676.68033,36.96996474266052,-2.464184245953796,1739502676.6803317,36.96996474266052,1.27281963558515,1739502676.6803336,36.96996474266052,0.6108,1739502676.6803353,36.96996474266052,0.9030611793933786,1739502676.6803374,36.96996474266052,0.0,1739502676.680339,36.96996474266052,-0.061603265682657726,1739502676.680341,36.96996474266052,3.4574482183294015,1739502676.6803432,36.96996474266052,0.9646644450760363 +1739502676.7002158,36.989964723587036,46.28290212407345,1739502676.7002194,36.989964723587036,8.026617871857878,1739502676.7002234,36.989964723587036,62.37632748007546,1739502676.700227,36.989964723587036,43.479100465975264,1739502676.700229,36.989964723587036,5.77128465359659,1739502676.700231,36.989964723587036,-2.464184245953796,1739502676.700233,36.989964723587036,1.27281963558515,1739502676.7002347,36.989964723587036,0.6108,1739502676.7002366,36.989964723587036,0.9030611793933786,1739502676.7002387,36.989964723587036,0.0,1739502676.7002404,36.989964723587036,-0.061603265682657726,1739502676.7002423,36.989964723587036,3.4574482183294015,1739502676.700244,36.989964723587036,0.9646644450760363 +1739502676.720341,37.00996470451355,46.28290212407345,1739502676.720344,37.00996470451355,8.026617871857878,1739502676.720348,37.00996470451355,62.37632748007546,1739502676.7203515,37.00996470451355,43.479100465975264,1739502676.7203534,37.00996470451355,5.77128465359659,1739502676.7203553,37.00996470451355,-2.464184245953796,1739502676.7203572,37.00996470451355,1.27281963558515,1739502676.7203588,37.00996470451355,0.6108,1739502676.7203608,37.00996470451355,0.9030611793933786,1739502676.7203627,37.00996470451355,0.0,1739502676.7203646,37.00996470451355,-0.061603265682657726,1739502676.7203662,37.00996470451355,3.4574482183294015,1739502676.7203681,37.00996470451355,0.9646644450760363 +1739502676.740374,37.02996468544006,46.18277605395547,1739502676.7403774,37.02996468544006,7.992502727895685,1739502676.7403817,37.02996468544006,62.39211689801623,1739502676.7403853,37.02996468544006,43.47832175690139,1739502676.7403867,37.02996468544006,5.769078311220603,1739502676.7403896,37.02996468544006,-2.4535001980798077,1739502676.7403915,37.02996468544006,1.1828577908331324,1739502676.7403932,37.02996468544006,0.6108,1739502676.740395,37.02996468544006,0.9704498997942981,1739502676.740397,37.02996468544006,0.0,1739502676.740399,37.02996468544006,0.04619831492752578,1739502676.7404006,37.02996468544006,3.4850499072719483,1739502676.7404025,37.02996468544006,0.9579396008950392 +1739502676.7602592,37.04996466636658,46.18277605395547,1739502676.7602625,37.04996466636658,7.992502727895685,1739502676.7602663,37.04996466636658,62.39211689801623,1739502676.7602696,37.04996466636658,43.47832175690139,1739502676.7602713,37.04996466636658,5.769078311220603,1739502676.760274,37.04996466636658,-2.4535001980798077,1739502676.7602756,37.04996466636658,1.1828577908331324,1739502676.7602775,37.04996466636658,0.6108,1739502676.760279,37.04996466636658,0.9704498997942981,1739502676.760281,37.04996466636658,0.0,1739502676.7602825,37.04996466636658,0.01251029889925892,1739502676.7602847,37.04996466636658,3.4850499072719483,1739502676.760286,37.04996466636658,0.9579396008950392 +1739502676.7803524,37.06996464729309,46.18277605395547,1739502676.7803557,37.06996464729309,7.992502727895685,1739502676.7803597,37.06996464729309,62.39211689801623,1739502676.7803633,37.06996464729309,43.47832175690139,1739502676.780365,37.06996464729309,5.769078311220603,1739502676.7803679,37.06996464729309,-2.4535001980798077,1739502676.78037,37.06996464729309,1.1828577908331324,1739502676.7803717,37.06996464729309,0.6108,1739502676.7803733,37.06996464729309,0.9704498997942981,1739502676.7803755,37.06996464729309,0.0,1739502676.7803771,37.06996464729309,0.01251029889925892,1739502676.7803788,37.06996464729309,3.4850499072719483,1739502676.7803807,37.06996464729309,0.9579396008950392 +1739502676.8002002,37.089964628219604,46.18277605395547,1739502676.8002076,37.089964628219604,7.992502727895685,1739502676.8002138,37.089964628219604,62.39211689801623,1739502676.8002176,37.089964628219604,43.47832175690139,1739502676.80022,37.089964628219604,5.769078311220603,1739502676.8002243,37.089964628219604,-2.4535001980798077,1739502676.800228,37.089964628219604,1.1828577908331324,1739502676.800232,37.089964628219604,0.6108,1739502676.800234,37.089964628219604,0.9704498997942981,1739502676.8002365,37.089964628219604,0.0,1739502676.8002398,37.089964628219604,0.01251029889925892,1739502676.8002508,37.089964628219604,3.4850499072719483,1739502676.800255,37.089964628219604,0.9579396008950392 +1739502676.820225,37.10996460914612,46.18277605395547,1739502676.8202283,37.10996460914612,7.992502727895685,1739502676.8202324,37.10996460914612,62.39211689801623,1739502676.8202357,37.10996460914612,43.47832175690139,1739502676.8202376,37.10996460914612,5.769078311220603,1739502676.8202398,37.10996460914612,-2.4535001980798077,1739502676.8202415,37.10996460914612,1.1828577908331324,1739502676.8202431,37.10996460914612,0.6108,1739502676.820245,37.10996460914612,0.9704498997942981,1739502676.8202467,37.10996460914612,0.0,1739502676.8202486,37.10996460914612,0.01251029889925892,1739502676.8202503,37.10996460914612,3.4850499072719483,1739502676.8202522,37.10996460914612,0.9579396008950392 +1739502676.840333,37.12996459007263,46.18277605395547,1739502676.8403368,37.12996459007263,7.992502727895685,1739502676.8403413,37.12996459007263,62.39211689801623,1739502676.8403451,37.12996459007263,43.47832175690139,1739502676.8403468,37.12996459007263,5.769078311220603,1739502676.8403494,37.12996459007263,-2.4535001980798077,1739502676.8403513,37.12996459007263,1.1828577908331324,1739502676.840353,37.12996459007263,0.6108,1739502676.8403544,37.12996459007263,0.9704498997942981,1739502676.8403566,37.12996459007263,0.0,1739502676.8403587,37.12996459007263,0.01251029889925892,1739502676.8403604,37.12996459007263,3.4850499072719483,1739502676.8403625,37.12996459007263,0.9579396008950392 +1739502676.8603387,37.149964570999146,46.08388899822574,1739502676.8603423,37.149964570999146,7.9557313872645405,1739502676.860346,37.149964570999146,62.56634479225655,1739502676.8603497,37.149964570999146,43.42345768697836,1739502676.8603516,37.149964570999146,5.599449342098141,1739502676.8603537,37.149964570999146,-2.416747568419496,1739502676.8603556,37.149964570999146,1.2312435903874428,1739502676.8603573,37.149964570999146,0.6108,1739502676.8603592,37.149964570999146,0.9336028545554426,1739502676.8603609,37.149964570999146,0.0,1739502676.8603628,37.149964570999146,-0.04405375308936546,1739502676.8603644,37.149964570999146,3.512651596214495,1739502676.8603663,37.149964570999146,0.959980329808892 +1739502676.8803277,37.16996455192566,46.08388899822574,1739502676.8803313,37.16996455192566,7.9557313872645405,1739502676.8803356,37.16996455192566,62.56634479225655,1739502676.8803394,37.16996455192566,43.42345768697836,1739502676.880341,37.16996455192566,5.599449342098141,1739502676.8803432,37.16996455192566,-2.416747568419496,1739502676.8803456,37.16996455192566,1.2312435903874428,1739502676.8803475,37.16996455192566,0.6108,1739502676.880349,37.16996455192566,0.9336028545554426,1739502676.8803513,37.16996455192566,0.0,1739502676.880353,37.16996455192566,-0.026377475253449467,1739502676.880355,37.16996455192566,3.512651596214495,1739502676.8803566,37.16996455192566,0.959980329808892 +1739502676.9002414,37.18996453285217,46.08388899822574,1739502676.9002452,37.18996453285217,7.9557313872645405,1739502676.9002488,37.18996453285217,62.56634479225655,1739502676.9002523,37.18996453285217,43.42345768697836,1739502676.9002542,37.18996453285217,5.599449342098141,1739502676.9002562,37.18996453285217,-2.416747568419496,1739502676.9002583,37.18996453285217,1.2312435903874428,1739502676.9002602,37.18996453285217,0.6108,1739502676.9002616,37.18996453285217,0.9336028545554426,1739502676.900264,37.18996453285217,0.0,1739502676.9002657,37.18996453285217,-0.026377475253449467,1739502676.9002676,37.18996453285217,3.512651596214495,1739502676.9002693,37.18996453285217,0.959980329808892 +1739502676.9202838,37.20996451377869,46.08388899822574,1739502676.9202878,37.20996451377869,7.9557313872645405,1739502676.9202914,37.20996451377869,62.56634479225655,1739502676.9202952,37.20996451377869,43.42345768697836,1739502676.920297,37.20996451377869,5.599449342098141,1739502676.920299,37.20996451377869,-2.416747568419496,1739502676.9203012,37.20996451377869,1.2312435903874428,1739502676.9203029,37.20996451377869,0.6108,1739502676.9203045,37.20996451377869,0.9336028545554426,1739502676.9203067,37.20996451377869,0.0,1739502676.9203086,37.20996451377869,-0.026377475253449467,1739502676.9203105,37.20996451377869,3.512651596214495,1739502676.9203124,37.20996451377869,0.959980329808892 +1739502676.9403033,37.2299644947052,46.08388899822574,1739502676.9403062,37.2299644947052,7.9557313872645405,1739502676.9403098,37.2299644947052,62.56634479225655,1739502676.9403126,37.2299644947052,43.42345768697836,1739502676.940314,37.2299644947052,5.599449342098141,1739502676.940316,37.2299644947052,-2.416747568419496,1739502676.9403176,37.2299644947052,1.2312435903874428,1739502676.940319,37.2299644947052,0.6108,1739502676.9403205,37.2299644947052,0.9336028545554426,1739502676.9403222,37.2299644947052,0.0,1739502676.9403236,37.2299644947052,-0.026377475253449467,1739502676.940325,37.2299644947052,3.512651596214495,1739502676.9403267,37.2299644947052,0.959980329808892 +1739502676.9596524,37.249964475631714,45.98609488572707,1739502676.9596543,37.249964475631714,7.9162626056146355,1739502676.9596574,37.249964475631714,62.69518662100846,1739502676.95966,37.249964475631714,43.389349328072605,1739502676.9596615,37.249964475631714,5.481163147267715,1739502676.9596632,37.249964475631714,-2.3883080643229615,1739502676.9596643,37.249964475631714,1.2361272064192776,1739502676.9596658,37.249964475631714,0.6108,1739502676.959667,37.249964475631714,0.9299624841601262,1739502676.9596684,37.249964475631714,0.0,1739502676.9596698,37.249964475631714,-0.02751522903594989,1739502676.9596713,37.249964475631714,3.540253285157042,1739502676.9596727,37.249964475631714,0.957122164905929 +1739502676.979701,37.26996445655823,45.98609488572707,1739502676.9797032,37.26996445655823,7.9162626056146355,1739502676.979706,37.26996445655823,62.69518662100846,1739502676.979709,37.26996445655823,43.389349328072605,1739502676.97971,37.26996445655823,5.481163147267715,1739502676.9797118,37.26996445655823,-2.3883080643229615,1739502676.9797132,37.26996445655823,1.2361272064192776,1739502676.9797146,37.26996445655823,0.6108,1739502676.9797158,37.26996445655823,0.9299624841601262,1739502676.9797175,37.26996445655823,0.0,1739502676.9797187,37.26996445655823,-0.027159680745802883,1739502676.97972,37.26996445655823,3.540253285157042,1739502676.9797215,37.26996445655823,0.957122164905929 +1739502676.9997678,37.28996443748474,45.98609488572707,1739502676.9997704,37.28996443748474,7.9162626056146355,1739502676.9997745,37.28996443748474,62.69518662100846,1739502676.9997773,37.28996443748474,43.389349328072605,1739502676.9997785,37.28996443748474,5.481163147267715,1739502676.9997804,37.28996443748474,-2.3883080643229615,1739502676.9997816,37.28996443748474,1.2361272064192776,1739502676.9997833,37.28996443748474,0.6108,1739502676.9997845,37.28996443748474,0.9299624841601262,1739502676.999786,37.28996443748474,0.0,1739502676.9997873,37.28996443748474,-0.027159680745802883,1739502676.9997888,37.28996443748474,3.540253285157042,1739502676.9997902,37.28996443748474,0.957122164905929 +1739502677.0195487,37.309964418411255,45.98609488572707,1739502677.0195508,37.309964418411255,7.9162626056146355,1739502677.019554,37.309964418411255,62.69518662100846,1739502677.0195563,37.309964418411255,43.389349328072605,1739502677.0195577,37.309964418411255,5.481163147267715,1739502677.0195591,37.309964418411255,-2.3883080643229615,1739502677.019561,37.309964418411255,1.2361272064192776,1739502677.0195622,37.309964418411255,0.6108,1739502677.0195634,37.309964418411255,0.9299624841601262,1739502677.0195649,37.309964418411255,0.0,1739502677.019566,37.309964418411255,-0.027159680745802883,1739502677.0195677,37.309964418411255,3.540253285157042,1739502677.019569,37.309964418411255,0.957122164905929 +1739502677.0396786,37.32996439933777,45.98609488572707,1739502677.039681,37.32996439933777,7.9162626056146355,1739502677.0396838,37.32996439933777,62.69518662100846,1739502677.0396864,37.32996439933777,43.389349328072605,1739502677.0396876,37.32996439933777,5.481163147267715,1739502677.0396893,37.32996439933777,-2.3883080643229615,1739502677.0396905,37.32996439933777,1.2361272064192776,1739502677.039692,37.32996439933777,0.6108,1739502677.039693,37.32996439933777,0.9299624841601262,1739502677.0396945,37.32996439933777,0.0,1739502677.039696,37.32996439933777,-0.027159680745802883,1739502677.0396972,37.32996439933777,3.540253285157042,1739502677.0396984,37.32996439933777,0.957122164905929 +1739502677.059578,37.34996438026428,45.98609488572707,1739502677.0595798,37.34996438026428,7.9162626056146355,1739502677.0595827,37.34996438026428,62.69518662100846,1739502677.059585,37.34996438026428,43.389349328072605,1739502677.0595865,37.34996438026428,5.481163147267715,1739502677.0595882,37.34996438026428,-2.3883080643229615,1739502677.0595894,37.34996438026428,1.2361272064192776,1739502677.0595908,37.34996438026428,0.6108,1739502677.059592,37.34996438026428,0.9299624841601262,1739502677.0595934,37.34996438026428,0.0,1739502677.059595,37.34996438026428,-0.027159680745802883,1739502677.0595963,37.34996438026428,3.540253285157042,1739502677.0595975,37.34996438026428,0.957122164905929 +1739502677.0797997,37.369964361190796,45.88972796501033,1739502677.0798018,37.369964361190796,7.874241008266301,1739502677.0798047,37.369964361190796,62.860767112777395,1739502677.079807,37.369964361190796,43.348748081030486,1739502677.0798082,37.369964361190796,5.3268053038643135,1739502677.0798101,37.369964361190796,-2.354925761872872,1739502677.0798113,37.369964361190796,1.2688646942390691,1739502677.0798125,37.369964361190796,0.6108,1739502677.079814,37.369964361190796,0.9059229474531123,1739502677.0798154,37.369964361190796,0.0,1739502677.0798168,37.369964361190796,-0.057785452156010615,1739502677.079818,37.369964361190796,3.5678549740995886,1739502677.0798192,37.369964361190796,0.954137839768485 +1739502677.0997696,37.38996434211731,45.88972796501033,1739502677.0997722,37.38996434211731,7.874241008266301,1739502677.0997753,37.38996434211731,62.860767112777395,1739502677.0997777,37.38996434211731,43.348748081030486,1739502677.0997791,37.38996434211731,5.3268053038643135,1739502677.0997808,37.38996434211731,-2.354925761872872,1739502677.0997822,37.38996434211731,1.2688646942390691,1739502677.0997834,37.38996434211731,0.6108,1739502677.0997846,37.38996434211731,0.9059229474531123,1739502677.0997863,37.38996434211731,0.0,1739502677.0997872,37.38996434211731,-0.04821489231537268,1739502677.0997891,37.38996434211731,3.5678549740995886,1739502677.09979,37.38996434211731,0.954137839768485 +1739502677.1195667,37.40996432304382,45.88972796501033,1739502677.1195686,37.40996432304382,7.874241008266301,1739502677.1195712,37.40996432304382,62.860767112777395,1739502677.1195738,37.40996432304382,43.348748081030486,1739502677.1195755,37.40996432304382,5.3268053038643135,1739502677.1195772,37.40996432304382,-2.354925761872872,1739502677.1195784,37.40996432304382,1.2688646942390691,1739502677.1195796,37.40996432304382,0.6108,1739502677.1195807,37.40996432304382,0.9059229474531123,1739502677.1195822,37.40996432304382,0.0,1739502677.1195836,37.40996432304382,-0.04821489231537268,1739502677.1195848,37.40996432304382,3.5678549740995886,1739502677.119586,37.40996432304382,0.954137839768485 +1739502677.1401262,37.42996430397034,45.88972796501033,1739502677.1401289,37.42996430397034,7.874241008266301,1739502677.1401322,37.42996430397034,62.860767112777395,1739502677.1401355,37.42996430397034,43.348748081030486,1739502677.140137,37.42996430397034,5.3268053038643135,1739502677.140139,37.42996430397034,-2.354925761872872,1739502677.1401405,37.42996430397034,1.2688646942390691,1739502677.140142,37.42996430397034,0.6108,1739502677.1401436,37.42996430397034,0.9059229474531123,1739502677.1401453,37.42996430397034,0.0,1739502677.140147,37.42996430397034,-0.04821489231537268,1739502677.1401484,37.42996430397034,3.5678549740995886,1739502677.14015,37.42996430397034,0.954137839768485 +1739502677.159864,37.44996428489685,45.88972796501033,1739502677.1598666,37.44996428489685,7.874241008266301,1739502677.15987,37.44996428489685,62.860767112777395,1739502677.159873,37.44996428489685,43.348748081030486,1739502677.159875,37.44996428489685,5.3268053038643135,1739502677.1598766,37.44996428489685,-2.354925761872872,1739502677.1598783,37.44996428489685,1.2688646942390691,1739502677.1598802,37.44996428489685,0.6108,1739502677.1598814,37.44996428489685,0.9059229474531123,1739502677.1598833,37.44996428489685,0.0,1739502677.1598847,37.44996428489685,-0.04821489231537268,1739502677.1598866,37.44996428489685,3.5678549740995886,1739502677.159888,37.44996428489685,0.954137839768485 +1739502677.180181,37.469964265823364,45.794953885458895,1739502677.180184,37.469964265823364,7.829762577743626,1739502677.1801875,37.469964265823364,62.94891159316861,1739502677.1801908,37.469964265823364,43.33141842798152,1739502677.1801922,37.469964265823364,5.251154557357217,1739502677.1801944,37.469964265823364,-2.333376299651488,1739502677.180196,37.469964265823364,1.237432439340549,1739502677.1801977,37.469964265823364,0.6108,1739502677.1801994,37.469964265823364,0.9289919368445353,1739502677.1802013,37.469964265823364,0.0,1739502677.1802025,37.469964265823364,-0.007002524481241959,1739502677.1802044,37.469964265823364,3.5954566630421354,1739502677.180206,37.469964265823364,0.9488733347179905 +1739502677.1998608,37.48996424674988,45.794953885458895,1739502677.199863,37.48996424674988,7.829762577743626,1739502677.1998663,37.48996424674988,62.94891159316861,1739502677.1998694,37.48996424674988,43.33141842798152,1739502677.199871,37.48996424674988,5.251154557357217,1739502677.1998732,37.48996424674988,-2.333376299651488,1739502677.1998749,37.48996424674988,1.237432439340549,1739502677.1998763,37.48996424674988,0.6108,1739502677.199878,37.48996424674988,0.9289919368445353,1739502677.1998796,37.48996424674988,0.0,1739502677.199881,37.48996424674988,-0.01988139787345522,1739502677.1998825,37.48996424674988,3.5954566630421354,1739502677.199884,37.48996424674988,0.9488733347179905 +1739502677.2199578,37.50996422767639,45.794953885458895,1739502677.2199602,37.50996422767639,7.829762577743626,1739502677.2199636,37.50996422767639,62.94891159316861,1739502677.2199667,37.50996422767639,43.33141842798152,1739502677.2199683,37.50996422767639,5.251154557357217,1739502677.21997,37.50996422767639,-2.333376299651488,1739502677.2199717,37.50996422767639,1.237432439340549,1739502677.219973,37.50996422767639,0.6108,1739502677.2199748,37.50996422767639,0.9289919368445353,1739502677.2199762,37.50996422767639,0.0,1739502677.2199776,37.50996422767639,-0.01988139787345522,1739502677.2199793,37.50996422767639,3.5954566630421354,1739502677.219981,37.50996422767639,0.9488733347179905 +1739502677.2401152,37.529964208602905,45.794953885458895,1739502677.2401183,37.529964208602905,7.829762577743626,1739502677.2401216,37.529964208602905,62.94891159316861,1739502677.240125,37.529964208602905,43.33141842798152,1739502677.2401264,37.529964208602905,5.251154557357217,1739502677.2401285,37.529964208602905,-2.333376299651488,1739502677.24013,37.529964208602905,1.237432439340549,1739502677.2401316,37.529964208602905,0.6108,1739502677.240133,37.529964208602905,0.9289919368445353,1739502677.240135,37.529964208602905,0.0,1739502677.2401364,37.529964208602905,-0.01988139787345522,1739502677.240138,37.529964208602905,3.5954566630421354,1739502677.2401397,37.529964208602905,0.9488733347179905 +1739502677.2598574,37.54996418952942,45.794953885458895,1739502677.25986,37.54996418952942,7.829762577743626,1739502677.2598634,37.54996418952942,62.94891159316861,1739502677.2598665,37.54996418952942,43.33141842798152,1739502677.259868,37.54996418952942,5.251154557357217,1739502677.2598698,37.54996418952942,-2.333376299651488,1739502677.2598715,37.54996418952942,1.237432439340549,1739502677.259873,37.54996418952942,0.6108,1739502677.2598743,37.54996418952942,0.9289919368445353,1739502677.259876,37.54996418952942,0.0,1739502677.2598777,37.54996418952942,-0.01988139787345522,1739502677.259879,37.54996418952942,3.5954566630421354,1739502677.2598808,37.54996418952942,0.9488733347179905 +1739502677.2801123,37.56996417045593,45.794953885458895,1739502677.2801151,37.56996417045593,7.829762577743626,1739502677.2801187,37.56996417045593,62.94891159316861,1739502677.280122,37.56996417045593,43.33141842798152,1739502677.2801237,37.56996417045593,5.251154557357217,1739502677.2801254,37.56996417045593,-2.333376299651488,1739502677.2801273,37.56996417045593,1.237432439340549,1739502677.2801287,37.56996417045593,0.6108,1739502677.2801304,37.56996417045593,0.9289919368445353,1739502677.280132,37.56996417045593,0.0,1739502677.2801337,37.56996417045593,-0.01988139787345522,1739502677.2801356,37.56996417045593,3.5954566630421354,1739502677.2801373,37.56996417045593,0.9488733347179905 +1739502677.2999742,37.589964151382446,45.70180478487369,1739502677.2999766,37.589964151382446,7.782866474232145,1739502677.29998,37.589964151382446,63.03877323825347,1739502677.299983,37.589964151382446,43.313209495600745,1739502677.2999847,37.589964151382446,5.167092170988236,1739502677.2999866,37.589964151382446,-2.3108295056600836,1739502677.2999883,37.589964151382446,1.2122978911748021,1739502677.2999897,37.589964151382446,0.6108,1739502677.2999914,37.589964151382446,0.9478608397019519,1739502677.299993,37.589964151382446,0.0,1739502677.2999945,37.589964151382446,0.010362154629471567,1739502677.299996,37.589964151382446,3.623058351984682,1739502677.2999973,37.589964151382446,0.9469498014262797 +1739502677.3199475,37.60996413230896,45.70180478487369,1739502677.3199506,37.60996413230896,7.782866474232145,1739502677.319954,37.60996413230896,63.03877323825347,1739502677.319957,37.60996413230896,43.313209495600745,1739502677.3199584,37.60996413230896,5.167092170988236,1739502677.3199604,37.60996413230896,-2.3108295056600836,1739502677.319962,37.60996413230896,1.2122978911748021,1739502677.3199637,37.60996413230896,0.6108,1739502677.319965,37.60996413230896,0.9478608397019519,1739502677.3199668,37.60996413230896,0.0,1739502677.3199682,37.60996413230896,0.0009110382756721824,1739502677.31997,37.60996413230896,3.623058351984682,1739502677.3199716,37.60996413230896,0.9469498014262797 +1739502677.3401675,37.629964113235474,45.70180478487369,1739502677.3401704,37.629964113235474,7.782866474232145,1739502677.3401742,37.629964113235474,63.03877323825347,1739502677.3401778,37.629964113235474,43.313209495600745,1739502677.3401794,37.629964113235474,5.167092170988236,1739502677.3401816,37.629964113235474,-2.3108295056600836,1739502677.340183,37.629964113235474,1.2122978911748021,1739502677.340185,37.629964113235474,0.6108,1739502677.3401864,37.629964113235474,0.9478608397019519,1739502677.3401883,37.629964113235474,0.0,1739502677.3401897,37.629964113235474,0.0009110382756721824,1739502677.3401916,37.629964113235474,3.623058351984682,1739502677.340193,37.629964113235474,0.9469498014262797 +1739502677.3598816,37.64996409416199,45.70180478487369,1739502677.3598845,37.64996409416199,7.782866474232145,1739502677.3598876,37.64996409416199,63.03877323825347,1739502677.3598907,37.64996409416199,43.313209495600745,1739502677.3598921,37.64996409416199,5.167092170988236,1739502677.3598943,37.64996409416199,-2.3108295056600836,1739502677.3598957,37.64996409416199,1.2122978911748021,1739502677.3598974,37.64996409416199,0.6108,1739502677.3598988,37.64996409416199,0.9478608397019519,1739502677.3599007,37.64996409416199,0.0,1739502677.3599021,37.64996409416199,0.0009110382756721824,1739502677.3599038,37.64996409416199,3.623058351984682,1739502677.3599052,37.64996409416199,0.9469498014262797 +1739502677.3800929,37.6699640750885,45.70180478487369,1739502677.380096,37.6699640750885,7.782866474232145,1739502677.3800993,37.6699640750885,63.03877323825347,1739502677.3801024,37.6699640750885,43.313209495600745,1739502677.3801038,37.6699640750885,5.167092170988236,1739502677.3801057,37.6699640750885,-2.3108295056600836,1739502677.3801074,37.6699640750885,1.2122978911748021,1739502677.380109,37.6699640750885,0.6108,1739502677.3801105,37.6699640750885,0.9478608397019519,1739502677.3801124,37.6699640750885,0.0,1739502677.3801136,37.6699640750885,0.0009110382756721824,1739502677.3801155,37.6699640750885,3.623058351984682,1739502677.380117,37.6699640750885,0.9469498014262797 +1739502677.4003246,37.689964056015015,45.61009698857563,1739502677.4003272,37.689964056015015,7.733476951042066,1739502677.4003305,37.689964056015015,63.20649040184432,1739502677.4003336,37.689964056015015,43.28071436478042,1739502677.400335,37.689964056015015,5.002388161727871,1739502677.4003372,37.689964056015015,-2.276979424613886,1739502677.4003386,37.689964056015015,1.24952997333673,1739502677.4003403,37.689964056015015,0.6108,1739502677.4003415,37.689964056015015,0.9200444942482262,1739502677.4003432,37.689964056015015,0.0,1739502677.4003448,37.689964056015015,-0.03966927116711755,1739502677.4003463,37.689964056015015,3.650660040927229,1739502677.400348,37.689964056015015,0.9470324103999277 +1739502677.420406,37.70996403694153,45.61009698857563,1739502677.4204087,37.70996403694153,7.733476951042066,1739502677.420412,37.70996403694153,63.20649040184432,1739502677.4204152,37.70996403694153,43.28071436478042,1739502677.4204168,37.70996403694153,5.002388161727871,1739502677.420419,37.70996403694153,-2.276979424613886,1739502677.4204204,37.70996403694153,1.24952997333673,1739502677.420422,37.70996403694153,0.6108,1739502677.4204235,37.70996403694153,0.9200444942482262,1739502677.4204252,37.70996403694153,0.0,1739502677.4204266,37.70996403694153,-0.026987916151701485,1739502677.4204283,37.70996403694153,3.650660040927229,1739502677.4204297,37.70996403694153,0.9470324103999277 +1739502677.440139,37.72996401786804,45.61009698857563,1739502677.4401422,37.72996401786804,7.733476951042066,1739502677.440146,37.72996401786804,63.20649040184432,1739502677.440149,37.72996401786804,43.28071436478042,1739502677.4401505,37.72996401786804,5.002388161727871,1739502677.440153,37.72996401786804,-2.276979424613886,1739502677.4401543,37.72996401786804,1.24952997333673,1739502677.440156,37.72996401786804,0.6108,1739502677.4401572,37.72996401786804,0.9200444942482262,1739502677.440159,37.72996401786804,0.0,1739502677.4401605,37.72996401786804,-0.026987916151701485,1739502677.4401627,37.72996401786804,3.650660040927229,1739502677.4401639,37.72996401786804,0.9470324103999277 +1739502677.4598315,37.749963998794556,45.61009698857563,1739502677.459834,37.749963998794556,7.733476951042066,1739502677.4598374,37.749963998794556,63.20649040184432,1739502677.4598405,37.749963998794556,43.28071436478042,1739502677.4598422,37.749963998794556,5.002388161727871,1739502677.459844,37.749963998794556,-2.276979424613886,1739502677.4598455,37.749963998794556,1.24952997333673,1739502677.4598472,37.749963998794556,0.6108,1739502677.4598484,37.749963998794556,0.9200444942482262,1739502677.4598503,37.749963998794556,0.0,1739502677.4598517,37.749963998794556,-0.026987916151701485,1739502677.4598536,37.749963998794556,3.650660040927229,1739502677.459855,37.749963998794556,0.9470324103999277 +1739502677.4802566,37.76996397972107,45.61009698857563,1739502677.4802597,37.76996397972107,7.733476951042066,1739502677.4802632,37.76996397972107,63.20649040184432,1739502677.4802663,37.76996397972107,43.28071436478042,1739502677.4802682,37.76996397972107,5.002388161727871,1739502677.4802701,37.76996397972107,-2.276979424613886,1739502677.4802718,37.76996397972107,1.24952997333673,1739502677.4802735,37.76996397972107,0.6108,1739502677.480275,37.76996397972107,0.9200444942482262,1739502677.4802768,37.76996397972107,0.0,1739502677.480278,37.76996397972107,-0.026987916151701485,1739502677.48028,37.76996397972107,3.650660040927229,1739502677.4802814,37.76996397972107,0.9470324103999277 +1739502677.4998257,37.78996396064758,45.61009698857563,1739502677.4998279,37.78996396064758,7.733476951042066,1739502677.4998312,37.78996396064758,63.20649040184432,1739502677.4998343,37.78996396064758,43.28071436478042,1739502677.499836,37.78996396064758,5.002388161727871,1739502677.4998376,37.78996396064758,-2.276979424613886,1739502677.4998393,37.78996396064758,1.24952997333673,1739502677.4998407,37.78996396064758,0.6108,1739502677.4998424,37.78996396064758,0.9200444942482262,1739502677.4998438,37.78996396064758,0.0,1739502677.4998453,37.78996396064758,-0.026987916151701485,1739502677.499847,37.78996396064758,3.650660040927229,1739502677.4998484,37.78996396064758,0.9470324103999277 +1739502677.5199118,37.8099639415741,45.519928516168946,1739502677.5199142,37.8099639415741,7.68165745952173,1739502677.5199175,37.8099639415741,63.23935091550466,1739502677.5199206,37.8099639415741,43.27566783834843,1739502677.5199223,37.8099639415741,4.976434597220501,1739502677.5199242,37.8099639415741,-2.2633289810494537,1739502677.5199256,37.8099639415741,1.1774760449222392,1739502677.519927,37.8099639415741,0.6108,1739502677.5199287,37.8099639415741,0.9746370788838833,1739502677.5199301,37.8099639415741,0.0,1739502677.5199316,37.8099639415741,0.05708922586142293,1739502677.5199332,37.8099639415741,3.6782617298697757,1739502677.5199347,37.8099639415741,0.9438219771282199 +1739502677.5402641,37.82996392250061,45.519928516168946,1739502677.5402687,37.82996392250061,7.68165745952173,1739502677.5402727,37.82996392250061,63.23935091550466,1739502677.5402763,37.82996392250061,43.27566783834843,1739502677.540278,37.82996392250061,4.976434597220501,1739502677.5402803,37.82996392250061,-2.2633289810494537,1739502677.540282,37.82996392250061,1.1774760449222392,1739502677.540284,37.82996392250061,0.6108,1739502677.5402856,37.82996392250061,0.9746370788838833,1739502677.5402877,37.82996392250061,0.0,1739502677.5402892,37.82996392250061,0.030815101755663377,1739502677.5402913,37.82996392250061,3.6782617298697757,1739502677.5402932,37.82996392250061,0.9438219771282199 +1739502677.5603395,37.849963903427124,45.519928516168946,1739502677.5603428,37.849963903427124,7.68165745952173,1739502677.5603464,37.849963903427124,63.23935091550466,1739502677.56035,37.849963903427124,43.27566783834843,1739502677.5603514,37.849963903427124,4.976434597220501,1739502677.560354,37.849963903427124,-2.2633289810494537,1739502677.5603561,37.849963903427124,1.1774760449222392,1739502677.5603576,37.849963903427124,0.6108,1739502677.5603595,37.849963903427124,0.9746370788838833,1739502677.5603611,37.849963903427124,0.0,1739502677.560363,37.849963903427124,0.030815101755663377,1739502677.5603647,37.849963903427124,3.6782617298697757,1739502677.5603666,37.849963903427124,0.9438219771282199 +1739502677.5804234,37.86996388435364,45.519928516168946,1739502677.5804267,37.86996388435364,7.68165745952173,1739502677.5804305,37.86996388435364,63.23935091550466,1739502677.580434,37.86996388435364,43.27566783834843,1739502677.580436,37.86996388435364,4.976434597220501,1739502677.580438,37.86996388435364,-2.2633289810494537,1739502677.5804398,37.86996388435364,1.1774760449222392,1739502677.5804417,37.86996388435364,0.6108,1739502677.5804434,37.86996388435364,0.9746370788838833,1739502677.5804455,37.86996388435364,0.0,1739502677.580447,37.86996388435364,0.030815101755663377,1739502677.5804489,37.86996388435364,3.6782617298697757,1739502677.5804508,37.86996388435364,0.9438219771282199 +1739502677.6001403,37.88996386528015,45.519928516168946,1739502677.6001437,37.88996386528015,7.68165745952173,1739502677.6001475,37.88996386528015,63.23935091550466,1739502677.6001508,37.88996386528015,43.27566783834843,1739502677.6001527,37.88996386528015,4.976434597220501,1739502677.6001549,37.88996386528015,-2.2633289810494537,1739502677.6001568,37.88996386528015,1.1774760449222392,1739502677.6001582,37.88996386528015,0.6108,1739502677.6001596,37.88996386528015,0.9746370788838833,1739502677.6001618,37.88996386528015,0.0,1739502677.6001632,37.88996386528015,0.030815101755663377,1739502677.6001651,37.88996386528015,3.6782617298697757,1739502677.6001668,37.88996386528015,0.9438219771282199 +1739502677.620377,37.909963846206665,45.43124648190866,1739502677.6203804,37.909963846206665,7.627380671245348,1739502677.6203842,37.909963846206665,63.447489784512214,1739502677.620388,37.909963846206665,43.23603616667843,1739502677.62039,37.909963846206665,4.765328857203361,1739502677.6203918,37.909963846206665,-2.2250926004304383,1739502677.6203938,37.909963846206665,1.2443751912192806,1739502677.6203954,37.909963846206665,0.6108,1739502677.620397,37.909963846206665,0.9238464312479788,1739502677.6203988,37.909963846206665,0.0,1739502677.6204007,37.909963846206665,-0.047903766700485725,1739502677.6204023,37.909963846206665,3.7058634188123225,1739502677.620404,37.909963846206665,0.9471505354271224 +1739502677.6402447,37.92996382713318,45.43124648190866,1739502677.6402483,37.92996382713318,7.627380671245348,1739502677.6402524,37.92996382713318,63.447489784512214,1739502677.6402557,37.92996382713318,43.23603616667843,1739502677.6402578,37.92996382713318,4.765328857203361,1739502677.6402597,37.92996382713318,-2.2250926004304383,1739502677.6402617,37.92996382713318,1.2443751912192806,1739502677.640263,37.92996382713318,0.6108,1739502677.6402647,37.92996382713318,0.9238464312479788,1739502677.6402667,37.92996382713318,0.0,1739502677.6402683,37.92996382713318,-0.023304104179143525,1739502677.64027,37.92996382713318,3.7058634188123225,1739502677.640272,37.92996382713318,0.9471505354271224 +1739502677.6603105,37.94996380805969,45.43124648190866,1739502677.660314,37.94996380805969,7.627380671245348,1739502677.6603177,37.94996380805969,63.447489784512214,1739502677.660321,37.94996380805969,43.23603616667843,1739502677.660323,37.94996380805969,4.765328857203361,1739502677.6603248,37.94996380805969,-2.2250926004304383,1739502677.6603265,37.94996380805969,1.2443751912192806,1739502677.6603281,37.94996380805969,0.6108,1739502677.6603298,37.94996380805969,0.9238464312479788,1739502677.6603317,37.94996380805969,0.0,1739502677.6603334,37.94996380805969,-0.023304104179143525,1739502677.660335,37.94996380805969,3.7058634188123225,1739502677.660337,37.94996380805969,0.9471505354271224 +1739502677.680254,37.969963788986206,45.43124648190866,1739502677.680257,37.969963788986206,7.627380671245348,1739502677.6802611,37.969963788986206,63.447489784512214,1739502677.6802647,37.969963788986206,43.23603616667843,1739502677.6802664,37.969963788986206,4.765328857203361,1739502677.6802685,37.969963788986206,-2.2250926004304383,1739502677.680271,37.969963788986206,1.2443751912192806,1739502677.6802726,37.969963788986206,0.6108,1739502677.6802742,37.969963788986206,0.9238464312479788,1739502677.6802764,37.969963788986206,0.0,1739502677.680278,37.969963788986206,-0.023304104179143525,1739502677.6802797,37.969963788986206,3.7058634188123225,1739502677.6802819,37.969963788986206,0.9471505354271224 +1739502677.7003586,37.98996376991272,45.43124648190866,1739502677.700362,37.98996376991272,7.627380671245348,1739502677.7003658,37.98996376991272,63.447489784512214,1739502677.7003694,37.98996376991272,43.23603616667843,1739502677.7003713,37.98996376991272,4.765328857203361,1739502677.7003736,37.98996376991272,-2.2250926004304383,1739502677.7003756,37.98996376991272,1.2443751912192806,1739502677.7003772,37.98996376991272,0.6108,1739502677.700379,37.98996376991272,0.9238464312479788,1739502677.700381,37.98996376991272,0.0,1739502677.7003825,37.98996376991272,-0.023304104179143525,1739502677.7003841,37.98996376991272,3.7058634188123225,1739502677.700386,37.98996376991272,0.9471505354271224 +1739502677.7204614,38.00996375083923,45.43124648190866,1739502677.7204645,38.00996375083923,7.627380671245348,1739502677.720468,38.00996375083923,63.447489784512214,1739502677.7204714,38.00996375083923,43.23603616667843,1739502677.720473,38.00996375083923,4.765328857203361,1739502677.7204752,38.00996375083923,-2.2250926004304383,1739502677.7204769,38.00996375083923,1.2443751912192806,1739502677.7204788,38.00996375083923,0.6108,1739502677.7204802,38.00996375083923,0.9238464312479788,1739502677.7204823,38.00996375083923,0.0,1739502677.7204838,38.00996375083923,-0.023304104179143525,1739502677.7204857,38.00996375083923,3.7058634188123225,1739502677.720487,38.00996375083923,0.9471505354271224 +1739502677.7403598,38.02996373176575,45.3440656423518,1739502677.7403626,38.02996373176575,7.5706591912697245,1739502677.7403662,38.02996373176575,63.54991490345318,1739502677.74037,38.02996373176575,43.21861586850282,1739502677.7403717,38.02996373176575,4.670582636092972,1739502677.740374,38.02996373176575,-2.2032596476551403,1739502677.7403755,38.02996373176575,1.220943855097649,1739502677.740378,38.02996373176575,0.6108,1739502677.7403796,38.02996373176575,0.9413273246647823,1739502677.7403817,38.02996373176575,0.0,1739502677.7403831,38.02996373176575,0.006549447143333295,1739502677.7403855,38.02996373176575,3.7334651077548693,1739502677.740387,38.02996373176575,0.94410711842645 +1739502677.760317,38.04996371269226,45.3440656423518,1739502677.7603207,38.04996371269226,7.5706591912697245,1739502677.7603242,38.04996371269226,63.54991490345318,1739502677.760328,38.04996371269226,43.21861586850282,1739502677.7603295,38.04996371269226,4.670582636092972,1739502677.7603319,38.04996371269226,-2.2032596476551403,1739502677.7603335,38.04996371269226,1.220943855097649,1739502677.7603352,38.04996371269226,0.6108,1739502677.7603369,38.04996371269226,0.9413273246647823,1739502677.7603388,38.04996371269226,0.0,1739502677.7603405,38.04996371269226,-0.0027797937616677038,1739502677.7603421,38.04996371269226,3.7334651077548693,1739502677.7603443,38.04996371269226,0.94410711842645 +1739502677.7805278,38.069963693618774,45.3440656423518,1739502677.7805312,38.069963693618774,7.5706591912697245,1739502677.7805352,38.069963693618774,63.54991490345318,1739502677.7805386,38.069963693618774,43.21861586850282,1739502677.7805405,38.069963693618774,4.670582636092972,1739502677.780543,38.069963693618774,-2.2032596476551403,1739502677.7805448,38.069963693618774,1.220943855097649,1739502677.7805467,38.069963693618774,0.6108,1739502677.7805483,38.069963693618774,0.9413273246647823,1739502677.7805505,38.069963693618774,0.0,1739502677.7805521,38.069963693618774,-0.0027797937616677038,1739502677.780554,38.069963693618774,3.7334651077548693,1739502677.7805557,38.069963693618774,0.94410711842645 +1739502677.8003547,38.08996367454529,45.3440656423518,1739502677.8003578,38.08996367454529,7.5706591912697245,1739502677.8003614,38.08996367454529,63.54991490345318,1739502677.800365,38.08996367454529,43.21861586850282,1739502677.8003669,38.08996367454529,4.670582636092972,1739502677.8003688,38.08996367454529,-2.2032596476551403,1739502677.8003707,38.08996367454529,1.220943855097649,1739502677.8003724,38.08996367454529,0.6108,1739502677.800374,38.08996367454529,0.9413273246647823,1739502677.8003762,38.08996367454529,0.0,1739502677.8003776,38.08996367454529,-0.0027797937616677038,1739502677.8003793,38.08996367454529,3.7334651077548693,1739502677.8003812,38.08996367454529,0.94410711842645 +1739502677.8203034,38.1099636554718,45.3440656423518,1739502677.820307,38.1099636554718,7.5706591912697245,1739502677.8203106,38.1099636554718,63.54991490345318,1739502677.820314,38.1099636554718,43.21861586850282,1739502677.8203156,38.1099636554718,4.670582636092972,1739502677.820318,38.1099636554718,-2.2032596476551403,1739502677.8203197,38.1099636554718,1.220943855097649,1739502677.8203213,38.1099636554718,0.6108,1739502677.8203228,38.1099636554718,0.9413273246647823,1739502677.820325,38.1099636554718,0.0,1739502677.8203263,38.1099636554718,-0.0027797937616677038,1739502677.8203282,38.1099636554718,3.7334651077548693,1739502677.82033,38.1099636554718,0.94410711842645 +1739502677.8403723,38.129963636398315,45.25863187194749,1739502677.840376,38.129963636398315,7.51165499189019,1739502677.8403795,38.129963636398315,63.63700024849922,1739502677.840383,38.129963636398315,43.2029795266888,1739502677.8403847,38.129963636398315,4.585567806254605,1739502677.8403873,38.129963636398315,-2.1832155864961202,1739502677.840389,38.129963636398315,1.188846694152971,1739502677.8403907,38.129963636398315,0.6108,1739502677.8403924,38.129963636398315,0.9658114757950209,1739502677.8403943,38.129963636398315,0.0,1739502677.840396,38.129963636398315,0.03330041067586707,1739502677.8403978,38.129963636398315,3.761066796697416,1739502677.8403995,38.129963636398315,0.9437861363983963 +1739502677.860163,38.14996361732483,45.25863187194749,1739502677.8601663,38.14996361732483,7.51165499189019,1739502677.8601701,38.14996361732483,63.63700024849922,1739502677.860174,38.14996361732483,43.2029795266888,1739502677.8601754,38.14996361732483,4.585567806254605,1739502677.860178,38.14996361732483,-2.1832155864961202,1739502677.8601797,38.14996361732483,1.188846694152971,1739502677.8601816,38.14996361732483,0.6108,1739502677.860183,38.14996361732483,0.9658114757950209,1739502677.860185,38.14996361732483,0.0,1739502677.8601866,38.14996361732483,0.022025339396624655,1739502677.8601885,38.14996361732483,3.761066796697416,1739502677.86019,38.14996361732483,0.9437861363983963 +1739502677.8802657,38.16996359825134,45.25863187194749,1739502677.8802693,38.16996359825134,7.51165499189019,1739502677.8802736,38.16996359825134,63.63700024849922,1739502677.8802774,38.16996359825134,43.2029795266888,1739502677.8802795,38.16996359825134,4.585567806254605,1739502677.880282,38.16996359825134,-2.1832155864961202,1739502677.8802836,38.16996359825134,1.188846694152971,1739502677.8802855,38.16996359825134,0.6108,1739502677.880287,38.16996359825134,0.9658114757950209,1739502677.880289,38.16996359825134,0.0,1739502677.8802907,38.16996359825134,0.022025339396624655,1739502677.8802931,38.16996359825134,3.761066796697416,1739502677.8802953,38.16996359825134,0.9437861363983963 +1739502677.9001458,38.189963579177856,45.25863187194749,1739502677.9001482,38.189963579177856,7.51165499189019,1739502677.9001517,38.189963579177856,63.63700024849922,1739502677.900155,38.189963579177856,43.2029795266888,1739502677.900157,38.189963579177856,4.585567806254605,1739502677.900159,38.189963579177856,-2.1832155864961202,1739502677.900161,38.189963579177856,1.188846694152971,1739502677.9001625,38.189963579177856,0.6108,1739502677.9001641,38.189963579177856,0.9658114757950209,1739502677.900166,38.189963579177856,0.0,1739502677.9001677,38.189963579177856,0.022025339396624655,1739502677.9001696,38.189963579177856,3.761066796697416,1739502677.9001713,38.189963579177856,0.9437861363983963 +1739502677.920103,38.20996356010437,45.25863187194749,1739502677.9201062,38.20996356010437,7.51165499189019,1739502677.9201097,38.20996356010437,63.63700024849922,1739502677.920113,38.20996356010437,43.2029795266888,1739502677.920115,38.20996356010437,4.585567806254605,1739502677.920117,38.20996356010437,-2.1832155864961202,1739502677.920119,38.20996356010437,1.188846694152971,1739502677.9201207,38.20996356010437,0.6108,1739502677.9201224,38.20996356010437,0.9658114757950209,1739502677.920124,38.20996356010437,0.0,1739502677.9201257,38.20996356010437,0.022025339396624655,1739502677.9201274,38.20996356010437,3.761066796697416,1739502677.9201293,38.20996356010437,0.9437861363983963 +1739502677.9403713,38.229963541030884,45.25863187194749,1739502677.9403753,38.229963541030884,7.51165499189019,1739502677.9403796,38.229963541030884,63.63700024849922,1739502677.9403834,38.229963541030884,43.2029795266888,1739502677.940386,38.229963541030884,4.585567806254605,1739502677.940389,38.229963541030884,-2.1832155864961202,1739502677.9403906,38.229963541030884,1.188846694152971,1739502677.9403925,38.229963541030884,0.6108,1739502677.940394,38.229963541030884,0.9658114757950209,1739502677.940396,38.229963541030884,0.0,1739502677.940398,38.229963541030884,0.022025339396624655,1739502677.9404,38.229963541030884,3.761066796697416,1739502677.9404016,38.229963541030884,0.9437861363983963 +1739502677.960295,38.2499635219574,45.17475729688604,1739502677.9602978,38.2499635219574,7.450240078634442,1739502677.9603016,38.2499635219574,63.722903347143486,1739502677.960305,38.2499635219574,43.18661249414505,1739502677.9603066,38.2499635219574,4.4958687177977845,1739502677.9603088,38.2499635219574,-2.163136463349281,1739502677.9603107,38.2499635219574,1.158580463251147,1739502677.9603126,38.2499635219574,0.6108,1739502677.960314,38.2499635219574,0.9894820656855484,1739502677.9603162,38.2499635219574,0.0,1739502677.9603176,38.2499635219574,0.05261749555495872,1739502677.9603195,38.2499635219574,3.788668485639963,1739502677.9603212,38.2499635219574,0.9464246251981296 +1739502677.9802713,38.26996350288391,45.17475729688604,1739502677.9802742,38.26996350288391,7.450240078634442,1739502677.9802778,38.26996350288391,63.722903347143486,1739502677.980281,38.26996350288391,43.18661249414505,1739502677.9802828,38.26996350288391,4.4958687177977845,1739502677.980285,38.26996350288391,-2.163136463349281,1739502677.9802868,38.26996350288391,1.158580463251147,1739502677.9802883,38.26996350288391,0.6108,1739502677.9802897,38.26996350288391,0.9894820656855484,1739502677.9802918,38.26996350288391,0.0,1739502677.9802938,38.26996350288391,0.043057440487418774,1739502677.9802952,38.26996350288391,3.788668485639963,1739502677.9802969,38.26996350288391,0.9464246251981296 +1739502678.0001473,38.289963483810425,45.17475729688604,1739502678.0001504,38.289963483810425,7.450240078634442,1739502678.0001543,38.289963483810425,63.722903347143486,1739502678.0001576,38.289963483810425,43.18661249414505,1739502678.0001597,38.289963483810425,4.4958687177977845,1739502678.0001621,38.289963483810425,-2.163136463349281,1739502678.0001638,38.289963483810425,1.158580463251147,1739502678.0001655,38.289963483810425,0.6108,1739502678.0001671,38.289963483810425,0.9894820656855484,1739502678.0001693,38.289963483810425,0.0,1739502678.0001707,38.289963483810425,0.043057440487418774,1739502678.0001726,38.289963483810425,3.788668485639963,1739502678.0001743,38.289963483810425,0.9464246251981296 +1739502678.0200748,38.30996346473694,45.17475729688604,1739502678.0200775,38.30996346473694,7.450240078634442,1739502678.0200815,38.30996346473694,63.722903347143486,1739502678.0200846,38.30996346473694,43.18661249414505,1739502678.0200868,38.30996346473694,4.4958687177977845,1739502678.020089,38.30996346473694,-2.163136463349281,1739502678.0200903,38.30996346473694,1.158580463251147,1739502678.0200922,38.30996346473694,0.6108,1739502678.0200937,38.30996346473694,0.9894820656855484,1739502678.0200958,38.30996346473694,0.0,1739502678.0200975,38.30996346473694,0.043057440487418774,1739502678.0200994,38.30996346473694,3.788668485639963,1739502678.020101,38.30996346473694,0.9464246251981296 +1739502678.0402737,38.32996344566345,45.17475729688604,1739502678.040277,38.32996344566345,7.450240078634442,1739502678.0402813,38.32996344566345,63.722903347143486,1739502678.0402846,38.32996344566345,43.18661249414505,1739502678.0402865,38.32996344566345,4.4958687177977845,1739502678.0402887,38.32996344566345,-2.163136463349281,1739502678.040291,38.32996344566345,1.158580463251147,1739502678.040293,38.32996344566345,0.6108,1739502678.040295,38.32996344566345,0.9894820656855484,1739502678.040297,38.32996344566345,0.0,1739502678.0402985,38.32996344566345,0.043057440487418774,1739502678.0403008,38.32996344566345,3.788668485639963,1739502678.0403025,38.32996344566345,0.9464246251981296 +1739502678.0602403,38.349963426589966,45.09231017500992,1739502678.0602431,38.349963426589966,7.386300847951501,1739502678.060247,38.349963426589966,63.88557802433963,1739502678.0602505,38.349963426589966,43.155131387764214,1739502678.0602522,38.349963426589966,4.326700734742485,1739502678.0602546,38.349963426589966,-2.1352332222091572,1739502678.0602562,38.349963426589966,1.1792174550468124,1739502678.0602584,38.349963426589966,0.6108,1739502678.0602598,38.349963426589966,0.9732802299339691,1739502678.0602617,38.349963426589966,0.0,1739502678.0602634,38.349963426589966,0.012655598583144648,1739502678.0602653,38.349963426589966,3.8162701745825096,1739502678.0602667,38.349963426589966,0.951124049526672 +1739502678.0802968,38.36996340751648,45.09231017500992,1739502678.0803003,38.36996340751648,7.386300847951501,1739502678.0803049,38.36996340751648,63.88557802433963,1739502678.0803087,38.36996340751648,43.155131387764214,1739502678.0803106,38.36996340751648,4.326700734742485,1739502678.0803125,38.36996340751648,-2.1352332222091572,1739502678.0803146,38.36996340751648,1.1792174550468124,1739502678.080316,38.36996340751648,0.6108,1739502678.080318,38.36996340751648,0.9732802299339691,1739502678.0803204,38.36996340751648,0.0,1739502678.080322,38.36996340751648,0.022156180407297166,1739502678.080324,38.36996340751648,3.8162701745825096,1739502678.0803256,38.36996340751648,0.951124049526672 +1739502678.1001272,38.38996338844299,45.09231017500992,1739502678.1001306,38.38996338844299,7.386300847951501,1739502678.1001341,38.38996338844299,63.88557802433963,1739502678.1001377,38.38996338844299,43.155131387764214,1739502678.1001396,38.38996338844299,4.326700734742485,1739502678.1001415,38.38996338844299,-2.1352332222091572,1739502678.1001437,38.38996338844299,1.1792174550468124,1739502678.100145,38.38996338844299,0.6108,1739502678.100147,38.38996338844299,0.9732802299339691,1739502678.1001487,38.38996338844299,0.0,1739502678.1001503,38.38996338844299,0.022156180407297166,1739502678.100152,38.38996338844299,3.8162701745825096,1739502678.100154,38.38996338844299,0.951124049526672 +1739502678.1202908,38.40996336936951,45.09231017500992,1739502678.120294,38.40996336936951,7.386300847951501,1739502678.1202977,38.40996336936951,63.88557802433963,1739502678.120301,38.40996336936951,43.155131387764214,1739502678.1203032,38.40996336936951,4.326700734742485,1739502678.1203048,38.40996336936951,-2.1352332222091572,1739502678.1203067,38.40996336936951,1.1792174550468124,1739502678.1203084,38.40996336936951,0.6108,1739502678.12031,38.40996336936951,0.9732802299339691,1739502678.120312,38.40996336936951,0.0,1739502678.1203136,38.40996336936951,0.022156180407297166,1739502678.1203153,38.40996336936951,3.8162701745825096,1739502678.1203172,38.40996336936951,0.951124049526672 +1739502678.1403484,38.42996335029602,45.09231017500992,1739502678.1403518,38.42996335029602,7.386300847951501,1739502678.1403556,38.42996335029602,63.88557802433963,1739502678.1403592,38.42996335029602,43.155131387764214,1739502678.1403606,38.42996335029602,4.326700734742485,1739502678.140363,38.42996335029602,-2.1352332222091572,1739502678.140365,38.42996335029602,1.1792174550468124,1739502678.1403668,38.42996335029602,0.6108,1739502678.1403682,38.42996335029602,0.9732802299339691,1739502678.1403701,38.42996335029602,0.0,1739502678.140372,38.42996335029602,0.022156180407297166,1739502678.1403737,38.42996335029602,3.8162701745825096,1739502678.140376,38.42996335029602,0.951124049526672 +1739502678.160153,38.449963331222534,45.09231017500992,1739502678.1601555,38.449963331222534,7.386300847951501,1739502678.1601596,38.449963331222534,63.88557802433963,1739502678.160163,38.449963331222534,43.155131387764214,1739502678.1601646,38.449963331222534,4.326700734742485,1739502678.1601667,38.449963331222534,-2.1352332222091572,1739502678.1601684,38.449963331222534,1.1792174550468124,1739502678.1601703,38.449963331222534,0.6108,1739502678.1601717,38.449963331222534,0.9732802299339691,1739502678.160174,38.449963331222534,0.0,1739502678.1601753,38.449963331222534,0.022156180407297166,1739502678.1601772,38.449963331222534,3.8162701745825096,1739502678.160179,38.449963331222534,0.951124049526672 +1739502678.1804016,38.46996331214905,45.0113578503601,1739502678.1804051,38.46996331214905,7.319864198681184,1739502678.1804092,38.46996331214905,63.97192679032444,1739502678.180413,38.46996331214905,43.138155229383514,1739502678.1804147,38.46996331214905,4.237473348754041,1739502678.1804173,38.46996331214905,-2.1168663483946544,1739502678.180419,38.46996331214905,1.142997985961035,1739502678.1804209,38.46996331214905,0.6108,1739502678.1804223,38.46996331214905,1.0018941347164771,1739502678.1804245,38.46996331214905,0.0,1739502678.1804264,38.46996331214905,0.06051821275000889,1739502678.180428,38.46996331214905,3.8438718635250564,1739502678.18043,38.46996331214905,0.9533640649336047 +1739502678.200309,38.48996329307556,45.0113578503601,1739502678.2003126,38.48996329307556,7.319864198681184,1739502678.200317,38.48996329307556,63.97192679032444,1739502678.2003205,38.48996329307556,43.138155229383514,1739502678.2003229,38.48996329307556,4.237473348754041,1739502678.200325,38.48996329307556,-2.1168663483946544,1739502678.200327,38.48996329307556,1.142997985961035,1739502678.2003286,38.48996329307556,0.6108,1739502678.2003303,38.48996329307556,1.0018941347164771,1739502678.2003326,38.48996329307556,0.0,1739502678.2003343,38.48996329307556,0.04853006978287244,1739502678.2003362,38.48996329307556,3.8438718635250564,1739502678.200338,38.48996329307556,0.9533640649336047 +1739502678.2202928,38.509963274002075,45.0113578503601,1739502678.2202957,38.509963274002075,7.319864198681184,1739502678.2202995,38.509963274002075,63.97192679032444,1739502678.2203028,38.509963274002075,43.138155229383514,1739502678.2203045,38.509963274002075,4.237473348754041,1739502678.2203064,38.509963274002075,-2.1168663483946544,1739502678.2203083,38.509963274002075,1.142997985961035,1739502678.2203097,38.509963274002075,0.6108,1739502678.2203116,38.509963274002075,1.0018941347164771,1739502678.2203133,38.509963274002075,0.0,1739502678.220315,38.509963274002075,0.04853006978287244,1739502678.2203166,38.509963274002075,3.8438718635250564,1739502678.2203183,38.509963274002075,0.9533640649336047 +1739502678.2404375,38.52996325492859,45.0113578503601,1739502678.2404408,38.52996325492859,7.319864198681184,1739502678.2404451,38.52996325492859,63.97192679032444,1739502678.2404487,38.52996325492859,43.138155229383514,1739502678.2404506,38.52996325492859,4.237473348754041,1739502678.2404528,38.52996325492859,-2.1168663483946544,1739502678.2404544,38.52996325492859,1.142997985961035,1739502678.2404563,38.52996325492859,0.6108,1739502678.2404587,38.52996325492859,1.0018941347164771,1739502678.2404616,38.52996325492859,0.0,1739502678.240463,38.52996325492859,0.04853006978287244,1739502678.240465,38.52996325492859,3.8438718635250564,1739502678.2404666,38.52996325492859,0.9533640649336047 +1739502678.260136,38.5499632358551,45.0113578503601,1739502678.260139,38.5499632358551,7.319864198681184,1739502678.2601428,38.5499632358551,63.97192679032444,1739502678.2601461,38.5499632358551,43.138155229383514,1739502678.2601483,38.5499632358551,4.237473348754041,1739502678.2601502,38.5499632358551,-2.1168663483946544,1739502678.2601523,38.5499632358551,1.142997985961035,1739502678.2601538,38.5499632358551,0.6108,1739502678.2601554,38.5499632358551,1.0018941347164771,1739502678.260158,38.5499632358551,0.0,1739502678.2601595,38.5499632358551,0.04853006978287244,1739502678.2601612,38.5499632358551,3.8438718635250564,1739502678.260163,38.5499632358551,0.9533640649336047 +1739502678.2802935,38.569963216781616,44.93196604184634,1739502678.2802966,38.569963216781616,7.250953946143964,1739502678.280301,38.569963216781616,64.07675856528029,1739502678.2803044,38.569963216781616,43.115919819353536,1739502678.280306,38.569963216781616,4.124214074186892,1739502678.2803087,38.569963216781616,-2.0969870744405075,1739502678.2803106,38.569963216781616,1.1193099430767386,1739502678.2803125,38.569963216781616,0.6108,1739502678.2803147,38.569963216781616,1.0210615050855307,1739502678.2803164,38.569963216781616,0.0,1739502678.280318,38.569963216781616,0.06870835727131995,1739502678.28032,38.569963216781616,3.871473552467603,1739502678.2803218,38.569963216781616,0.9586588667887022 +1739502678.300298,38.58996319770813,44.93196604184634,1739502678.300301,38.58996319770813,7.250953946143964,1739502678.3003047,38.58996319770813,64.07675856528029,1739502678.3003085,38.58996319770813,43.115919819353536,1739502678.3003104,38.58996319770813,4.124214074186892,1739502678.3003123,38.58996319770813,-2.0969870744405075,1739502678.3003142,38.58996319770813,1.1193099430767386,1739502678.3003159,38.58996319770813,0.6108,1739502678.3003175,38.58996319770813,1.0210615050855307,1739502678.3003194,38.58996319770813,0.0,1739502678.300321,38.58996319770813,0.06240263829682857,1739502678.300323,38.58996319770813,3.871473552467603,1739502678.300325,38.58996319770813,0.9586588667887022 +1739502678.3201733,38.609963178634644,44.93196604184634,1739502678.3201768,38.609963178634644,7.250953946143964,1739502678.3201807,38.609963178634644,64.07675856528029,1739502678.320184,38.609963178634644,43.115919819353536,1739502678.320186,38.609963178634644,4.124214074186892,1739502678.320188,38.609963178634644,-2.0969870744405075,1739502678.32019,38.609963178634644,1.1193099430767386,1739502678.3201919,38.609963178634644,0.6108,1739502678.3201933,38.609963178634644,1.0210615050855307,1739502678.320195,38.609963178634644,0.0,1739502678.3201966,38.609963178634644,0.06240263829682857,1739502678.3201983,38.609963178634644,3.871473552467603,1739502678.3202002,38.609963178634644,0.9586588667887022 +1739502678.3403125,38.62996315956116,44.93196604184634,1739502678.340316,38.62996315956116,7.250953946143964,1739502678.34032,38.62996315956116,64.07675856528029,1739502678.3403237,38.62996315956116,43.115919819353536,1739502678.3403254,38.62996315956116,4.124214074186892,1739502678.3403277,38.62996315956116,-2.0969870744405075,1739502678.3403294,38.62996315956116,1.1193099430767386,1739502678.3403313,38.62996315956116,0.6108,1739502678.340333,38.62996315956116,1.0210615050855307,1739502678.3403351,38.62996315956116,0.0,1739502678.3403368,38.62996315956116,0.06240263829682857,1739502678.340339,38.62996315956116,3.871473552467603,1739502678.3403409,38.62996315956116,0.9586588667887022 +1739502678.3601775,38.64996314048767,44.93196604184634,1739502678.3601809,38.64996314048767,7.250953946143964,1739502678.3601844,38.64996314048767,64.07675856528029,1739502678.3601875,38.64996314048767,43.115919819353536,1739502678.3601894,38.64996314048767,4.124214074186892,1739502678.3601916,38.64996314048767,-2.0969870744405075,1739502678.3601933,38.64996314048767,1.1193099430767386,1739502678.3601952,38.64996314048767,0.6108,1739502678.3601966,38.64996314048767,1.0210615050855307,1739502678.3601987,38.64996314048767,0.0,1739502678.3602002,38.64996314048767,0.06240263829682857,1739502678.360202,38.64996314048767,3.871473552467603,1739502678.3602037,38.64996314048767,0.9586588667887022 +1739502678.3803084,38.669963121414185,44.93196604184634,1739502678.380312,38.669963121414185,7.250953946143964,1739502678.3803163,38.669963121414185,64.07675856528029,1739502678.38032,38.669963121414185,43.115919819353536,1739502678.3803217,38.669963121414185,4.124214074186892,1739502678.380324,38.669963121414185,-2.0969870744405075,1739502678.3803256,38.669963121414185,1.1193099430767386,1739502678.3803277,38.669963121414185,0.6108,1739502678.3803291,38.669963121414185,1.0210615050855307,1739502678.3803313,38.669963121414185,0.0,1739502678.380333,38.669963121414185,0.06240263829682857,1739502678.3803349,38.669963121414185,3.871473552467603,1739502678.380337,38.669963121414185,0.9586588667887022 +1739502678.4003775,38.6899631023407,44.854007976535186,1739502678.4003808,38.6899631023407,7.179421154030781,1739502678.4003844,38.6899631023407,64.09210386662248,1739502678.400388,38.6899631023407,43.11027174211225,1739502678.40039,38.6899631023407,4.095487226659114,1739502678.4003918,38.6899631023407,-2.08540567923098,1739502678.4003937,38.6899631023407,1.0425760721607849,1739502678.4003952,38.6899631023407,0.6108,1739502678.4003968,38.6899631023407,1.0857053567374333,1739502678.4003987,38.6899631023407,0.0,1739502678.4004006,38.6899631023407,0.1462979086493505,1739502678.4004025,38.6899631023407,3.89907524141015,1739502678.4004042,38.6899631023407,0.9656247372626402 +1739502678.425017,38.70996308326721,44.854007976535186,1739502678.4250255,38.70996308326721,7.179421154030781,1739502678.425036,38.70996308326721,64.09210386662248,1739502678.425046,38.70996308326721,43.11027174211225,1739502678.425051,38.70996308326721,4.095487226659114,1739502678.4250572,38.70996308326721,-2.08540567923098,1739502678.4250624,38.70996308326721,1.0425760721607849,1739502678.4250672,38.70996308326721,0.6108,1739502678.4250717,38.70996308326721,1.0857053567374333,1739502678.4250772,38.70996308326721,0.0,1739502678.4250822,38.70996308326721,0.1200806194747931,1739502678.4250875,38.70996308326721,3.89907524141015,1739502678.4250927,38.70996308326721,0.9656247372626402 +1739502678.4421983,38.729963064193726,44.854007976535186,1739502678.442202,38.729963064193726,7.179421154030781,1739502678.4422064,38.729963064193726,64.09210386662248,1739502678.4422116,38.729963064193726,43.11027174211225,1739502678.4422145,38.729963064193726,4.095487226659114,1739502678.4422412,38.729963064193726,-2.08540567923098,1739502678.4422455,38.729963064193726,1.0425760721607849,1739502678.4422483,38.729963064193726,0.6108,1739502678.4422517,38.729963064193726,1.0857053567374333,1739502678.4422555,38.729963064193726,0.0,1739502678.4422586,38.729963064193726,0.1200806194747931,1739502678.4422622,38.729963064193726,3.89907524141015,1739502678.4422655,38.729963064193726,0.9656247372626402 +1739502678.461519,38.74996304512024,44.854007976535186,1739502678.4615223,38.74996304512024,7.179421154030781,1739502678.4615266,38.74996304512024,64.09210386662248,1739502678.4615316,38.74996304512024,43.11027174211225,1739502678.4615343,38.74996304512024,4.095487226659114,1739502678.461538,38.74996304512024,-2.08540567923098,1739502678.4615412,38.74996304512024,1.0425760721607849,1739502678.4615445,38.74996304512024,0.6108,1739502678.4615476,38.74996304512024,1.0857053567374333,1739502678.461551,38.74996304512024,0.0,1739502678.4615543,38.74996304512024,0.1200806194747931,1739502678.4615574,38.74996304512024,3.89907524141015,1739502678.4615607,38.74996304512024,0.9656247372626402 +1739502678.4812365,38.76996302604675,44.854007976535186,1739502678.481239,38.76996302604675,7.179421154030781,1739502678.481242,38.76996302604675,64.09210386662248,1739502678.4812443,38.76996302604675,43.11027174211225,1739502678.4812458,38.76996302604675,4.095487226659114,1739502678.4812474,38.76996302604675,-2.08540567923098,1739502678.4812489,38.76996302604675,1.0425760721607849,1739502678.48125,38.76996302604675,0.6108,1739502678.481251,38.76996302604675,1.0857053567374333,1739502678.4812524,38.76996302604675,0.0,1739502678.4812536,38.76996302604675,0.1200806194747931,1739502678.4812548,38.76996302604675,3.89907524141015,1739502678.4812565,38.76996302604675,0.9656247372626402 +1739502678.5046632,38.78996300697327,44.77729588381564,1739502678.5046678,38.78996300697327,7.105026885556137,1739502678.5046961,38.78996300697327,64.36909755025987,1739502678.5047019,38.78996300697327,43.04695361563633,1739502678.504705,38.78996300697327,3.7989709801651452,1739502678.5047085,38.78996300697327,-2.052976962829182,1739502678.5047119,38.78996300697327,1.1153155786375397,1739502678.5047154,38.78996300697327,0.6067548794964923,1739502678.5047188,38.78996300697327,1.024329517170102,1739502678.504722,38.78996300697327,0.0,1739502678.5047252,38.78996300697327,0.011742184732238523,1739502678.5047283,38.78996300697327,3.9266769303526967,1739502678.5047314,38.78996300697327,0.9787315493832339 +1739502678.5235138,38.80996298789978,44.77729588381564,1739502678.5235186,38.80996298789978,7.105026885556137,1739502678.5235233,38.80996298789978,64.36909755025987,1739502678.523529,38.80996298789978,43.04695361563633,1739502678.523532,38.80996298789978,3.7989709801651452,1739502678.5235357,38.80996298789978,-2.052976962829182,1739502678.5235388,38.80996298789978,1.1153155786375397,1739502678.5235417,38.80996298789978,0.6067548794964923,1739502678.523545,38.80996298789978,1.024329517170102,1739502678.5235484,38.80996298789978,0.0,1739502678.5235517,38.80996298789978,0.04559796778686798,1739502678.5235548,38.80996298789978,3.9266769303526967,1739502678.5235584,38.80996298789978,0.9787315493832339 +1739502678.541807,38.829962968826294,44.77729588381564,1739502678.541812,38.829962968826294,7.105026885556137,1739502678.5418172,38.829962968826294,64.36909755025987,1739502678.5418224,38.829962968826294,43.04695361563633,1739502678.5418262,38.829962968826294,3.7989709801651452,1739502678.54183,38.829962968826294,-2.052976962829182,1739502678.5418339,38.829962968826294,1.1153155786375397,1739502678.541837,38.829962968826294,0.6067548794964923,1739502678.54184,38.829962968826294,1.024329517170102,1739502678.541844,38.829962968826294,0.0,1739502678.5418472,38.829962968826294,0.04559796778686798,1739502678.5418506,38.829962968826294,3.9266769303526967,1739502678.5418544,38.829962968826294,0.9787315493832339 +1739502678.5618002,38.84996294975281,44.77729588381564,1739502678.5618033,38.84996294975281,7.105026885556137,1739502678.5618074,38.84996294975281,64.36909755025987,1739502678.5618122,38.84996294975281,43.04695361563633,1739502678.5618148,38.84996294975281,3.7989709801651452,1739502678.5618181,38.84996294975281,-2.052976962829182,1739502678.5618212,38.84996294975281,1.1153155786375397,1739502678.5618243,38.84996294975281,0.6067548794964923,1739502678.5618274,38.84996294975281,1.024329517170102,1739502678.5618303,38.84996294975281,0.0,1739502678.5618334,38.84996294975281,0.04559796778686798,1739502678.5618365,38.84996294975281,3.9266769303526967,1739502678.5618396,38.84996294975281,0.9787315493832339 +1739502678.5825083,38.86996293067932,44.77729588381564,1739502678.5825117,38.86996293067932,7.105026885556137,1739502678.582516,38.86996293067932,64.36909755025987,1739502678.5825205,38.86996293067932,43.04695361563633,1739502678.5825236,38.86996293067932,3.7989709801651452,1739502678.582527,38.86996293067932,-2.052976962829182,1739502678.58253,38.86996293067932,1.1153155786375397,1739502678.5825331,38.86996293067932,0.6067548794964923,1739502678.5825362,38.86996293067932,1.024329517170102,1739502678.5825396,38.86996293067932,0.0,1739502678.5825427,38.86996293067932,0.04559796778686798,1739502678.5825458,38.86996293067932,3.9266769303526967,1739502678.5825486,38.86996293067932,0.9787315493832339 +1739502678.6019874,38.889962911605835,44.77729588381564,1739502678.6019893,38.889962911605835,7.105026885556137,1739502678.6019921,38.889962911605835,64.36909755025987,1739502678.6019948,38.889962911605835,43.04695361563633,1739502678.601996,38.889962911605835,3.7989709801651452,1739502678.6019976,38.889962911605835,-2.052976962829182,1739502678.6019988,38.889962911605835,1.1153155786375397,1739502678.6019998,38.889962911605835,0.6067548794964923,1739502678.6020012,38.889962911605835,1.024329517170102,1739502678.6020024,38.889962911605835,0.0,1739502678.6020038,38.889962911605835,0.04559796778686798,1739502678.602005,38.889962911605835,3.9266769303526967,1739502678.6020064,38.889962911605835,0.9787315493832339 +1739502678.6217234,38.90996289253235,44.70197851453948,1739502678.621726,38.90996289253235,7.027842360976964,1739502678.6217287,38.90996289253235,64.45014451946166,1739502678.6217313,38.90996289253235,43.02768086163712,1739502678.6217327,38.90996289253235,3.7113675528959944,1739502678.6217341,38.90996289253235,-2.0383104798643155,1739502678.6217353,38.90996289253235,1.064475351710482,1739502678.6217365,38.90996289253235,0.5847848803623967,1739502678.6217377,38.90996289253235,1.0668500737588258,1739502678.6217391,38.90996289253235,0.0,1739502678.6217406,38.90996289253235,0.10115413095561036,1739502678.6217418,38.90996289253235,3.9542786192952435,1739502678.6217432,38.90996289253235,0.9830572551764108 +1739502678.6396658,38.92996287345886,44.70197851453948,1739502678.6396685,38.92996287345886,7.027842360976964,1739502678.6396718,38.92996287345886,64.45014451946166,1739502678.6396744,38.92996287345886,43.02768086163712,1739502678.6396759,38.92996287345886,3.7113675528959944,1739502678.6396782,38.92996287345886,-2.0383104798643155,1739502678.6396797,38.92996287345886,1.064475351710482,1739502678.639681,38.92996287345886,0.5847848803623967,1739502678.639682,38.92996287345886,1.0668500737588258,1739502678.6396835,38.92996287345886,0.0,1739502678.6396856,38.92996287345886,0.08379281858241494,1739502678.639687,38.92996287345886,3.9542786192952435,1739502678.6396885,38.92996287345886,0.9830572551764108 +1739502678.659717,38.949962854385376,44.70197851453948,1739502678.6597195,38.949962854385376,7.027842360976964,1739502678.6597223,38.949962854385376,64.45014451946166,1739502678.659725,38.949962854385376,43.02768086163712,1739502678.6597264,38.949962854385376,3.7113675528959944,1739502678.659728,38.949962854385376,-2.0383104798643155,1739502678.6597295,38.949962854385376,1.064475351710482,1739502678.6597307,38.949962854385376,0.5847848803623967,1739502678.6597319,38.949962854385376,1.0668500737588258,1739502678.6597333,38.949962854385376,0.0,1739502678.6597345,38.949962854385376,0.08379281858241494,1739502678.6597362,38.949962854385376,3.9542786192952435,1739502678.6597373,38.949962854385376,0.9830572551764108 +1739502678.679941,38.96996283531189,44.70197851453948,1739502678.6799433,38.96996283531189,7.027842360976964,1739502678.6799464,38.96996283531189,64.45014451946166,1739502678.6799493,38.96996283531189,43.02768086163712,1739502678.679951,38.96996283531189,3.7113675528959944,1739502678.6799524,38.96996283531189,-2.0383104798643155,1739502678.6799538,38.96996283531189,1.064475351710482,1739502678.6799555,38.96996283531189,0.5847848803623967,1739502678.6799564,38.96996283531189,1.0668500737588258,1739502678.6799583,38.96996283531189,0.0,1739502678.6799595,38.96996283531189,0.08379281858241494,1739502678.6799612,38.96996283531189,3.9542786192952435,1739502678.6799626,38.96996283531189,0.9830572551764108 +1739502678.6997433,38.9899628162384,44.70197851453948,1739502678.6997457,38.9899628162384,7.027842360976964,1739502678.6997485,38.9899628162384,64.45014451946166,1739502678.6997514,38.9899628162384,43.02768086163712,1739502678.6997528,38.9899628162384,3.7113675528959944,1739502678.6997547,38.9899628162384,-2.0383104798643155,1739502678.6997561,38.9899628162384,1.064475351710482,1739502678.6997576,38.9899628162384,0.5847848803623967,1739502678.6997588,38.9899628162384,1.0668500737588258,1739502678.6997604,38.9899628162384,0.0,1739502678.6997619,38.9899628162384,0.08379281858241494,1739502678.6997633,38.9899628162384,3.9542786192952435,1739502678.6997647,38.9899628162384,0.9830572551764108 +1739502678.719833,39.00996279716492,44.62831844111934,1739502678.7198353,39.00996279716492,6.948063643706952,1739502678.7198381,39.00996279716492,64.60117546488465,1739502678.7198408,39.00996279716492,42.98960237800876,1739502678.7198422,39.00996279716492,3.5463987354025424,1739502678.7198439,39.00996279716492,-2.0197290411962947,1739502678.7198453,39.00996279716492,1.0491829185441024,1739502678.719847,39.00996279716492,0.5586401962541434,1739502678.7198482,39.00996279716492,1.0799820245245575,1739502678.7198498,39.00996279716492,0.0,1739502678.719851,39.00996279716492,0.08958760615854328,1739502678.7198524,39.00996279716492,3.9818803082377903,1739502678.719854,39.00996279716492,0.9922052906708547 +1739502678.7400105,39.02996277809143,44.62831844111934,1739502678.7400136,39.02996277809143,6.948063643706952,1739502678.7400167,39.02996277809143,64.60117546488465,1739502678.7400196,39.02996277809143,42.98960237800876,1739502678.7400208,39.02996277809143,3.5463987354025424,1739502678.7400224,39.02996277809143,-2.0197290411962947,1739502678.740024,39.02996277809143,1.0491829185441024,1739502678.7400255,39.02996277809143,0.5586401962541434,1739502678.740027,39.02996277809143,1.0799820245245575,1739502678.7400284,39.02996277809143,0.0,1739502678.74003,39.02996277809143,0.08777673385370277,1739502678.7400315,39.02996277809143,3.9818803082377903,1739502678.740033,39.02996277809143,0.9922052906708547 +1739502678.7597136,39.049962759017944,44.62831844111934,1739502678.7597158,39.049962759017944,6.948063643706952,1739502678.7597187,39.049962759017944,64.60117546488465,1739502678.7597215,39.049962759017944,42.98960237800876,1739502678.759723,39.049962759017944,3.5463987354025424,1739502678.7597249,39.049962759017944,-2.0197290411962947,1739502678.759726,39.049962759017944,1.0491829185441024,1739502678.7597277,39.049962759017944,0.5586401962541434,1739502678.759729,39.049962759017944,1.0799820245245575,1739502678.7597306,39.049962759017944,0.0,1739502678.759732,39.049962759017944,0.08777673385370277,1739502678.7597332,39.049962759017944,3.9818803082377903,1739502678.7597349,39.049962759017944,0.9922052906708547 +1739502678.7799876,39.06996273994446,44.62831844111934,1739502678.7799904,39.06996273994446,6.948063643706952,1739502678.7799935,39.06996273994446,64.60117546488465,1739502678.7799969,39.06996273994446,42.98960237800876,1739502678.7799983,39.06996273994446,3.5463987354025424,1739502678.78,39.06996273994446,-2.0197290411962947,1739502678.7800016,39.06996273994446,1.0491829185441024,1739502678.780003,39.06996273994446,0.5586401962541434,1739502678.7800043,39.06996273994446,1.0799820245245575,1739502678.780006,39.06996273994446,0.0,1739502678.7800074,39.06996273994446,0.08777673385370277,1739502678.7800088,39.06996273994446,3.9818803082377903,1739502678.7800102,39.06996273994446,0.9922052906708547 +1739502678.7999284,39.08996272087097,44.62831844111934,1739502678.7999308,39.08996272087097,6.948063643706952,1739502678.799934,39.08996272087097,64.60117546488465,1739502678.7999372,39.08996272087097,42.98960237800876,1739502678.7999392,39.08996272087097,3.5463987354025424,1739502678.799941,39.08996272087097,-2.0197290411962947,1739502678.799943,39.08996272087097,1.0491829185441024,1739502678.7999446,39.08996272087097,0.5586401962541434,1739502678.7999463,39.08996272087097,1.0799820245245575,1739502678.799948,39.08996272087097,0.0,1739502678.79995,39.08996272087097,0.08777673385370277,1739502678.7999513,39.08996272087097,3.9818803082377903,1739502678.7999532,39.08996272087097,0.9922052906708547 +1739502678.8302166,39.109962701797485,44.62831844111934,1739502678.8302236,39.109962701797485,6.948063643706952,1739502678.8302329,39.109962701797485,64.60117546488465,1739502678.830243,39.109962701797485,42.98960237800876,1739502678.830249,39.109962701797485,3.5463987354025424,1739502678.8302565,39.109962701797485,-2.0197290411962947,1739502678.8302631,39.109962701797485,1.0491829185441024,1739502678.8302698,39.109962701797485,0.5586401962541434,1739502678.8302765,39.109962701797485,1.0799820245245575,1739502678.8302834,39.109962701797485,0.0,1739502678.83029,39.109962701797485,0.08777673385370277,1739502678.830297,39.109962701797485,3.9818803082377903,1739502678.830304,39.109962701797485,0.9922052906708547 +1739502678.8451955,39.129962682724,44.556203743968034,1739502678.8451993,39.129962682724,6.865498744781602,1739502678.8452048,39.129962682724,64.60949784918272,1739502678.8452108,39.129962682724,42.98272911043931,1739502678.8452141,39.129962682724,3.5196291669741404,1739502678.845219,39.129962682724,-2.0103814103267355,1739502678.845223,39.129962682724,0.9623903877435694,1739502678.8452268,39.129962682724,0.5349163829507128,1739502678.8452306,39.129962682724,1.157634179042974,1739502678.8452346,39.129962682724,0.0,1739502678.8452387,39.129962682724,0.1866777291380962,1739502678.845243,39.129962682724,4.009481997180338,1739502678.845247,39.129962682724,1.0018630311951846 +1739502678.864088,39.14996266365051,44.556203743968034,1739502678.8640916,39.14996266365051,6.865498744781602,1739502678.8640957,39.14996266365051,64.60949784918272,1739502678.8641005,39.14996266365051,42.98272911043931,1739502678.864103,39.14996266365051,3.5196291669741404,1739502678.8641064,39.14996266365051,-2.0103814103267355,1739502678.8641095,39.14996266365051,0.9623903877435694,1739502678.864113,39.14996266365051,0.5349163829507128,1739502678.8641162,39.14996266365051,1.157634179042974,1739502678.8641193,39.14996266365051,0.0,1739502678.8641224,39.14996266365051,0.15577114784778945,1739502678.8641257,39.14996266365051,4.009481997180338,1739502678.8641288,39.14996266365051,1.0018630311951846 +1739502678.883684,39.169962644577026,44.556203743968034,1739502678.8836873,39.169962644577026,6.865498744781602,1739502678.8836915,39.169962644577026,64.60949784918272,1739502678.883696,39.169962644577026,42.98272911043931,1739502678.8836987,39.169962644577026,3.5196291669741404,1739502678.8837023,39.169962644577026,-2.0103814103267355,1739502678.8837054,39.169962644577026,0.9623903877435694,1739502678.8837085,39.169962644577026,0.5349163829507128,1739502678.8837116,39.169962644577026,1.157634179042974,1739502678.8837147,39.169962644577026,0.0,1739502678.8837175,39.169962644577026,0.15577114784778945,1739502678.8837209,39.169962644577026,4.009481997180338,1739502678.883724,39.169962644577026,1.0018630311951846 +1739502678.9025915,39.18996262550354,44.556203743968034,1739502678.9025936,39.18996262550354,6.865498744781602,1739502678.902596,39.18996262550354,64.60949784918272,1739502678.9025986,39.18996262550354,42.98272911043931,1739502678.9026,39.18996262550354,3.5196291669741404,1739502678.9026015,39.18996262550354,-2.0103814103267355,1739502678.9026027,39.18996262550354,0.9623903877435694,1739502678.902604,39.18996262550354,0.5349163829507128,1739502678.902605,39.18996262550354,1.157634179042974,1739502678.9026065,39.18996262550354,0.0,1739502678.902608,39.18996262550354,0.15577114784778945,1739502678.902609,39.18996262550354,4.009481997180338,1739502678.9026105,39.18996262550354,1.0018630311951846 +1739502678.921822,39.209962606430054,44.556203743968034,1739502678.921824,39.209962606430054,6.865498744781602,1739502678.9218268,39.209962606430054,64.60949784918272,1739502678.9218295,39.209962606430054,42.98272911043931,1739502678.9218307,39.209962606430054,3.5196291669741404,1739502678.921832,39.209962606430054,-2.0103814103267355,1739502678.9218335,39.209962606430054,0.9623903877435694,1739502678.9218347,39.209962606430054,0.5349163829507128,1739502678.9218361,39.209962606430054,1.157634179042974,1739502678.9218373,39.209962606430054,0.0,1739502678.9218385,39.209962606430054,0.15577114784778945,1739502678.92184,39.209962606430054,4.009481997180338,1739502678.9218411,39.209962606430054,1.0018630311951846 +1739502678.9419553,39.22996258735657,44.48549491926457,1739502678.941958,39.22996258735657,6.779882060165891,1739502678.9419613,39.22996258735657,64.82418496013082,1739502678.9419637,39.22996258735657,42.91822290311661,1739502678.941965,39.22996258735657,3.2794469204240104,1739502678.9419668,39.22996258735657,-1.9917661972079124,1739502678.9419684,39.22996258735657,0.9649656367332045,1739502678.9419696,39.22996258735657,0.49916548171349484,1739502678.9419706,39.22996258735657,1.1552516770999997,1739502678.9419723,39.22996258735657,0.0,1739502678.9419734,39.22996258735657,0.1275676254129947,1739502678.941975,39.22996258735657,4.03708368612289,1739502678.9419765,39.22996258735657,1.0188704451474808 +1739502678.9615278,39.24996256828308,44.48549491926457,1739502678.96153,39.24996256828308,6.779882060165891,1739502678.9615326,39.24996256828308,64.82418496013082,1739502678.9615352,39.24996256828308,42.91822290311661,1739502678.9615364,39.24996256828308,3.2794469204240104,1739502678.9615386,39.24996256828308,-1.9917661972079124,1739502678.9615397,39.24996256828308,0.9649656367332045,1739502678.9615412,39.24996256828308,0.49916548171349484,1739502678.9615424,39.24996256828308,1.1552516770999997,1739502678.961544,39.24996256828308,0.0,1739502678.9615452,39.24996256828308,0.13638123195251883,1739502678.9615464,39.24996256828308,4.03708368612289,1739502678.961548,39.24996256828308,1.0188704451474808 +1739502678.9815943,39.269962549209595,44.48549491926457,1739502678.9815965,39.269962549209595,6.779882060165891,1739502678.9815993,39.269962549209595,64.82418496013082,1739502678.9816017,39.269962549209595,42.91822290311661,1739502678.9816031,39.269962549209595,3.2794469204240104,1739502678.9816048,39.269962549209595,-1.9917661972079124,1739502678.9816062,39.269962549209595,0.9649656367332045,1739502678.9816074,39.269962549209595,0.49916548171349484,1739502678.9816086,39.269962549209595,1.1552516770999997,1739502678.9816103,39.269962549209595,0.0,1739502678.9816115,39.269962549209595,0.13638123195251883,1739502678.9816127,39.269962549209595,4.03708368612289,1739502678.981614,39.269962549209595,1.0188704451474808 +1739502679.0018792,39.28996253013611,44.48549491926457,1739502679.0018816,39.28996253013611,6.779882060165891,1739502679.0018842,39.28996253013611,64.82418496013082,1739502679.001887,39.28996253013611,42.91822290311661,1739502679.0018883,39.28996253013611,3.2794469204240104,1739502679.00189,39.28996253013611,-1.9917661972079124,1739502679.0018914,39.28996253013611,0.9649656367332045,1739502679.0018926,39.28996253013611,0.49916548171349484,1739502679.001894,39.28996253013611,1.1552516770999997,1739502679.0018954,39.28996253013611,0.0,1739502679.0018966,39.28996253013611,0.13638123195251883,1739502679.001898,39.28996253013611,4.03708368612289,1739502679.0018995,39.28996253013611,1.0188704451474808 +1739502679.0215976,39.30996251106262,44.48549491926457,1739502679.0216,39.30996251106262,6.779882060165891,1739502679.021603,39.30996251106262,64.82418496013082,1739502679.021606,39.30996251106262,42.91822290311661,1739502679.0216074,39.30996251106262,3.2794469204240104,1739502679.0216093,39.30996251106262,-1.9917661972079124,1739502679.0216105,39.30996251106262,0.9649656367332045,1739502679.021612,39.30996251106262,0.49916548171349484,1739502679.0216134,39.30996251106262,1.1552516770999997,1739502679.0216148,39.30996251106262,0.0,1739502679.0216165,39.30996251106262,0.13638123195251883,1739502679.0216177,39.30996251106262,4.03708368612289,1739502679.021619,39.30996251106262,1.0188704451474808 +1739502679.0416667,39.329962491989136,44.48549491926457,1739502679.041669,39.329962491989136,6.779882060165891,1739502679.041672,39.329962491989136,64.82418496013082,1739502679.0416746,39.329962491989136,42.91822290311661,1739502679.041676,39.329962491989136,3.2794469204240104,1739502679.0416777,39.329962491989136,-1.9917661972079124,1739502679.0416791,39.329962491989136,0.9649656367332045,1739502679.0416806,39.329962491989136,0.49916548171349484,1739502679.0416818,39.329962491989136,1.1552516770999997,1739502679.0416834,39.329962491989136,0.0,1739502679.041685,39.329962491989136,0.13638123195251883,1739502679.0416863,39.329962491989136,4.03708368612289,1739502679.041688,39.329962491989136,1.0188704451474808 +1739502679.0615776,39.34996247291565,44.41607124987378,1739502679.0615797,39.34996247291565,6.690971206073019,1739502679.061583,39.34996247291565,64.97164985768009,1739502679.061586,39.34996247291565,42.86734013220335,1739502679.061587,39.34996247291565,3.109914001898209,1739502679.0615888,39.34996247291565,-1.9789844446220828,1739502679.0615902,39.34996247291565,0.9285096918474474,1739502679.0615919,39.34996247291565,0.4646945585883585,1739502679.061593,39.34996247291565,1.1894404404133723,1739502679.0615947,39.34996247291565,0.0,1739502679.061596,39.34996247291565,0.16462076339896553,1739502679.0615973,39.34996247291565,4.063913919626914,1739502679.061599,39.34996247291565,1.03364453637745 +1739502679.0815644,39.36996245384216,44.41607124987378,1739502679.0815668,39.36996245384216,6.690971206073019,1739502679.0815694,39.36996245384216,64.97164985768009,1739502679.0815725,39.36996245384216,42.86734013220335,1739502679.081574,39.36996245384216,3.109914001898209,1739502679.0815756,39.36996245384216,-1.9789844446220828,1739502679.0815773,39.36996245384216,0.9285096918474474,1739502679.0815785,39.36996245384216,0.4646945585883585,1739502679.0815797,39.36996245384216,1.1894404404133723,1739502679.0815814,39.36996245384216,0.0,1739502679.0815825,39.36996245384216,0.15579590403592225,1739502679.0815842,39.36996245384216,4.063913919626914,1739502679.0815854,39.36996245384216,1.03364453637745 +1739502679.1018207,39.38996243476868,44.41607124987378,1739502679.101823,39.38996243476868,6.690971206073019,1739502679.101826,39.38996243476868,64.97164985768009,1739502679.1018288,39.38996243476868,42.86734013220335,1739502679.1018305,39.38996243476868,3.109914001898209,1739502679.1018322,39.38996243476868,-1.9789844446220828,1739502679.1018336,39.38996243476868,0.9285096918474474,1739502679.101835,39.38996243476868,0.4646945585883585,1739502679.1018362,39.38996243476868,1.1894404404133723,1739502679.1018379,39.38996243476868,0.0,1739502679.101839,39.38996243476868,0.15579590403592225,1739502679.1018405,39.38996243476868,4.063913919626914,1739502679.1018422,39.38996243476868,1.03364453637745 +1739502679.1215293,39.40996241569519,44.41607124987378,1739502679.1215317,39.40996241569519,6.690971206073019,1739502679.1215343,39.40996241569519,64.97164985768009,1739502679.1215374,39.40996241569519,42.86734013220335,1739502679.1215389,39.40996241569519,3.109914001898209,1739502679.1215405,39.40996241569519,-1.9789844446220828,1739502679.1215422,39.40996241569519,0.9285096918474474,1739502679.1215436,39.40996241569519,0.4646945585883585,1739502679.121545,39.40996241569519,1.1894404404133723,1739502679.1215465,39.40996241569519,0.0,1739502679.1215477,39.40996241569519,0.15579590403592225,1739502679.1215491,39.40996241569519,4.063913919626914,1739502679.1215506,39.40996241569519,1.03364453637745 +1739502679.1416254,39.429962396621704,44.41607124987378,1739502679.1416276,39.429962396621704,6.690971206073019,1739502679.1416306,39.429962396621704,64.97164985768009,1739502679.1416335,39.429962396621704,42.86734013220335,1739502679.1416352,39.429962396621704,3.109914001898209,1739502679.1416366,39.429962396621704,-1.9789844446220828,1739502679.141638,39.429962396621704,0.9285096918474474,1739502679.1416395,39.429962396621704,0.4646945585883585,1739502679.1416407,39.429962396621704,1.1894404404133723,1739502679.1416426,39.429962396621704,0.0,1739502679.1416438,39.429962396621704,0.15579590403592225,1739502679.1416452,39.429962396621704,4.063913919626914,1739502679.1416469,39.429962396621704,1.03364453637745 +1739502679.1616364,39.44996237754822,44.34795274867498,1739502679.1616387,39.44996237754822,6.598878849228061,1739502679.1616414,39.44996237754822,65.11532788649832,1739502679.1616442,39.44996237754822,42.811584274066625,1739502679.1616457,39.44996237754822,2.9411070102468524,1739502679.1616473,39.44996237754822,-1.968448557477314,1739502679.161649,39.44996237754822,0.8875989975458408,1739502679.1616502,39.44996237754822,0.4301211469891629,1739502679.1616514,39.44996237754822,1.2290131543690526,1739502679.1616533,39.44996237754822,0.0,1739502679.1616545,39.44996237754822,0.18855718196866073,1739502679.1616561,39.44996237754822,4.089100089785886,1739502679.1616576,39.44996237754822,1.050693878466867 +1739502679.1816144,39.46996235847473,44.34795274867498,1739502679.1816168,39.46996235847473,6.598878849228061,1739502679.1816196,39.46996235847473,65.11532788649832,1739502679.1816227,39.46996235847473,42.811584274066625,1739502679.1816242,39.46996235847473,2.9411070102468524,1739502679.1816258,39.46996235847473,-1.968448557477314,1739502679.1816273,39.46996235847473,0.8875989975458408,1739502679.1816287,39.46996235847473,0.4301211469891629,1739502679.18163,39.46996235847473,1.2290131543690526,1739502679.181632,39.46996235847473,0.0,1739502679.1816332,39.46996235847473,0.17831927590218566,1739502679.1816351,39.46996235847473,4.089100089785886,1739502679.1816363,39.46996235847473,1.050693878466867 +1739502679.2016683,39.489962339401245,44.34795274867498,1739502679.2016706,39.489962339401245,6.598878849228061,1739502679.2016737,39.489962339401245,65.11532788649832,1739502679.2016766,39.489962339401245,42.811584274066625,1739502679.2016778,39.489962339401245,2.9411070102468524,1739502679.2016795,39.489962339401245,-1.968448557477314,1739502679.201681,39.489962339401245,0.8875989975458408,1739502679.2016823,39.489962339401245,0.4301211469891629,1739502679.2016838,39.489962339401245,1.2290131543690526,1739502679.2016854,39.489962339401245,0.0,1739502679.2016869,39.489962339401245,0.17831927590218566,1739502679.2016883,39.489962339401245,4.089100089785886,1739502679.2016895,39.489962339401245,1.050693878466867 +1739502679.228569,39.50996232032776,44.34795274867498,1739502679.2285786,39.50996232032776,6.598878849228061,1739502679.2285903,39.50996232032776,65.11532788649832,1739502679.2286007,39.50996232032776,42.811584274066625,1739502679.2286067,39.50996232032776,2.9411070102468524,1739502679.228613,39.50996232032776,-1.968448557477314,1739502679.228618,39.50996232032776,0.8875989975458408,1739502679.228623,39.50996232032776,0.4301211469891629,1739502679.2286282,39.50996232032776,1.2290131543690526,1739502679.2286346,39.50996232032776,0.0,1739502679.2286396,39.50996232032776,0.17831927590218566,1739502679.2286453,39.50996232032776,4.089100089785886,1739502679.2286506,39.50996232032776,1.050693878466867 +1739502679.250117,39.52996230125427,44.34795274867498,1739502679.2501266,39.52996230125427,6.598878849228061,1739502679.250138,39.52996230125427,65.11532788649832,1739502679.2501533,39.52996230125427,42.811584274066625,1739502679.250157,39.52996230125427,2.9411070102468524,1739502679.250161,39.52996230125427,-1.968448557477314,1739502679.2501643,39.52996230125427,0.8875989975458408,1739502679.250167,39.52996230125427,0.4301211469891629,1739502679.2501695,39.52996230125427,1.2290131543690526,1739502679.2501726,39.52996230125427,0.0,1739502679.2501752,39.52996230125427,0.17831927590218566,1739502679.250178,39.52996230125427,4.089100089785886,1739502679.250181,39.52996230125427,1.050693878466867 +1739502679.2658246,39.549962282180786,44.34795274867498,1739502679.2658281,39.549962282180786,6.598878849228061,1739502679.2658327,39.549962282180786,65.11532788649832,1739502679.265837,39.549962282180786,42.811584274066625,1739502679.265839,39.549962282180786,2.9411070102468524,1739502679.2658417,39.549962282180786,-1.968448557477314,1739502679.2658436,39.549962282180786,0.8875989975458408,1739502679.2658458,39.549962282180786,0.4301211469891629,1739502679.265848,39.549962282180786,1.2290131543690526,1739502679.26585,39.549962282180786,0.0,1739502679.2658522,39.549962282180786,0.17831927590218566,1739502679.2658544,39.549962282180786,4.089100089785886,1739502679.2658565,39.549962282180786,1.050693878466867 +1739502679.2883806,39.5699622631073,44.280945116959785,1739502679.2883844,39.5699622631073,6.503490517874942,1739502679.28839,39.5699622631073,65.2064656209765,1739502679.2883961,39.5699622631073,42.76916038414714,1739502679.2883995,39.5699622631073,2.8175578031019493,1739502679.288404,39.5699622631073,-1.960021832343225,1739502679.2884078,39.5699622631073,0.8321370375206173,1739502679.2884119,39.5699622631073,0.4002651553896347,1739502679.2884157,39.5699622631073,1.2847717830791086,1739502679.2884197,39.5699622631073,0.0,1739502679.288424,39.5699622631073,0.23069711285818284,1739502679.288428,39.5699622631073,4.112739951095686,1739502679.2884321,39.5699622631073,1.0704427550014275 +1739502679.3071697,39.58996224403381,44.280945116959785,1739502679.307174,39.58996224403381,6.503490517874942,1739502679.3071785,39.58996224403381,65.2064656209765,1739502679.3071835,39.58996224403381,42.76916038414714,1739502679.3071861,39.58996224403381,2.8175578031019493,1739502679.3071902,39.58996224403381,-1.960021832343225,1739502679.3071935,39.58996224403381,0.8321370375206173,1739502679.3071966,39.58996224403381,0.4002651553896347,1739502679.3072,39.58996224403381,1.2847717830791086,1739502679.3072035,39.58996224403381,0.0,1739502679.3072069,39.58996224403381,0.21432902807768106,1739502679.3072104,39.58996224403381,4.112739951095686,1739502679.3072138,39.58996224403381,1.0704427550014275 +1739502679.326848,39.60996222496033,44.280945116959785,1739502679.3268523,39.60996222496033,6.503490517874942,1739502679.3268573,39.60996222496033,65.2064656209765,1739502679.3268626,39.60996222496033,42.76916038414714,1739502679.3268654,39.60996222496033,2.8175578031019493,1739502679.3268692,39.60996222496033,-1.960021832343225,1739502679.3268726,39.60996222496033,0.8321370375206173,1739502679.3268762,39.60996222496033,0.4002651553896347,1739502679.3268795,39.60996222496033,1.2847717830791086,1739502679.326883,39.60996222496033,0.0,1739502679.3268867,39.60996222496033,0.21432902807768106,1739502679.3269143,39.60996222496033,4.112739951095686,1739502679.3269176,39.60996222496033,1.0704427550014275 +1739502679.3451684,39.62996220588684,44.280945116959785,1739502679.3451712,39.62996220588684,6.503490517874942,1739502679.345174,39.62996220588684,65.2064656209765,1739502679.345177,39.62996220588684,42.76916038414714,1739502679.3451781,39.62996220588684,2.8175578031019493,1739502679.3451796,39.62996220588684,-1.960021832343225,1739502679.3451812,39.62996220588684,0.8321370375206173,1739502679.3451824,39.62996220588684,0.4002651553896347,1739502679.3451834,39.62996220588684,1.2847717830791086,1739502679.3451853,39.62996220588684,0.0,1739502679.3451865,39.62996220588684,0.21432902807768106,1739502679.345188,39.62996220588684,4.112739951095686,1739502679.345189,39.62996220588684,1.0704427550014275 +1739502679.365061,39.649962186813354,44.280945116959785,1739502679.3650637,39.649962186813354,6.503490517874942,1739502679.3650665,39.649962186813354,65.2064656209765,1739502679.3650692,39.649962186813354,42.76916038414714,1739502679.3650703,39.649962186813354,2.8175578031019493,1739502679.365072,39.649962186813354,-1.960021832343225,1739502679.3650734,39.649962186813354,0.8321370375206173,1739502679.3650746,39.649962186813354,0.4002651553896347,1739502679.3650758,39.649962186813354,1.2847717830791086,1739502679.3650773,39.649962186813354,0.0,1739502679.3650784,39.649962186813354,0.21432902807768106,1739502679.3650799,39.649962186813354,4.112739951095686,1739502679.365081,39.649962186813354,1.0704427550014275 +1739502679.3849998,39.66996216773987,44.21484464058674,1739502679.3850029,39.66996216773987,6.4046419893506155,1739502679.3850057,39.66996216773987,65.33076129102716,1739502679.3850083,39.66996216773987,42.710911036533425,1739502679.3850102,39.66996216773987,2.6566134801643426,1739502679.3850117,39.66996216773987,-1.9523883661303614,1739502679.3850133,39.66996216773987,0.7860297324898056,1739502679.3850145,39.66996216773987,0.3682726082234923,1739502679.3850155,39.66996216773987,1.3330465287581212,1739502679.3850172,39.66996216773987,0.0,1739502679.3850183,39.66996216773987,0.2504437181338079,1739502679.3850195,39.66996216773987,4.134912873671614,1739502679.385021,39.66996216773987,1.0938886586664316 +1739502679.4046006,39.68996214866638,44.21484464058674,1739502679.4046025,39.68996214866638,6.4046419893506155,1739502679.4046054,39.68996214866638,65.33076129102716,1739502679.404608,39.68996214866638,42.710911036533425,1739502679.4046092,39.68996214866638,2.6566134801643426,1739502679.404611,39.68996214866638,-1.9523883661303614,1739502679.4046125,39.68996214866638,0.7860297324898056,1739502679.4046142,39.68996214866638,0.3682726082234923,1739502679.4046154,39.68996214866638,1.3330465287581212,1739502679.404617,39.68996214866638,0.0,1739502679.4046183,39.68996214866638,0.23915787009168965,1739502679.4046195,39.68996214866638,4.134912873671614,1739502679.4046211,39.68996214866638,1.0938886586664316 +1739502679.4246073,39.709962129592896,44.21484464058674,1739502679.4246092,39.709962129592896,6.4046419893506155,1739502679.424612,39.709962129592896,65.33076129102716,1739502679.4246147,39.709962129592896,42.710911036533425,1739502679.4246159,39.709962129592896,2.6566134801643426,1739502679.4246175,39.709962129592896,-1.9523883661303614,1739502679.4246187,39.709962129592896,0.7860297324898056,1739502679.42462,39.709962129592896,0.3682726082234923,1739502679.4246213,39.709962129592896,1.3330465287581212,1739502679.4246225,39.709962129592896,0.0,1739502679.424624,39.709962129592896,0.23915787009168965,1739502679.4246252,39.709962129592896,4.134912873671614,1739502679.4246266,39.709962129592896,1.0938886586664316 +1739502679.4573262,39.72996211051941,44.21484464058674,1739502679.4573352,39.72996211051941,6.4046419893506155,1739502679.4573457,39.72996211051941,65.33076129102716,1739502679.4573557,39.72996211051941,42.710911036533425,1739502679.4573607,39.72996211051941,2.6566134801643426,1739502679.4573667,39.72996211051941,-1.9523883661303614,1739502679.457372,39.72996211051941,0.7860297324898056,1739502679.4573765,39.72996211051941,0.3682726082234923,1739502679.4573815,39.72996211051941,1.3330465287581212,1739502679.457387,39.72996211051941,0.0,1739502679.4573922,39.72996211051941,0.23915787009168965,1739502679.4573972,39.72996211051941,4.134912873671614,1739502679.4574025,39.72996211051941,1.0938886586664316 +1739502679.4742737,39.74996209144592,44.21484464058674,1739502679.4742806,39.74996209144592,6.4046419893506155,1739502679.4742897,39.74996209144592,65.33076129102716,1739502679.4743001,39.74996209144592,42.710911036533425,1739502679.474306,39.74996209144592,2.6566134801643426,1739502679.4743135,39.74996209144592,-1.9523883661303614,1739502679.4743202,39.74996209144592,0.7860297324898056,1739502679.4743268,39.74996209144592,0.3682726082234923,1739502679.4743335,39.74996209144592,1.3330465287581212,1739502679.4743404,39.74996209144592,0.0,1739502679.4743474,39.74996209144592,0.23915787009168965,1739502679.4743543,39.74996209144592,4.134912873671614,1739502679.4743612,39.74996209144592,1.0938886586664316 +1739502679.4896135,39.76996207237244,44.21484464058674,1739502679.4896178,39.76996207237244,6.4046419893506155,1739502679.4896233,39.76996207237244,65.33076129102716,1739502679.4896295,39.76996207237244,42.710911036533425,1739502679.4896328,39.76996207237244,2.6566134801643426,1739502679.4896371,39.76996207237244,-1.9523883661303614,1739502679.4896412,39.76996207237244,0.7860297324898056,1739502679.4896452,39.76996207237244,0.3682726082234923,1739502679.489649,39.76996207237244,1.3330465287581212,1739502679.4896533,39.76996207237244,0.0,1739502679.4896574,39.76996207237244,0.23915787009168965,1739502679.4896615,39.76996207237244,4.134912873671614,1739502679.4896655,39.76996207237244,1.0938886586664316 +1739502679.5267217,39.79996204376221,44.149430954311306,1739502679.526725,39.79996204376221,6.302109489451567,1739502679.5267298,39.79996204376221,65.46786032304153,1739502679.5267346,39.79996204376221,42.640188741608455,1739502679.5267375,39.79996204376221,2.4811167215910537,1739502679.5267413,39.79996204376221,-1.9469736376259628,1739502679.5267446,39.79996204376221,0.7376083954694466,1739502679.526748,39.79996204376221,0.3342481598673533,1739502679.5267513,39.79996204376221,1.3856980439140945,1739502679.5267546,39.79996204376221,0.0,1739502679.526758,39.79996204376221,0.2778338998312451,1739502679.5267613,39.79996204376221,4.155690003732978,1739502679.5267649,39.79996204376221,1.1199504113008347 +1739502679.5474083,39.81996202468872,44.149430954311306,1739502679.5474117,39.81996202468872,6.302109489451567,1739502679.5474162,39.81996202468872,65.46786032304153,1739502679.5474215,39.81996202468872,42.640188741608455,1739502679.547424,39.81996202468872,2.4811167215910537,1739502679.5474277,39.81996202468872,-1.9469736376259628,1739502679.547431,39.81996202468872,0.7376083954694466,1739502679.5474343,39.81996202468872,0.3342481598673533,1739502679.5474374,39.81996202468872,1.3856980439140945,1739502679.5474412,39.81996202468872,0.0,1739502679.547444,39.81996202468872,0.26574763261325973,1739502679.5474474,39.81996202468872,4.155690003732978,1739502679.5474508,39.81996202468872,1.1199504113008347 +1739502679.5669975,39.839962005615234,44.149430954311306,1739502679.5670016,39.839962005615234,6.302109489451567,1739502679.5670063,39.839962005615234,65.46786032304153,1739502679.567028,39.839962005615234,42.640188741608455,1739502679.5670307,39.839962005615234,2.4811167215910537,1739502679.5670347,39.839962005615234,-1.9469736376259628,1739502679.5670376,39.839962005615234,0.7376083954694466,1739502679.567041,39.839962005615234,0.3342481598673533,1739502679.5670443,39.839962005615234,1.3856980439140945,1739502679.5670507,39.839962005615234,0.0,1739502679.567054,39.839962005615234,0.26574763261325973,1739502679.5670574,39.839962005615234,4.155690003732978,1739502679.567061,39.839962005615234,1.1199504113008347 +1739502679.5869443,39.85996198654175,44.149430954311306,1739502679.586948,39.85996198654175,6.302109489451567,1739502679.5869763,39.85996198654175,65.46786032304153,1739502679.5869813,39.85996198654175,42.640188741608455,1739502679.5869842,39.85996198654175,2.4811167215910537,1739502679.5869877,39.85996198654175,-1.9469736376259628,1739502679.586991,39.85996198654175,0.7376083954694466,1739502679.5869944,39.85996198654175,0.3342481598673533,1739502679.5869977,39.85996198654175,1.3856980439140945,1739502679.5870013,39.85996198654175,0.0,1739502679.5870044,39.85996198654175,0.26574763261325973,1739502679.587008,39.85996198654175,4.155690003732978,1739502679.5870113,39.85996198654175,1.1199504113008347 +1739502679.606858,39.87996196746826,44.149430954311306,1739502679.6068618,39.87996196746826,6.302109489451567,1739502679.6068664,39.87996196746826,65.46786032304153,1739502679.6068716,39.87996196746826,42.640188741608455,1739502679.606893,39.87996196746826,2.4811167215910537,1739502679.6068969,39.87996196746826,-1.9469736376259628,1739502679.6069002,39.87996196746826,0.7376083954694466,1739502679.6069038,39.87996196746826,0.3342481598673533,1739502679.6069071,39.87996196746826,1.3856980439140945,1739502679.6069107,39.87996196746826,0.0,1739502679.6069143,39.87996196746826,0.26574763261325973,1739502679.6069176,39.87996196746826,4.155690003732978,1739502679.6069212,39.87996196746826,1.1199504113008347 +1739502679.6271753,39.899961948394775,44.084539466149295,1739502679.627179,39.899961948394775,6.195723217903817,1739502679.6271837,39.899961948394775,65.55889049941742,1739502679.6271887,39.899961948394775,42.57994041150022,1739502679.6271915,39.899961948394775,2.345256987600516,1739502679.6271951,39.899961948394775,-1.9433098389052585,1739502679.6271985,39.899961948394775,0.6779590321677863,1739502679.6272018,39.899961948394775,0.3036256990790963,1739502679.627205,39.899961948394775,1.4534259680418935,1739502679.6272085,39.899961948394775,0.0,1739502679.6272118,39.899961948394775,0.32236817438421744,1739502679.6272151,39.899961948394775,4.175135197863339,1739502679.6272185,39.899961948394775,1.1487517245621455 +1739502679.6445367,39.91996192932129,44.084539466149295,1739502679.6445389,39.91996192932129,6.195723217903817,1739502679.6445417,39.91996192932129,65.55889049941742,1739502679.6445444,39.91996192932129,42.57994041150022,1739502679.6445453,39.91996192932129,2.345256987600516,1739502679.644547,39.91996192932129,-1.9433098389052585,1739502679.6445484,39.91996192932129,0.6779590321677863,1739502679.6445498,39.91996192932129,0.3036256990790963,1739502679.6445513,39.91996192932129,1.4534259680418935,1739502679.6445527,39.91996192932129,0.0,1739502679.644554,39.91996192932129,0.30467424347974803,1739502679.6445553,39.91996192932129,4.175135197863339,1739502679.6445568,39.91996192932129,1.1487517245621455 +1739502679.6647253,39.9399619102478,44.084539466149295,1739502679.6647294,39.9399619102478,6.195723217903817,1739502679.6647346,39.9399619102478,65.55889049941742,1739502679.6647403,39.9399619102478,42.57994041150022,1739502679.6647437,39.9399619102478,2.345256987600516,1739502679.6647608,39.9399619102478,-1.9433098389052585,1739502679.6647644,39.9399619102478,0.6779590321677863,1739502679.664768,39.9399619102478,0.3036256990790963,1739502679.6647713,39.9399619102478,1.4534259680418935,1739502679.664775,39.9399619102478,0.0,1739502679.6647787,39.9399619102478,0.30467424347974803,1739502679.6647823,39.9399619102478,4.175135197863339,1739502679.6647859,39.9399619102478,1.1487517245621455 +1739502679.685028,39.959961891174316,44.084539466149295,1739502679.6850307,39.959961891174316,6.195723217903817,1739502679.6850336,39.959961891174316,65.55889049941742,1739502679.685036,39.959961891174316,42.57994041150022,1739502679.6850374,39.959961891174316,2.345256987600516,1739502679.685039,39.959961891174316,-1.9433098389052585,1739502679.685041,39.959961891174316,0.6779590321677863,1739502679.6850421,39.959961891174316,0.3036256990790963,1739502679.685043,39.959961891174316,1.4534259680418935,1739502679.6850448,39.959961891174316,0.0,1739502679.685046,39.959961891174316,0.30467424347974803,1739502679.6850476,39.959961891174316,4.175135197863339,1739502679.6850488,39.959961891174316,1.1487517245621455 +1739502679.704584,39.97996187210083,44.084539466149295,1739502679.704586,39.97996187210083,6.195723217903817,1739502679.7045887,39.97996187210083,65.55889049941742,1739502679.704591,39.97996187210083,42.57994041150022,1739502679.7045925,39.97996187210083,2.345256987600516,1739502679.704594,39.97996187210083,-1.9433098389052585,1739502679.704595,39.97996187210083,0.6779590321677863,1739502679.7045968,39.97996187210083,0.3036256990790963,1739502679.7045977,39.97996187210083,1.4534259680418935,1739502679.7045994,39.97996187210083,0.0,1739502679.7046006,39.97996187210083,0.30467424347974803,1739502679.7046018,39.97996187210083,4.175135197863339,1739502679.7046032,39.97996187210083,1.1487517245621455 +1739502679.724856,39.999961853027344,44.019947492129425,1739502679.7248583,39.999961853027344,6.085190281307652,1739502679.7248614,39.999961853027344,65.73470666531047,1739502679.7248642,39.999961853027344,42.46852556287881,1739502679.7248654,39.999961853027344,2.12994601318186,1739502679.7248673,39.999961853027344,-1.94459890762032,1739502679.7248688,39.999961853027344,0.6150566147541952,1739502679.7248702,39.999961853027344,0.26102396100594694,1739502679.7248714,39.999961853027344,1.5284366873594344,1739502679.7248747,39.999961853027344,0.0,1739502679.7248785,39.999961853027344,0.3652916442114812,1739502679.7248821,39.999961853027344,4.1933100965130095,1739502679.724887,39.999961853027344,1.1820879932965858 +1739502679.7450838,40.01996183395386,44.019947492129425,1739502679.7450867,40.01996183395386,6.085190281307652,1739502679.7450898,40.01996183395386,65.73470666531047,1739502679.7450926,40.01996183395386,42.46852556287881,1739502679.7450938,40.01996183395386,2.12994601318186,1739502679.7450957,40.01996183395386,-1.94459890762032,1739502679.7450972,40.01996183395386,0.6150566147541952,1739502679.7450986,40.01996183395386,0.26102396100594694,1739502679.7451,40.01996183395386,1.5284366873594344,1739502679.7451015,40.01996183395386,0.0,1739502679.7451031,40.01996183395386,0.3463486940628486,1739502679.7451046,40.01996183395386,4.1933100965130095,1739502679.7451062,40.01996183395386,1.1820879932965858 +1739502679.765,40.03996181488037,44.019947492129425,1739502679.7650025,40.03996181488037,6.085190281307652,1739502679.7650056,40.03996181488037,65.73470666531047,1739502679.7650084,40.03996181488037,42.46852556287881,1739502679.7650096,40.03996181488037,2.12994601318186,1739502679.7650115,40.03996181488037,-1.94459890762032,1739502679.7650127,40.03996181488037,0.6150566147541952,1739502679.7650142,40.03996181488037,0.26102396100594694,1739502679.7650156,40.03996181488037,1.5284366873594344,1739502679.7650173,40.03996181488037,0.0,1739502679.765019,40.03996181488037,0.3463486940628486,1739502679.7650201,40.03996181488037,4.1933100965130095,1739502679.7650218,40.03996181488037,1.1820879932965858 +1739502679.7850776,40.059961795806885,44.019947492129425,1739502679.7850814,40.059961795806885,6.085190281307652,1739502679.7850864,40.059961795806885,65.73470666531047,1739502679.7850926,40.059961795806885,42.46852556287881,1739502679.785096,40.059961795806885,2.12994601318186,1739502679.7851,40.059961795806885,-1.94459890762032,1739502679.7851043,40.059961795806885,0.6150566147541952,1739502679.7851083,40.059961795806885,0.26102396100594694,1739502679.7851121,40.059961795806885,1.5284366873594344,1739502679.785116,40.059961795806885,0.0,1739502679.7851198,40.059961795806885,0.3463486940628486,1739502679.7851238,40.059961795806885,4.1933100965130095,1739502679.7851279,40.059961795806885,1.1820879932965858 +1739502679.8063142,40.0799617767334,44.019947492129425,1739502679.8063183,40.0799617767334,6.085190281307652,1739502679.806323,40.0799617767334,65.73470666531047,1739502679.8063276,40.0799617767334,42.46852556287881,1739502679.8063295,40.0799617767334,2.12994601318186,1739502679.806332,40.0799617767334,-1.94459890762032,1739502679.8063345,40.0799617767334,0.6150566147541952,1739502679.8063369,40.0799617767334,0.26102396100594694,1739502679.8063385,40.0799617767334,1.5284366873594344,1739502679.8063416,40.0799617767334,0.0,1739502679.8063438,40.0799617767334,0.3463486940628486,1739502679.806346,40.0799617767334,4.1933100965130095,1739502679.8063483,40.0799617767334,1.1820879932965858 +1739502679.825897,40.09996175765991,44.019947492129425,1739502679.825901,40.09996175765991,6.085190281307652,1739502679.8259053,40.09996175765991,65.73470666531047,1739502679.8259096,40.09996175765991,42.46852556287881,1739502679.8259118,40.09996175765991,2.12994601318186,1739502679.8259144,40.09996175765991,-1.94459890762032,1739502679.8259165,40.09996175765991,0.6150566147541952,1739502679.8259187,40.09996175765991,0.26102396100594694,1739502679.8259208,40.09996175765991,1.5284366873594344,1739502679.8259234,40.09996175765991,0.0,1739502679.8259256,40.09996175765991,0.3463486940628486,1739502679.8259277,40.09996175765991,4.1933100965130095,1739502679.8259304,40.09996175765991,1.1820879932965858 +1739502679.8468301,40.119961738586426,43.95540742551599,1739502679.8468356,40.119961738586426,5.970139591604212,1739502679.846842,40.119961738586426,65.9231168476777,1739502679.8468494,40.119961738586426,42.33403180508694,1739502679.8468559,40.119961738586426,1.9026214079937578,1739502679.8468635,40.119961738586426,-1.9501085629782808,1739502679.84687,40.119961738586426,0.5363864530174463,1739502679.8468764,40.119961738586426,0.21448421975772125,1739502679.8468833,40.119961738586426,1.6277221271772537,1739502679.84689,40.119961738586426,0.0,1739502679.846897,40.119961738586426,0.4356417562616662,1739502679.8469038,40.119961738586426,4.210271036133182,1739502679.846911,40.119961738586426,1.2199844711480718 +1739502679.8658552,40.13996171951294,43.95540742551599,1739502679.8658586,40.13996171951294,5.970139591604212,1739502679.8658626,40.13996171951294,65.9231168476777,1739502679.8658662,40.13996171951294,42.33403180508694,1739502679.8658683,40.13996171951294,1.9026214079937578,1739502679.8658705,40.13996171951294,-1.9501085629782808,1739502679.8658724,40.13996171951294,0.5363864530174463,1739502679.8658743,40.13996171951294,0.21448421975772125,1739502679.8658757,40.13996171951294,1.6277221271772537,1739502679.865878,40.13996171951294,0.0,1739502679.8658798,40.13996171951294,0.4077376560291819,1739502679.865882,40.13996171951294,4.210271036133182,1739502679.8658836,40.13996171951294,1.2199844711480718 +1739502679.8855324,40.15996170043945,43.95540742551599,1739502679.8855355,40.15996170043945,5.970139591604212,1739502679.8855395,40.15996170043945,65.9231168476777,1739502679.885543,40.15996170043945,42.33403180508694,1739502679.885545,40.15996170043945,1.9026214079937578,1739502679.8855472,40.15996170043945,-1.9501085629782808,1739502679.8855493,40.15996170043945,0.5363864530174463,1739502679.8855512,40.15996170043945,0.21448421975772125,1739502679.8855526,40.15996170043945,1.6277221271772537,1739502679.8855553,40.15996170043945,0.0,1739502679.885557,40.15996170043945,0.4077376560291819,1739502679.8855588,40.15996170043945,4.210271036133182,1739502679.8855608,40.15996170043945,1.2199844711480718 +1739502679.905727,40.17996168136597,43.95540742551599,1739502679.90573,40.17996168136597,5.970139591604212,1739502679.905734,40.17996168136597,65.9231168476777,1739502679.9057379,40.17996168136597,42.33403180508694,1739502679.9057398,40.17996168136597,1.9026214079937578,1739502679.9057422,40.17996168136597,-1.9501085629782808,1739502679.9057438,40.17996168136597,0.5363864530174463,1739502679.905746,40.17996168136597,0.21448421975772125,1739502679.9057477,40.17996168136597,1.6277221271772537,1739502679.90575,40.17996168136597,0.0,1739502679.9057517,40.17996168136597,0.4077376560291819,1739502679.9057536,40.17996168136597,4.210271036133182,1739502679.9057558,40.17996168136597,1.2199844711480718 +1739502679.9253938,40.19996166229248,43.95540742551599,1739502679.925397,40.19996166229248,5.970139591604212,1739502679.9254007,40.19996166229248,65.9231168476777,1739502679.9254043,40.19996166229248,42.33403180508694,1739502679.9254062,40.19996166229248,1.9026214079937578,1739502679.9254088,40.19996166229248,-1.9501085629782808,1739502679.9254107,40.19996166229248,0.5363864530174463,1739502679.9254127,40.19996166229248,0.21448421975772125,1739502679.925414,40.19996166229248,1.6277221271772537,1739502679.9254165,40.19996166229248,0.0,1739502679.9254181,40.19996166229248,0.4077376560291819,1739502679.92542,40.19996166229248,4.210271036133182,1739502679.9254217,40.19996166229248,1.2199844711480718 +1739502679.945784,40.219961643218994,43.89065927590672,1739502679.9457874,40.219961643218994,5.850138539193511,1739502679.9457917,40.219961643218994,65.98983010691589,1739502679.9457953,40.219961643218994,42.24965573462951,1739502679.9457972,40.219961643218994,1.7730304401320927,1739502679.9457996,40.219961643218994,-1.953449163318698,1739502679.9458015,40.219961643218994,0.4547810084718916,1739502679.9458032,40.219961643218994,0.1806042298411432,1739502679.9458048,40.219961643218994,1.7375323640881235,1739502679.9458072,40.219961643218994,0.0,1739502679.945809,40.219961643218994,0.5035137306790473,1739502679.945811,40.219961643218994,4.226072811269136,1739502679.9458127,40.219961643218994,1.2639486763608245 +1739502679.9655688,40.23996162414551,43.89065927590672,1739502679.9655719,40.23996162414551,5.850138539193511,1739502679.9655762,40.23996162414551,65.98983010691589,1739502679.9655797,40.23996162414551,42.24965573462951,1739502679.965582,40.23996162414551,1.7730304401320927,1739502679.965584,40.23996162414551,-1.953449163318698,1739502679.965586,40.23996162414551,0.4547810084718916,1739502679.9655876,40.23996162414551,0.1806042298411432,1739502679.9655895,40.23996162414551,1.7375323640881235,1739502679.9655917,40.23996162414551,0.0,1739502679.965593,40.23996162414551,0.473583687727299,1739502679.9655952,40.23996162414551,4.226072811269136,1739502679.965597,40.23996162414551,1.2639486763608245 +1739502679.9856591,40.25996160507202,43.89065927590672,1739502679.9856622,40.25996160507202,5.850138539193511,1739502679.9856663,40.25996160507202,65.98983010691589,1739502679.9856699,40.25996160507202,42.24965573462951,1739502679.985672,40.25996160507202,1.7730304401320927,1739502679.9856741,40.25996160507202,-1.953449163318698,1739502679.985676,40.25996160507202,0.4547810084718916,1739502679.9856777,40.25996160507202,0.1806042298411432,1739502679.9856794,40.25996160507202,1.7375323640881235,1739502679.9856813,40.25996160507202,0.0,1739502679.9856832,40.25996160507202,0.473583687727299,1739502679.985685,40.25996160507202,4.226072811269136,1739502679.985687,40.25996160507202,1.2639486763608245 +1739502680.0054889,40.279961585998535,43.89065927590672,1739502680.0054927,40.279961585998535,5.850138539193511,1739502680.0054967,40.279961585998535,65.98983010691589,1739502680.0055003,40.279961585998535,42.24965573462951,1739502680.0055022,40.279961585998535,1.7730304401320927,1739502680.0055046,40.279961585998535,-1.953449163318698,1739502680.0055063,40.279961585998535,0.4547810084718916,1739502680.0055084,40.279961585998535,0.1806042298411432,1739502680.0055099,40.279961585998535,1.7375323640881235,1739502680.005512,40.279961585998535,0.0,1739502680.0055137,40.279961585998535,0.473583687727299,1739502680.0055158,40.279961585998535,4.226072811269136,1739502680.0055175,40.279961585998535,1.2639486763608245 +1739502680.0256047,40.29996156692505,43.89065927590672,1739502680.0256076,40.29996156692505,5.850138539193511,1739502680.0256112,40.29996156692505,65.98983010691589,1739502680.0256152,40.29996156692505,42.24965573462951,1739502680.0256171,40.29996156692505,1.7730304401320927,1739502680.0256193,40.29996156692505,-1.953449163318698,1739502680.0256212,40.29996156692505,0.4547810084718916,1739502680.0256228,40.29996156692505,0.1806042298411432,1739502680.0256245,40.29996156692505,1.7375323640881235,1739502680.0256267,40.29996156692505,0.0,1739502680.0256283,40.29996156692505,0.473583687727299,1739502680.0256305,40.29996156692505,4.226072811269136,1739502680.0256321,40.29996156692505,1.2639486763608245 +1739502680.0459123,40.31996154785156,43.89065927590672,1739502680.0459158,40.31996154785156,5.850138539193511,1739502680.04592,40.31996154785156,65.98983010691589,1739502680.045924,40.31996154785156,42.24965573462951,1739502680.0459259,40.31996154785156,1.7730304401320927,1739502680.0459282,40.31996154785156,-1.953449163318698,1739502680.0459301,40.31996154785156,0.4547810084718916,1739502680.045932,40.31996154785156,0.1806042298411432,1739502680.0459337,40.31996154785156,1.7375323640881235,1739502680.0459359,40.31996154785156,0.0,1739502680.0459378,40.31996154785156,0.473583687727299,1739502680.0459394,40.31996154785156,4.226072811269136,1739502680.0459416,40.31996154785156,1.2639486763608245 +1739502680.0655432,40.339961528778076,43.82532810826379,1739502680.0655463,40.339961528778076,5.724495040791501,1739502680.0655503,40.339961528778076,66.11442593428217,1739502680.0655537,40.339961528778076,42.11699661178501,1739502680.0655556,40.339961528778076,1.5873801846419333,1739502680.0655577,40.339961528778076,-1.9623978065485206,1739502680.0655596,40.339961528778076,0.35778151009390585,1739502680.0655613,40.339961528778076,0.13705870601304496,1739502680.065563,40.339961528778076,1.877733611473321,1739502680.0655649,40.339961528778076,0.0,1739502680.0655668,40.339961528778076,0.602158163607095,1739502680.0655687,40.339961528778076,4.240767900659373,1739502680.0655706,40.339961528778076,1.3157549979224281 +1739502680.0854502,40.35996150970459,43.82532810826379,1739502680.0854533,40.35996150970459,5.724495040791501,1739502680.085457,40.35996150970459,66.11442593428217,1739502680.0854607,40.35996150970459,42.11699661178501,1739502680.0854626,40.35996150970459,1.5873801846419333,1739502680.0854647,40.35996150970459,-1.9623978065485206,1739502680.0854666,40.35996150970459,0.35778151009390585,1739502680.0854685,40.35996150970459,0.13705870601304496,1739502680.0854702,40.35996150970459,1.877733611473321,1739502680.0854723,40.35996150970459,0.0,1739502680.085474,40.35996150970459,0.5619786135508928,1739502680.0854762,40.35996150970459,4.240767900659373,1739502680.0854778,40.35996150970459,1.3157549979224281 +1739502680.105753,40.3799614906311,43.82532810826379,1739502680.105756,40.3799614906311,5.724495040791501,1739502680.1057606,40.3799614906311,66.11442593428217,1739502680.1057649,40.3799614906311,42.11699661178501,1739502680.105767,40.3799614906311,1.5873801846419333,1739502680.1057696,40.3799614906311,-1.9623978065485206,1739502680.1057723,40.3799614906311,0.35778151009390585,1739502680.1057746,40.3799614906311,0.13705870601304496,1739502680.1057768,40.3799614906311,1.877733611473321,1739502680.1057794,40.3799614906311,0.0,1739502680.1057816,40.3799614906311,0.5619786135508928,1739502680.1057837,40.3799614906311,4.240767900659373,1739502680.1057863,40.3799614906311,1.3157549979224281 +1739502680.125585,40.39996147155762,43.82532810826379,1739502680.1255884,40.39996147155762,5.724495040791501,1739502680.1255925,40.39996147155762,66.11442593428217,1739502680.125596,40.39996147155762,42.11699661178501,1739502680.125598,40.39996147155762,1.5873801846419333,1739502680.1256003,40.39996147155762,-1.9623978065485206,1739502680.125602,40.39996147155762,0.35778151009390585,1739502680.1256042,40.39996147155762,0.13705870601304496,1739502680.1256056,40.39996147155762,1.877733611473321,1739502680.125608,40.39996147155762,0.0,1739502680.1256096,40.39996147155762,0.5619786135508928,1739502680.1256115,40.39996147155762,4.240767900659373,1739502680.1256135,40.39996147155762,1.3157549979224281 +1739502680.145691,40.41996145248413,43.82532810826379,1739502680.145694,40.41996145248413,5.724495040791501,1739502680.1456983,40.41996145248413,66.11442593428217,1739502680.1457021,40.41996145248413,42.11699661178501,1739502680.145704,40.41996145248413,1.5873801846419333,1739502680.1457062,40.41996145248413,-1.9623978065485206,1739502680.145708,40.41996145248413,0.35778151009390585,1739502680.1457098,40.41996145248413,0.13705870601304496,1739502680.1457117,40.41996145248413,1.877733611473321,1739502680.1457138,40.41996145248413,0.0,1739502680.1457155,40.41996145248413,0.5619786135508928,1739502680.1457176,40.41996145248413,4.240767900659373,1739502680.1457195,40.41996145248413,1.3157549979224281 +1739502680.1655152,40.439961433410645,43.75905758466241,1739502680.165518,40.439961433410645,5.592495810161582,1739502680.1655219,40.439961433410645,66.32918276969377,1739502680.1655254,40.439961433410645,41.89921265442837,1739502680.1655273,40.439961433410645,1.3319355315816626,1739502680.1655295,40.439961433410645,-1.9823888747319083,1739502680.1655314,40.439961433410645,0.2156224075881395,1739502680.165533,40.439961433410645,0.07660865776554665,1739502680.165535,40.439961433410645,2.103900085365336,1739502680.165537,40.439961433410645,0.0,1739502680.1655385,40.439961433410645,0.8028796279937307,1739502680.1655407,40.439961433410645,4.254397465591249,1739502680.1655424,40.439961433410645,1.3763020737434661 +1739502680.1854432,40.45996141433716,43.75905758466241,1739502680.1854463,40.45996141433716,5.592495810161582,1739502680.1854506,40.45996141433716,66.32918276969377,1739502680.1854541,40.45996141433716,41.89921265442837,1739502680.1854558,40.45996141433716,1.3319355315816626,1739502680.1854582,40.45996141433716,-1.9823888747319083,1739502680.1854603,40.45996141433716,0.2156224075881395,1739502680.1854618,40.45996141433716,0.07660865776554665,1739502680.1854637,40.45996141433716,2.103900085365336,1739502680.1854656,40.45996141433716,0.0,1739502680.1854672,40.45996141433716,0.7275980116218699,1739502680.1854692,40.45996141433716,4.254397465591249,1739502680.185471,40.45996141433716,1.3763020737434661 +1739502680.2058008,40.47996139526367,43.75905758466241,1739502680.205804,40.47996139526367,5.592495810161582,1739502680.2058082,40.47996139526367,66.32918276969377,1739502680.205812,40.47996139526367,41.89921265442837,1739502680.2058136,40.47996139526367,1.3319355315816626,1739502680.2058158,40.47996139526367,-1.9823888747319083,1739502680.205818,40.47996139526367,0.2156224075881395,1739502680.2058196,40.47996139526367,0.07660865776554665,1739502680.2058215,40.47996139526367,2.103900085365336,1739502680.2058234,40.47996139526367,0.0,1739502680.2058253,40.47996139526367,0.7275980116218699,1739502680.2058272,40.47996139526367,4.254397465591249,1739502680.2058294,40.47996139526367,1.3763020737434661 +1739502680.2256246,40.499961376190186,43.75905758466241,1739502680.2256286,40.499961376190186,5.592495810161582,1739502680.2256334,40.499961376190186,66.32918276969377,1739502680.2256374,40.499961376190186,41.89921265442837,1739502680.2256393,40.499961376190186,1.3319355315816626,1739502680.225642,40.499961376190186,-1.9823888747319083,1739502680.2256439,40.499961376190186,0.2156224075881395,1739502680.2256458,40.499961376190186,0.07660865776554665,1739502680.2256477,40.499961376190186,2.103900085365336,1739502680.2256498,40.499961376190186,0.0,1739502680.2256517,40.499961376190186,0.7275980116218699,1739502680.2256536,40.499961376190186,4.254397465591249,1739502680.2256558,40.499961376190186,1.3763020737434661 +1739502680.2458315,40.5199613571167,43.75905758466241,1739502680.2458353,40.5199613571167,5.592495810161582,1739502680.2458394,40.5199613571167,66.32918276969377,1739502680.2458434,40.5199613571167,41.89921265442837,1739502680.2458453,40.5199613571167,1.3319355315816626,1739502680.2458475,40.5199613571167,-1.9823888747319083,1739502680.2458496,40.5199613571167,0.2156224075881395,1739502680.2458513,40.5199613571167,0.07660865776554665,1739502680.2458532,40.5199613571167,2.103900085365336,1739502680.2458553,40.5199613571167,0.0,1739502680.245857,40.5199613571167,0.7275980116218699,1739502680.2458591,40.5199613571167,4.254397465591249,1739502680.2458608,40.5199613571167,1.3763020737434661 +1739502680.2656543,40.53996133804321,43.75905758466241,1739502680.2656574,40.53996133804321,5.592495810161582,1739502680.2656612,40.53996133804321,66.32918276969377,1739502680.265665,40.53996133804321,41.89921265442837,1739502680.2656667,40.53996133804321,1.3319355315816626,1739502680.265669,40.53996133804321,-1.9823888747319083,1739502680.265671,40.53996133804321,0.2156224075881395,1739502680.2656727,40.53996133804321,0.07660865776554665,1739502680.2656746,40.53996133804321,2.103900085365336,1739502680.2656765,40.53996133804321,0.0,1739502680.2656784,40.53996133804321,0.7275980116218699,1739502680.2656806,40.53996133804321,4.254397465591249,1739502680.2656827,40.53996133804321,1.3763020737434661 +1739502680.2856028,40.55996131896973,43.69119289521759,1739502680.2856061,40.55996131896973,5.452761420004242,1739502680.28561,40.55996131896973,66.4168617148449,1739502680.2856135,40.55996131896973,41.724686871484636,1739502680.2856154,40.55996131896973,1.1576244286223973,1739502680.2856178,40.55996131896973,-2.0001547860478803,1739502680.2856197,40.55996131896973,0.07567780449329715,1739502680.2856214,40.55996131896973,0.026044449065603457,1739502680.285623,40.55996131896973,2.3531350155646495,1739502680.285625,40.55996131896973,0.0,1739502680.285627,40.55996131896973,0.9744410648710566,1739502680.285629,40.55996131896973,4.267009681493933,1739502680.2856307,40.55996131896973,1.4558324554099087 +1739502680.305732,40.57996129989624,43.69119289521759,1739502680.3057353,40.57996129989624,5.452761420004242,1739502680.3057394,40.57996129989624,66.4168617148449,1739502680.3057432,40.57996129989624,41.724686871484636,1739502680.3057451,40.57996129989624,1.1576244286223973,1739502680.3057475,40.57996129989624,-2.0001547860478803,1739502680.3057494,40.57996129989624,0.07567780449329715,1739502680.3057516,40.57996129989624,0.026044449065603457,1739502680.305753,40.57996129989624,2.3531350155646495,1739502680.3057551,40.57996129989624,0.0,1739502680.305757,40.57996129989624,0.8973025601547409,1739502680.305759,40.57996129989624,4.267009681493933,1739502680.305761,40.57996129989624,1.4558324554099087 +1739502680.325508,40.599961280822754,43.69119289521759,1739502680.325511,40.599961280822754,5.452761420004242,1739502680.3255148,40.599961280822754,66.4168617148449,1739502680.3255186,40.599961280822754,41.724686871484636,1739502680.3255203,40.599961280822754,1.1576244286223973,1739502680.3255227,40.599961280822754,-2.0001547860478803,1739502680.3255246,40.599961280822754,0.07567780449329715,1739502680.3255262,40.599961280822754,0.026044449065603457,1739502680.3255281,40.599961280822754,2.3531350155646495,1739502680.32553,40.599961280822754,0.0,1739502680.325532,40.599961280822754,0.8973025601547409,1739502680.3255339,40.599961280822754,4.267009681493933,1739502680.3255358,40.599961280822754,1.4558324554099087 +1739502680.3456142,40.61996126174927,43.69119289521759,1739502680.345618,40.61996126174927,5.452761420004242,1739502680.3456223,40.61996126174927,66.4168617148449,1739502680.3456259,40.61996126174927,41.724686871484636,1739502680.345628,40.61996126174927,1.1576244286223973,1739502680.3456302,40.61996126174927,-2.0001547860478803,1739502680.3456326,40.61996126174927,0.07567780449329715,1739502680.3456342,40.61996126174927,0.026044449065603457,1739502680.3456361,40.61996126174927,2.3531350155646495,1739502680.3456388,40.61996126174927,0.0,1739502680.3456404,40.61996126174927,0.8973025601547409,1739502680.3456426,40.61996126174927,4.267009681493933,1739502680.3456445,40.61996126174927,1.4558324554099087 +1739502680.3652053,40.63996124267578,43.69119289521759,1739502680.3652086,40.63996124267578,5.452761420004242,1739502680.3652124,40.63996124267578,66.4168617148449,1739502680.365216,40.63996124267578,41.724686871484636,1739502680.3652184,40.63996124267578,1.1576244286223973,1739502680.3652205,40.63996124267578,-2.0001547860478803,1739502680.3652225,40.63996124267578,0.07567780449329715,1739502680.3652241,40.63996124267578,0.026044449065603457,1739502680.365226,40.63996124267578,2.3531350155646495,1739502680.365228,40.63996124267578,0.0,1739502680.3652298,40.63996124267578,0.8973025601547409,1739502680.3652315,40.63996124267578,4.267009681493933,1739502680.3652337,40.63996124267578,1.4558324554099087 +1739502680.387729,40.659961223602295,43.62098625293405,1739502680.387734,40.659961223602295,5.303612723936526,1739502680.38774,40.659961223602295,66.6535665591532,1739502680.387746,40.659961223602295,41.39271084132243,1739502680.3877497,40.659961223602295,0.8856506009445924,1739502680.387754,40.659961223602295,-2.037931629886639,1739502680.3877578,40.659961223602295,-0.165213627114184,1739502680.3877618,40.659961223602295,-0.05181894951529288,1739502680.3877661,40.659961223602295,2.19047809929551,1739502680.3877702,40.659961223602295,0.0,1739502680.3877742,40.659961223602295,0.5205619148564565,1739502680.3877783,40.659961223602295,4.278649254254395,1739502680.3877828,40.659961223602295,1.5521846555925343 +1739502680.4052622,40.67996120452881,43.62098625293405,1739502680.4052649,40.67996120452881,5.303612723936526,1739502680.4052677,40.67996120452881,66.6535665591532,1739502680.4052706,40.67996120452881,41.39271084132243,1739502680.405272,40.67996120452881,0.8856506009445924,1739502680.4052737,40.67996120452881,-2.037931629886639,1739502680.4052749,40.67996120452881,-0.165213627114184,1739502680.4052763,40.67996120452881,-0.05181894951529288,1739502680.4052777,40.67996120452881,2.19047809929551,1739502680.4052792,40.67996120452881,0.0,1739502680.4052806,40.67996120452881,0.6382934437029759,1739502680.405282,40.67996120452881,4.278649254254395,1739502680.4052837,40.67996120452881,1.5521846555925343 +1739502680.4249346,40.69996118545532,43.62098625293405,1739502680.4249375,40.69996118545532,5.303612723936526,1739502680.4249408,40.69996118545532,66.6535665591532,1739502680.4249434,40.69996118545532,41.39271084132243,1739502680.4249449,40.69996118545532,0.8856506009445924,1739502680.4249465,40.69996118545532,-2.037931629886639,1739502680.424948,40.69996118545532,-0.165213627114184,1739502680.4249492,40.69996118545532,-0.05181894951529288,1739502680.4249506,40.69996118545532,2.19047809929551,1739502680.424952,40.69996118545532,0.0,1739502680.4249535,40.69996118545532,0.6382934437029759,1739502680.424955,40.69996118545532,4.278649254254395,1739502680.4249563,40.69996118545532,1.5521846555925343 +1739502680.444521,40.719961166381836,43.62098625293405,1739502680.4445233,40.719961166381836,5.303612723936526,1739502680.4445262,40.719961166381836,66.6535665591532,1739502680.4445286,40.719961166381836,41.39271084132243,1739502680.44453,40.719961166381836,0.8856506009445924,1739502680.4445317,40.719961166381836,-2.037931629886639,1739502680.4445336,40.719961166381836,-0.165213627114184,1739502680.4445348,40.719961166381836,-0.05181894951529288,1739502680.444536,40.719961166381836,2.19047809929551,1739502680.4445376,40.719961166381836,0.0,1739502680.4445388,40.719961166381836,0.6382934437029759,1739502680.4445403,40.719961166381836,4.278649254254395,1739502680.4445415,40.719961166381836,1.5521846555925343 +1739502680.464714,40.73996114730835,43.62098625293405,1739502680.4647164,40.73996114730835,5.303612723936526,1739502680.4647195,40.73996114730835,66.6535665591532,1739502680.4647224,40.73996114730835,41.39271084132243,1739502680.4647238,40.73996114730835,0.8856506009445924,1739502680.4647255,40.73996114730835,-2.037931629886639,1739502680.4647267,40.73996114730835,-0.165213627114184,1739502680.4647284,40.73996114730835,-0.05181894951529288,1739502680.4647295,40.73996114730835,2.19047809929551,1739502680.4647489,40.73996114730835,0.0,1739502680.46475,40.73996114730835,0.6382934437029759,1739502680.4647512,40.73996114730835,4.278649254254395,1739502680.464753,40.73996114730835,1.5521846555925343 +1739502680.4849668,40.75996112823486,43.62098625293405,1739502680.484969,40.75996112823486,5.303612723936526,1739502680.4849718,40.75996112823486,66.6535665591532,1739502680.4849746,40.75996112823486,41.39271084132243,1739502680.4849758,40.75996112823486,0.8856506009445924,1739502680.4849775,40.75996112823486,-2.037931629886639,1739502680.484979,40.75996112823486,-0.165213627114184,1739502680.4849806,40.75996112823486,-0.05181894951529288,1739502680.4849818,40.75996112823486,2.19047809929551,1739502680.4849832,40.75996112823486,0.0,1739502680.4849846,40.75996112823486,0.6382934437029759,1739502680.4849858,40.75996112823486,4.278649254254395,1739502680.4849875,40.75996112823486,1.5521846555925343 +1739502680.504906,40.77996110916138,43.54867757999823,1739502680.5049086,40.77996110916138,5.145431621012044,1739502680.5049117,40.77996110916138,66.89953670712414,1739502680.5049148,40.77996110916138,41.075507614180346,1739502680.5049162,40.77996110916138,0.6788964864947077,1739502680.5049179,40.77996110916138,-2.0764842651809037,1739502680.5049193,40.77996110916138,-0.42143969748874155,1739502680.5049205,40.77996110916138,-0.12409835637520397,1739502680.5049222,40.77996110916138,1.7845012668796068,1739502680.5049236,40.77996110916138,0.0,1739502680.504925,40.77996110916138,-0.048830677608906525,1739502680.5049264,40.77996110916138,4.289340691627053,1739502680.5049276,40.77996110916138,1.6186055157929324 +1739502680.524664,40.79996109008789,43.54867757999823,1739502680.5246663,40.79996109008789,5.145431621012044,1739502680.5246692,40.79996109008789,66.89953670712414,1739502680.5246844,40.79996109008789,41.075507614180346,1739502680.524689,40.79996109008789,0.6788964864947077,1739502680.5246942,40.79996109008789,-2.0764842651809037,1739502680.5246987,40.79996109008789,-0.42143969748874155,1739502680.5247028,40.79996109008789,-0.12409835637520397,1739502680.5247066,40.79996109008789,1.7845012668796068,1739502680.5247107,40.79996109008789,0.0,1739502680.5247145,40.79996109008789,0.16589575108667431,1739502680.5247185,40.79996109008789,4.289340691627053,1739502680.5247226,40.79996109008789,1.6186055157929324 +1739502680.5450573,40.819961071014404,43.54867757999823,1739502680.54506,40.819961071014404,5.145431621012044,1739502680.5450633,40.819961071014404,66.89953670712414,1739502680.5450664,40.819961071014404,41.075507614180346,1739502680.545068,40.819961071014404,0.6788964864947077,1739502680.54507,40.819961071014404,-2.0764842651809037,1739502680.5450716,40.819961071014404,-0.42143969748874155,1739502680.5450733,40.819961071014404,-0.12409835637520397,1739502680.5450745,40.819961071014404,1.7845012668796068,1739502680.5450761,40.819961071014404,0.0,1739502680.5450778,40.819961071014404,0.16589575108667431,1739502680.5450795,40.819961071014404,4.289340691627053,1739502680.5450814,40.819961071014404,1.6186055157929324 +1739502680.5653858,40.83996105194092,43.54867757999823,1739502680.565389,40.83996105194092,5.145431621012044,1739502680.5653927,40.83996105194092,66.89953670712414,1739502680.5653963,40.83996105194092,41.075507614180346,1739502680.565398,40.83996105194092,0.6788964864947077,1739502680.5654004,40.83996105194092,-2.0764842651809037,1739502680.565402,40.83996105194092,-0.42143969748874155,1739502680.5654037,40.83996105194092,-0.12409835637520397,1739502680.5654054,40.83996105194092,1.7845012668796068,1739502680.5654075,40.83996105194092,0.0,1739502680.5654092,40.83996105194092,0.16589575108667431,1739502680.565411,40.83996105194092,4.289340691627053,1739502680.5654128,40.83996105194092,1.6186055157929324 +1739502680.5853577,40.85996103286743,43.54867757999823,1739502680.5853605,40.85996103286743,5.145431621012044,1739502680.5853646,40.85996103286743,66.89953670712414,1739502680.585368,40.85996103286743,41.075507614180346,1739502680.5853696,40.85996103286743,0.6788964864947077,1739502680.585372,40.85996103286743,-2.0764842651809037,1739502680.5853736,40.85996103286743,-0.42143969748874155,1739502680.5853755,40.85996103286743,-0.12409835637520397,1739502680.585377,40.85996103286743,1.7845012668796068,1739502680.5853791,40.85996103286743,0.0,1739502680.5853806,40.85996103286743,0.16589575108667431,1739502680.5853825,40.85996103286743,4.289340691627053,1739502680.5853844,40.85996103286743,1.6186055157929324 +1739502680.6056633,40.879961013793945,43.47565661434227,1739502680.6056664,40.879961013793945,4.981270551737543,1739502680.60567,40.879961013793945,67.03122766164026,1739502680.6056736,40.879961013793945,40.91558781424563,1739502680.6056752,40.879961013793945,0.5914398266275426,1739502680.6056774,40.879961013793945,-2.0987576073749072,1739502680.605679,40.879961013793945,-0.5813373298690442,1739502680.6056812,40.879961013793945,-0.17269363218323736,1739502680.6056826,40.879961013793945,1.570228056893437,1739502680.6056848,40.879961013793945,0.0,1739502680.6056864,40.879961013793945,-0.1825842228256523,1739502680.6056886,40.879961013793945,4.29907491384199,1739502680.6056905,40.879961013793945,1.6439122164710418 +1739502680.6254153,40.89996099472046,43.47565661434227,1739502680.6254182,40.89996099472046,4.981270551737543,1739502680.6254222,40.89996099472046,67.03122766164026,1739502680.6254258,40.89996099472046,40.91558781424563,1739502680.6254275,40.89996099472046,0.5914398266275426,1739502680.6254299,40.89996099472046,-2.0987576073749072,1739502680.6254315,40.89996099472046,-0.5813373298690442,1739502680.6254332,40.89996099472046,-0.17269363218323736,1739502680.6254349,40.89996099472046,1.570228056893437,1739502680.625437,40.89996099472046,0.0,1739502680.6254387,40.89996099472046,-0.07368415957760477,1739502680.6254406,40.89996099472046,4.29907491384199,1739502680.6254425,40.89996099472046,1.6439122164710418 +1739502680.6454177,40.91996097564697,43.47565661434227,1739502680.645421,40.91996097564697,4.981270551737543,1739502680.645425,40.91996097564697,67.03122766164026,1739502680.6454287,40.91996097564697,40.91558781424563,1739502680.6454306,40.91996097564697,0.5914398266275426,1739502680.645433,40.91996097564697,-2.0987576073749072,1739502680.6454346,40.91996097564697,-0.5813373298690442,1739502680.6454365,40.91996097564697,-0.17269363218323736,1739502680.6454382,40.91996097564697,1.570228056893437,1739502680.6454403,40.91996097564697,0.0,1739502680.6454418,40.91996097564697,-0.07368415957760477,1739502680.645444,40.91996097564697,4.29907491384199,1739502680.6454456,40.91996097564697,1.6439122164710418 +1739502680.6653914,40.939960956573486,43.47565661434227,1739502680.665394,40.939960956573486,4.981270551737543,1739502680.6653984,40.939960956573486,67.03122766164026,1739502680.665402,40.939960956573486,40.91558781424563,1739502680.6654034,40.939960956573486,0.5914398266275426,1739502680.665406,40.939960956573486,-2.0987576073749072,1739502680.6654077,40.939960956573486,-0.5813373298690442,1739502680.6654096,40.939960956573486,-0.17269363218323736,1739502680.665411,40.939960956573486,1.570228056893437,1739502680.6654131,40.939960956573486,0.0,1739502680.6654148,40.939960956573486,-0.07368415957760477,1739502680.6654167,40.939960956573486,4.29907491384199,1739502680.6654189,40.939960956573486,1.6439122164710418 +1739502680.6853511,40.9599609375,43.47565661434227,1739502680.6853545,40.9599609375,4.981270551737543,1739502680.6853583,40.9599609375,67.03122766164026,1739502680.6853619,40.9599609375,40.91558781424563,1739502680.6853635,40.9599609375,0.5914398266275426,1739502680.6853657,40.9599609375,-2.0987576073749072,1739502680.6853676,40.9599609375,-0.5813373298690442,1739502680.6853693,40.9599609375,-0.17269363218323736,1739502680.685371,40.9599609375,1.570228056893437,1739502680.6853728,40.9599609375,0.0,1739502680.6853747,40.9599609375,-0.07368415957760477,1739502680.6853764,40.9599609375,4.29907491384199,1739502680.6853783,40.9599609375,1.6439122164710418 +1739502680.7056446,40.979960918426514,43.47565661434227,1739502680.705648,40.979960918426514,4.981270551737543,1739502680.705652,40.979960918426514,67.03122766164026,1739502680.7056556,40.979960918426514,40.91558781424563,1739502680.7056572,40.979960918426514,0.5914398266275426,1739502680.7056596,40.979960918426514,-2.0987576073749072,1739502680.7056615,40.979960918426514,-0.5813373298690442,1739502680.7056632,40.979960918426514,-0.17269363218323736,1739502680.705665,40.979960918426514,1.570228056893437,1739502680.705667,40.979960918426514,0.0,1739502680.7056687,40.979960918426514,-0.07368415957760477,1739502680.7056706,40.979960918426514,4.29907491384199,1739502680.7056727,40.979960918426514,1.6439122164710418 +1739502680.7254367,40.99996089935303,43.40383916445726,1739502680.72544,40.99996089935303,4.815697594816973,1739502680.7254436,40.99996089935303,67.03605721872654,1739502680.7254472,40.99996089935303,40.92528711691458,1739502680.7254488,40.99996089935303,0.5964760030133427,1739502680.7254512,40.99996089935303,-2.101931545683271,1739502680.725453,40.99996089935303,-0.6176923579006497,1739502680.7254546,40.99996089935303,-0.19782790001947298,1739502680.7254562,40.99996089935303,1.5252172295989825,1739502680.7254584,40.99996089935303,0.0,1739502680.7254603,40.99996089935303,-0.1276938174570042,1739502680.725462,40.99996089935303,4.307821929558391,1739502680.725464,40.99996089935303,1.6360330179025762 +1739502680.7457163,41.01996088027954,43.40383916445726,1739502680.7457192,41.01996088027954,4.815697594816973,1739502680.7457232,41.01996088027954,67.03605721872654,1739502680.7457268,41.01996088027954,40.92528711691458,1739502680.7457287,41.01996088027954,0.5964760030133427,1739502680.7457309,41.01996088027954,-2.101931545683271,1739502680.7457325,41.01996088027954,-0.6176923579006497,1739502680.7457345,41.01996088027954,-0.19782790001947298,1739502680.745736,41.01996088027954,1.5252172295989825,1739502680.745738,41.01996088027954,0.0,1739502680.7457397,41.01996088027954,-0.11081578830359362,1739502680.7457418,41.01996088027954,4.307821929558391,1739502680.7457435,41.01996088027954,1.6360330179025762 +1739502680.7652597,41.039960861206055,43.40383916445726,1739502680.765263,41.039960861206055,4.815697594816973,1739502680.7652667,41.039960861206055,67.03605721872654,1739502680.7652705,41.039960861206055,40.92528711691458,1739502680.7652724,41.039960861206055,0.5964760030133427,1739502680.7652745,41.039960861206055,-2.101931545683271,1739502680.7652764,41.039960861206055,-0.6176923579006497,1739502680.7652786,41.039960861206055,-0.19782790001947298,1739502680.76528,41.039960861206055,1.5252172295989825,1739502680.7652822,41.039960861206055,0.0,1739502680.7652836,41.039960861206055,-0.11081578830359362,1739502680.7652857,41.039960861206055,4.307821929558391,1739502680.7652874,41.039960861206055,1.6360330179025762 +1739502680.7849746,41.05996084213257,43.40383916445726,1739502680.7849774,41.05996084213257,4.815697594816973,1739502680.7849805,41.05996084213257,67.03605721872654,1739502680.7849832,41.05996084213257,40.92528711691458,1739502680.7849844,41.05996084213257,0.5964760030133427,1739502680.7849867,41.05996084213257,-2.101931545683271,1739502680.784988,41.05996084213257,-0.6176923579006497,1739502680.784989,41.05996084213257,-0.19782790001947298,1739502680.7849905,41.05996084213257,1.5252172295989825,1739502680.784992,41.05996084213257,0.0,1739502680.784994,41.05996084213257,-0.11081578830359362,1739502680.784995,41.05996084213257,4.307821929558391,1739502680.7849965,41.05996084213257,1.6360330179025762 +1739502680.8046472,41.07996082305908,43.40383916445726,1739502680.8046494,41.07996082305908,4.815697594816973,1739502680.804652,41.07996082305908,67.03605721872654,1739502680.8046546,41.07996082305908,40.92528711691458,1739502680.8046558,41.07996082305908,0.5964760030133427,1739502680.8046577,41.07996082305908,-2.101931545683271,1739502680.804659,41.07996082305908,-0.6176923579006497,1739502680.8046603,41.07996082305908,-0.19782790001947298,1739502680.8046615,41.07996082305908,1.5252172295989825,1739502680.804663,41.07996082305908,0.0,1739502680.8046644,41.07996082305908,-0.11081578830359362,1739502680.8046658,41.07996082305908,4.307821929558391,1739502680.8046672,41.07996082305908,1.6360330179025762 +1739502680.8248827,41.099960803985596,43.33381696021285,1739502680.8248847,41.099960803985596,4.650525604353186,1739502680.8248878,41.099960803985596,67.04086697349028,1739502680.8248906,41.099960803985596,40.941830608385715,1739502680.8248925,41.099960803985596,0.6050658928156597,1739502680.8248942,41.099960803985596,-2.104776996341631,1739502680.8248954,41.099960803985596,-0.6425849005217806,1739502680.8248968,41.099960803985596,-0.22302173079571705,1739502680.824898,41.099960803985596,1.4951444308742827,1739502680.8249002,41.099960803985596,0.0,1739502680.8249016,41.099960803985596,-0.13750321917659447,1739502680.8249032,41.099960803985596,4.315566365104971,1739502680.8249047,41.099960803985596,1.6243078224350473 +1739502680.845259,41.11996078491211,43.33381696021285,1739502680.845262,41.11996078491211,4.650525604353186,1739502680.8452656,41.11996078491211,67.04086697349028,1739502680.8452687,41.11996078491211,40.941830608385715,1739502680.8452709,41.11996078491211,0.6050658928156597,1739502680.8452728,41.11996078491211,-2.104776996341631,1739502680.8452747,41.11996078491211,-0.6425849005217806,1739502680.8452764,41.11996078491211,-0.22302173079571705,1739502680.845278,41.11996078491211,1.4951444308742827,1739502680.84528,41.11996078491211,0.0,1739502680.8452816,41.11996078491211,-0.12916339156076462,1739502680.8452833,41.11996078491211,4.315566365104971,1739502680.8452852,41.11996078491211,1.6243078224350473 +1739502680.8657105,41.13996076583862,43.33381696021285,1739502680.8657138,41.13996076583862,4.650525604353186,1739502680.8657184,41.13996076583862,67.04086697349028,1739502680.8657222,41.13996076583862,40.941830608385715,1739502680.865724,41.13996076583862,0.6050658928156597,1739502680.8657262,41.13996076583862,-2.104776996341631,1739502680.8657281,41.13996076583862,-0.6425849005217806,1739502680.86573,41.13996076583862,-0.22302173079571705,1739502680.8657315,41.13996076583862,1.4951444308742827,1739502680.8657339,41.13996076583862,0.0,1739502680.8657358,41.13996076583862,-0.12916339156076462,1739502680.8657374,41.13996076583862,4.315566365104971,1739502680.8657396,41.13996076583862,1.6243078224350473 +1739502680.8855896,41.15996074676514,43.33381696021285,1739502680.8855925,41.15996074676514,4.650525604353186,1739502680.8855968,41.15996074676514,67.04086697349028,1739502680.8856003,41.15996074676514,40.941830608385715,1739502680.885602,41.15996074676514,0.6050658928156597,1739502680.8856046,41.15996074676514,-2.104776996341631,1739502680.8856063,41.15996074676514,-0.6425849005217806,1739502680.8856082,41.15996074676514,-0.22302173079571705,1739502680.8856099,41.15996074676514,1.4951444308742827,1739502680.8856122,41.15996074676514,0.0,1739502680.8856142,41.15996074676514,-0.12916339156076462,1739502680.885616,41.15996074676514,4.315566365104971,1739502680.8856182,41.15996074676514,1.6243078224350473 +1739502680.905721,41.17996072769165,43.33381696021285,1739502680.9057245,41.17996072769165,4.650525604353186,1739502680.9057283,41.17996072769165,67.04086697349028,1739502680.9057322,41.17996072769165,40.941830608385715,1739502680.9057338,41.17996072769165,0.6050658928156597,1739502680.9057364,41.17996072769165,-2.104776996341631,1739502680.9057386,41.17996072769165,-0.6425849005217806,1739502680.9057403,41.17996072769165,-0.22302173079571705,1739502680.9057422,41.17996072769165,1.4951444308742827,1739502680.905744,41.17996072769165,0.0,1739502680.905746,41.17996072769165,-0.12916339156076462,1739502680.9057481,41.17996072769165,4.315566365104971,1739502680.9057503,41.17996072769165,1.6243078224350473 +1739502680.9256172,41.199960708618164,43.33381696021285,1739502680.9256208,41.199960708618164,4.650525604353186,1739502680.9256246,41.199960708618164,67.04086697349028,1739502680.9256284,41.199960708618164,40.941830608385715,1739502680.9256306,41.199960708618164,0.6050658928156597,1739502680.9256327,41.199960708618164,-2.104776996341631,1739502680.9256349,41.199960708618164,-0.6425849005217806,1739502680.9256365,41.199960708618164,-0.22302173079571705,1739502680.9256384,41.199960708618164,1.4951444308742827,1739502680.9256408,41.199960708618164,0.0,1739502680.9256425,41.199960708618164,-0.12916339156076462,1739502680.9256446,41.199960708618164,4.315566365104971,1739502680.9256463,41.199960708618164,1.6243078224350473 +1739502680.9457893,41.21996068954468,43.26554903788969,1739502680.9457934,41.21996068954468,4.4861698697564005,1739502680.9457974,41.21996068954468,67.40100505017455,1739502680.9458015,41.21996068954468,40.64079566198971,1739502680.9458034,41.21996068954468,0.4656482183172033,1739502680.945806,41.21996068954468,-2.149164748366473,1739502680.945808,41.21996068954468,-0.8986787848935566,1739502680.9458098,41.21996068954468,-0.29839075689031586,1739502680.9458117,41.21996068954468,1.218167528750256,1739502680.9458137,41.21996068954468,0.0,1739502680.9458158,41.21996068954468,-0.5114955234685237,1739502680.945818,41.21996068954468,4.322299161128889,1739502680.9458199,41.21996068954468,1.6101841826611536 +1739502680.96551,41.23996067047119,43.26554903788969,1739502680.9655132,41.23996067047119,4.4861698697564005,1739502680.9655173,41.23996067047119,67.40100505017455,1739502680.9655213,41.23996067047119,40.64079566198971,1739502680.9655235,41.23996067047119,0.4656482183172033,1739502680.9655259,41.23996067047119,-2.149164748366473,1739502680.9655278,41.23996067047119,-0.8986787848935566,1739502680.9655294,41.23996067047119,-0.29839075689031586,1739502680.965531,41.23996067047119,1.218167528750256,1739502680.9655335,41.23996067047119,0.0,1739502680.9655352,41.23996067047119,-0.3920166539108976,1739502680.965537,41.23996067047119,4.322299161128889,1739502680.9655392,41.23996067047119,1.6101841826611536 +1739502680.9854646,41.259960651397705,43.26554903788969,1739502680.9854677,41.259960651397705,4.4861698697564005,1739502680.9854717,41.259960651397705,67.40100505017455,1739502680.9854755,41.259960651397705,40.64079566198971,1739502680.9854777,41.259960651397705,0.4656482183172033,1739502680.9854798,41.259960651397705,-2.149164748366473,1739502680.9854822,41.259960651397705,-0.8986787848935566,1739502680.9854841,41.259960651397705,-0.29839075689031586,1739502680.9854858,41.259960651397705,1.218167528750256,1739502680.985488,41.259960651397705,0.0,1739502680.9854896,41.259960651397705,-0.3920166539108976,1739502680.9854918,41.259960651397705,4.322299161128889,1739502680.9854937,41.259960651397705,1.6101841826611536 +1739502681.005797,41.27996063232422,43.26554903788969,1739502681.0058005,41.27996063232422,4.4861698697564005,1739502681.0058045,41.27996063232422,67.40100505017455,1739502681.0058084,41.27996063232422,40.64079566198971,1739502681.0058105,41.27996063232422,0.4656482183172033,1739502681.0058126,41.27996063232422,-2.149164748366473,1739502681.0058148,41.27996063232422,-0.8986787848935566,1739502681.0058165,41.27996063232422,-0.29839075689031586,1739502681.0058184,41.27996063232422,1.218167528750256,1739502681.0058208,41.27996063232422,0.0,1739502681.0058224,41.27996063232422,-0.3920166539108976,1739502681.0058246,41.27996063232422,4.322299161128889,1739502681.0058265,41.27996063232422,1.6101841826611536 +1739502681.0252953,41.29996061325073,43.26554903788969,1739502681.0252986,41.29996061325073,4.4861698697564005,1739502681.025303,41.29996061325073,67.40100505017455,1739502681.025307,41.29996061325073,40.64079566198971,1739502681.0253086,41.29996061325073,0.4656482183172033,1739502681.025311,41.29996061325073,-2.149164748366473,1739502681.0253127,41.29996061325073,-0.8986787848935566,1739502681.0253146,41.29996061325073,-0.29839075689031586,1739502681.0253162,41.29996061325073,1.218167528750256,1739502681.0253186,41.29996061325073,0.0,1739502681.0253208,41.29996061325073,-0.3920166539108976,1739502681.0253227,41.29996061325073,4.322299161128889,1739502681.0253246,41.29996061325073,1.6101841826611536 +1739502681.0458724,41.319960594177246,43.199256158678075,1739502681.045876,41.319960594177246,4.3237047370920365,1739502681.0458803,41.319960594177246,67.41388927742146,1739502681.0458841,41.319960594177246,40.691904895719276,1739502681.0458863,41.319960594177246,0.48683295639169855,1739502681.0458884,41.319960594177246,-2.149619953358518,1739502681.0458903,41.319960594177246,-0.8855914871577935,1739502681.0458922,41.319960594177246,-0.322496011267461,1739502681.045894,41.319960594177246,1.2309885455313305,1739502681.0458963,41.319960594177246,0.0,1739502681.045898,41.319960594177246,-0.3237603670175679,1739502681.0459,41.319960594177246,4.32800145057792,1739502681.045902,41.319960594177246,1.5760790161881697 +1739502681.065304,41.33996057510376,43.199256158678075,1739502681.0653074,41.33996057510376,4.3237047370920365,1739502681.0653114,41.33996057510376,67.41388927742146,1739502681.0653152,41.33996057510376,40.691904895719276,1739502681.0653172,41.33996057510376,0.48683295639169855,1739502681.0653195,41.33996057510376,-2.149619953358518,1739502681.0653214,41.33996057510376,-0.8855914871577935,1739502681.0653234,41.33996057510376,-0.322496011267461,1739502681.065325,41.33996057510376,1.2309885455313305,1739502681.0653272,41.33996057510376,0.0,1739502681.065329,41.33996057510376,-0.3450904706568392,1739502681.0653312,41.33996057510376,4.32800145057792,1739502681.0653334,41.33996057510376,1.5760790161881697 +1739502681.092999,41.35996055603027,43.199256158678075,1739502681.0930076,41.35996055603027,4.3237047370920365,1739502681.0930197,41.35996055603027,67.41388927742146,1739502681.0930297,41.35996055603027,40.691904895719276,1739502681.0930343,41.35996055603027,0.48683295639169855,1739502681.0930405,41.35996055603027,-2.149619953358518,1739502681.0930452,41.35996055603027,-0.8855914871577935,1739502681.0930498,41.35996055603027,-0.322496011267461,1739502681.0930548,41.35996055603027,1.2309885455313305,1739502681.09306,41.35996055603027,0.0,1739502681.093065,41.35996055603027,-0.3450904706568392,1739502681.0930698,41.35996055603027,4.32800145057792,1739502681.093075,41.35996055603027,1.5760790161881697 +1739502681.1234312,41.389960527420044,43.199256158678075,1739502681.123439,41.389960527420044,4.3237047370920365,1739502681.123449,41.389960527420044,67.41388927742146,1739502681.1234596,41.389960527420044,40.691904895719276,1739502681.1234648,41.389960527420044,0.48683295639169855,1739502681.1234708,41.389960527420044,-2.149619953358518,1739502681.1234763,41.389960527420044,-0.8855914871577935,1739502681.123481,41.389960527420044,-0.322496011267461,1739502681.123486,41.389960527420044,1.2309885455313305,1739502681.1234918,41.389960527420044,0.0,1739502681.1234965,41.389960527420044,-0.3450904706568392,1739502681.1235018,41.389960527420044,4.32800145057792,1739502681.123507,41.389960527420044,1.5760790161881697 +1739502681.1468096,41.40996050834656,43.199256158678075,1739502681.1468189,41.40996050834656,4.3237047370920365,1739502681.1468298,41.40996050834656,67.41388927742146,1739502681.1468396,41.40996050834656,40.691904895719276,1739502681.1468444,41.40996050834656,0.48683295639169855,1739502681.1468503,41.40996050834656,-2.149619953358518,1739502681.146855,41.40996050834656,-0.8855914871577935,1739502681.14686,41.40996050834656,-0.322496011267461,1739502681.1468647,41.40996050834656,1.2309885455313305,1739502681.1468704,41.40996050834656,0.0,1739502681.1468751,41.40996050834656,-0.3450904706568392,1739502681.1468801,41.40996050834656,4.32800145057792,1739502681.1468856,41.40996050834656,1.5760790161881697 +1739502681.1813176,41.449960470199585,43.135217579243886,1739502681.1813223,41.449960470199585,4.164391114185152,1739502681.1813278,41.449960470199585,67.42651098704923,1739502681.181333,41.449960470199585,40.741302228455844,1739502681.1813354,41.449960470199585,0.5083991798406686,1739502681.1813388,41.449960470199585,-2.1505330983045248,1739502681.1813421,41.449960470199585,-0.8681271292782405,1739502681.1813447,41.449960470199585,-0.3475584301371821,1739502681.1813474,41.449960470199585,1.248307992611735,1739502681.1813505,41.449960470199585,0.0,1739502681.1813533,41.449960470199585,-0.27151248584066157,1739502681.181356,41.449960470199585,4.332637600100819,1739502681.1813588,41.449960470199585,1.5428136137829265 +1739502681.200146,41.479960441589355,43.135217579243886,1739502681.200149,41.479960441589355,4.164391114185152,1739502681.2001526,41.479960441589355,67.42651098704923,1739502681.2001557,41.479960441589355,40.741302228455844,1739502681.2001572,41.479960441589355,0.5083991798406686,1739502681.2001593,41.479960441589355,-2.1505330983045248,1739502681.2001607,41.479960441589355,-0.8681271292782405,1739502681.2001626,41.479960441589355,-0.3475584301371821,1739502681.200164,41.479960441589355,1.248307992611735,1739502681.200166,41.479960441589355,0.0,1739502681.2001674,41.479960441589355,-0.2945056211711914,1739502681.2001693,41.479960441589355,4.332637600100819,1739502681.200171,41.479960441589355,1.5428136137829265 +1739502681.2192035,41.49996042251587,43.135217579243886,1739502681.2192063,41.49996042251587,4.164391114185152,1739502681.2192094,41.49996042251587,67.42651098704923,1739502681.2192123,41.49996042251587,40.741302228455844,1739502681.2192135,41.49996042251587,0.5083991798406686,1739502681.2192154,41.49996042251587,-2.1505330983045248,1739502681.2192168,41.49996042251587,-0.8681271292782405,1739502681.2192183,41.49996042251587,-0.3475584301371821,1739502681.2192194,41.49996042251587,1.248307992611735,1739502681.2192209,41.49996042251587,0.0,1739502681.2192223,41.49996042251587,-0.2945056211711914,1739502681.2192237,41.49996042251587,4.332637600100819,1739502681.2192254,41.49996042251587,1.5428136137829265 +1739502681.2396955,41.51996040344238,43.135217579243886,1739502681.2396986,41.51996040344238,4.164391114185152,1739502681.2397015,41.51996040344238,67.42651098704923,1739502681.2397046,41.51996040344238,40.741302228455844,1739502681.2397058,41.51996040344238,0.5083991798406686,1739502681.2397077,41.51996040344238,-2.1505330983045248,1739502681.239709,41.51996040344238,-0.8681271292782405,1739502681.2397106,41.51996040344238,-0.3475584301371821,1739502681.2397118,41.51996040344238,1.248307992611735,1739502681.2397132,41.51996040344238,0.0,1739502681.2397146,41.51996040344238,-0.2945056211711914,1739502681.239716,41.51996040344238,4.332637600100819,1739502681.2397177,41.51996040344238,1.5428136137829265 +1739502681.2588277,41.5399603843689,43.07318573034666,1739502681.2588305,41.5399603843689,4.008200158137457,1739502681.2588334,41.5399603843689,67.46907941349103,1739502681.258836,41.5399603843689,40.76251227236112,1739502681.2588372,41.5399603843689,0.5182186446116313,1739502681.2588391,41.5399603843689,-2.155622098727374,1739502681.2588403,41.5399603843689,-0.8669326939319677,1739502681.2588418,41.5399603843689,-0.37802938440756595,1739502681.258843,41.5399603843689,1.249501381242684,1739502681.2588444,41.5399603843689,0.0,1739502681.2588458,41.5399603843689,-0.2448125116539764,1739502681.2588472,41.5399603843689,4.336196541187949,1739502681.2588484,41.5399603843689,1.509842999802466 +1739502681.281232,41.55996036529541,43.07318573034666,1739502681.281236,41.55996036529541,4.008200158137457,1739502681.2812405,41.55996036529541,67.46907941349103,1739502681.2812457,41.55996036529541,40.76251227236112,1739502681.2812486,41.55996036529541,0.5182186446116313,1739502681.2812521,41.55996036529541,-2.155622098727374,1739502681.2812555,41.55996036529541,-0.8669326939319677,1739502681.2812586,41.55996036529541,-0.37802938440756595,1739502681.281262,41.55996036529541,1.249501381242684,1739502681.2812653,41.55996036529541,0.0,1739502681.2812681,41.55996036529541,-0.260341618559782,1739502681.2812715,41.55996036529541,4.336196541187949,1739502681.281275,41.55996036529541,1.509842999802466 +1739502681.2986667,41.579960346221924,43.07318573034666,1739502681.2986696,41.579960346221924,4.008200158137457,1739502681.298673,41.579960346221924,67.46907941349103,1739502681.2986755,41.579960346221924,40.76251227236112,1739502681.298677,41.579960346221924,0.5182186446116313,1739502681.2986786,41.579960346221924,-2.155622098727374,1739502681.29868,41.579960346221924,-0.8669326939319677,1739502681.2986813,41.579960346221924,-0.37802938440756595,1739502681.2986827,41.579960346221924,1.249501381242684,1739502681.2986841,41.579960346221924,0.0,1739502681.2986856,41.579960346221924,-0.260341618559782,1739502681.2986867,41.579960346221924,4.336196541187949,1739502681.2986882,41.579960346221924,1.509842999802466 +1739502681.318616,41.59996032714844,43.07318573034666,1739502681.318618,41.59996032714844,4.008200158137457,1739502681.3186212,41.59996032714844,67.46907941349103,1739502681.3186238,41.59996032714844,40.76251227236112,1739502681.318625,41.59996032714844,0.5182186446116313,1739502681.3186269,41.59996032714844,-2.155622098727374,1739502681.318628,41.59996032714844,-0.8669326939319677,1739502681.3186293,41.59996032714844,-0.37802938440756595,1739502681.3186307,41.59996032714844,1.249501381242684,1739502681.3186324,41.59996032714844,0.0,1739502681.3186338,41.59996032714844,-0.260341618559782,1739502681.3186352,41.59996032714844,4.336196541187949,1739502681.3186367,41.59996032714844,1.509842999802466 +1739502681.3390498,41.61996030807495,43.07318573034666,1739502681.339053,41.61996030807495,4.008200158137457,1739502681.339056,41.61996030807495,67.46907941349103,1739502681.339059,41.61996030807495,40.76251227236112,1739502681.3390605,41.61996030807495,0.5182186446116313,1739502681.3390622,41.61996030807495,-2.155622098727374,1739502681.3390641,41.61996030807495,-0.8669326939319677,1739502681.3390656,41.61996030807495,-0.37802938440756595,1739502681.339067,41.61996030807495,1.249501381242684,1739502681.3390687,41.61996030807495,0.0,1739502681.3390698,41.61996030807495,-0.260341618559782,1739502681.3390718,41.61996030807495,4.336196541187949,1739502681.3390732,41.61996030807495,1.509842999802466 +1739502681.3588855,41.639960289001465,43.07318573034666,1739502681.3588884,41.639960289001465,4.008200158137457,1739502681.3588917,41.639960289001465,67.46907941349103,1739502681.3588943,41.639960289001465,40.76251227236112,1739502681.3588958,41.639960289001465,0.5182186446116313,1739502681.3588974,41.639960289001465,-2.155622098727374,1739502681.3588986,41.639960289001465,-0.8669326939319677,1739502681.3589,41.639960289001465,-0.37802938440756595,1739502681.3589013,41.639960289001465,1.249501381242684,1739502681.3589034,41.639960289001465,0.0,1739502681.3589046,41.639960289001465,-0.260341618559782,1739502681.358906,41.639960289001465,4.336196541187949,1739502681.3589077,41.639960289001465,1.509842999802466 +1739502681.3787925,41.65996026992798,43.01295574145203,1739502681.3787951,41.65996026992798,3.855181052824962,1739502681.378799,41.65996026992798,67.47155539003741,1739502681.3788016,41.65996026992798,40.819578914980625,1739502681.378803,41.65996026992798,0.5446383865651034,1739502681.3788047,41.65996026992798,-2.155938639115837,1739502681.3788064,41.65996026992798,-0.8333209621660153,1739502681.3788075,41.65996026992798,-0.40336414659146713,1739502681.3788087,41.65996026992798,1.2835555007825084,1739502681.3788104,41.65996026992798,0.0,1739502681.3788116,41.65996026992798,-0.16327259940423616,1739502681.3788133,41.65996026992798,4.338657978803536,1739502681.3788145,41.65996026992798,1.4771621885614308 +1739502681.3988461,41.67996025085449,43.01295574145203,1739502681.3988488,41.67996025085449,3.855181052824962,1739502681.3988516,41.67996025085449,67.47155539003741,1739502681.3988545,41.67996025085449,40.819578914980625,1739502681.398856,41.67996025085449,0.5446383865651034,1739502681.3988574,41.67996025085449,-2.155938639115837,1739502681.3988588,41.67996025085449,-0.8333209621660153,1739502681.39886,41.67996025085449,-0.40336414659146713,1739502681.3988614,41.67996025085449,1.2835555007825084,1739502681.3988628,41.67996025085449,0.0,1739502681.398864,41.67996025085449,-0.19360668777892243,1739502681.3988657,41.67996025085449,4.338657978803536,1739502681.398867,41.67996025085449,1.4771621885614308 +1739502681.4191043,41.699960231781006,43.01295574145203,1739502681.4191062,41.699960231781006,3.855181052824962,1739502681.419109,41.699960231781006,67.47155539003741,1739502681.4191117,41.699960231781006,40.819578914980625,1739502681.419113,41.699960231781006,0.5446383865651034,1739502681.4191146,41.699960231781006,-2.155938639115837,1739502681.4191158,41.699960231781006,-0.8333209621660153,1739502681.419117,41.699960231781006,-0.40336414659146713,1739502681.4191184,41.699960231781006,1.2835555007825084,1739502681.4191198,41.699960231781006,0.0,1739502681.4191213,41.699960231781006,-0.19360668777892243,1739502681.4191225,41.699960231781006,4.338657978803536,1739502681.4191236,41.699960231781006,1.4771621885614308 +1739502681.438596,41.71996021270752,43.01295574145203,1739502681.4385986,41.71996021270752,3.855181052824962,1739502681.4386024,41.71996021270752,67.47155539003741,1739502681.438605,41.71996021270752,40.819578914980625,1739502681.4386063,41.71996021270752,0.5446383865651034,1739502681.4386086,41.71996021270752,-2.155938639115837,1739502681.43861,41.71996021270752,-0.8333209621660153,1739502681.4386117,41.71996021270752,-0.40336414659146713,1739502681.438613,41.71996021270752,1.2835555007825084,1739502681.4386146,41.71996021270752,0.0,1739502681.4386158,41.71996021270752,-0.19360668777892243,1739502681.4386172,41.71996021270752,4.338657978803536,1739502681.438619,41.71996021270752,1.4771621885614308 +1739502681.4586883,41.73996019363403,43.01295574145203,1739502681.4586911,41.73996019363403,3.855181052824962,1739502681.4586942,41.73996019363403,67.47155539003741,1739502681.4586966,41.73996019363403,40.819578914980625,1739502681.458698,41.73996019363403,0.5446383865651034,1739502681.4586997,41.73996019363403,-2.155938639115837,1739502681.4587014,41.73996019363403,-0.8333209621660153,1739502681.4587026,41.73996019363403,-0.40336414659146713,1739502681.4587038,41.73996019363403,1.2835555007825084,1739502681.4587054,41.73996019363403,0.0,1739502681.4587066,41.73996019363403,-0.19360668777892243,1739502681.4587083,41.73996019363403,4.338657978803536,1739502681.45871,41.73996019363403,1.4771621885614308 +1739502681.4789596,41.75996017456055,42.95414466181501,1739502681.4789624,41.75996017456055,3.7049039016101837,1739502681.4789658,41.75996017456055,68.27914949115363,1739502681.4789689,41.75996017456055,40.10495806850803,1739502681.47897,41.75996017456055,0.2753781765883212,1739502681.4789722,41.75996017456055,-2.2640267233198945,1739502681.4789736,41.75996017456055,-1.4061153603287375,1739502681.4789753,41.75996017456055,-0.5373980544903364,1739502681.4789765,41.75996017456055,0.8117185953072014,1739502681.4789784,41.75996017456055,0.0,1739502681.4789798,41.75996017456055,-0.8484643128317292,1739502681.4789815,41.75996017456055,4.340003369734488,1739502681.478983,41.75996017456055,1.4555397661354288 +1739502681.4994926,41.77996015548706,42.95414466181501,1739502681.4994955,41.77996015548706,3.7049039016101837,1739502681.499499,41.77996015548706,68.27914949115363,1739502681.4995024,41.77996015548706,40.10495806850803,1739502681.499504,41.77996015548706,0.2753781765883212,1739502681.4995062,41.77996015548706,-2.2640267233198945,1739502681.499508,41.77996015548706,-1.4061153603287375,1739502681.4995098,41.77996015548706,-0.5373980544903364,1739502681.4995112,41.77996015548706,0.8117185953072014,1739502681.4995134,41.77996015548706,0.0,1739502681.499515,41.77996015548706,-0.6438211708282274,1739502681.499517,41.77996015548706,4.340003369734488,1739502681.4995184,41.77996015548706,1.4555397661354288 +1739502681.5191967,41.799960136413574,42.95414466181501,1739502681.5192,41.799960136413574,3.7049039016101837,1739502681.519204,41.799960136413574,68.27914949115363,1739502681.5192077,41.799960136413574,40.10495806850803,1739502681.5192094,41.799960136413574,0.2753781765883212,1739502681.519212,41.799960136413574,-2.2640267233198945,1739502681.519214,41.799960136413574,-1.4061153603287375,1739502681.5192158,41.799960136413574,-0.5373980544903364,1739502681.5192177,41.799960136413574,0.8117185953072014,1739502681.5192196,41.799960136413574,0.0,1739502681.5192213,41.799960136413574,-0.6438211708282274,1739502681.5192232,41.799960136413574,4.340003369734488,1739502681.5192251,41.799960136413574,1.4555397661354288 +1739502681.539393,41.81996011734009,42.95414466181501,1739502681.5393958,41.81996011734009,3.7049039016101837,1739502681.5393994,41.81996011734009,68.27914949115363,1739502681.5394027,41.81996011734009,40.10495806850803,1739502681.5394046,41.81996011734009,0.2753781765883212,1739502681.5394065,41.81996011734009,-2.2640267233198945,1739502681.5394084,41.81996011734009,-1.4061153603287375,1739502681.53941,41.81996011734009,-0.5373980544903364,1739502681.5394118,41.81996011734009,0.8117185953072014,1739502681.5394137,41.81996011734009,0.0,1739502681.5394156,41.81996011734009,-0.6438211708282274,1739502681.5394173,41.81996011734009,4.340003369734488,1739502681.5394194,41.81996011734009,1.4555397661354288 +1739502681.5592508,41.8399600982666,42.95414466181501,1739502681.5592716,41.8399600982666,3.7049039016101837,1739502681.559277,41.8399600982666,68.27914949115363,1739502681.5592828,41.8399600982666,40.10495806850803,1739502681.5592866,41.8399600982666,0.2753781765883212,1739502681.5592897,41.8399600982666,-2.2640267233198945,1739502681.5593023,41.8399600982666,-1.4061153603287375,1739502681.5593047,41.8399600982666,-0.5373980544903364,1739502681.5593064,41.8399600982666,0.8117185953072014,1739502681.5593102,41.8399600982666,0.0,1739502681.5593212,41.8399600982666,-0.6438211708282274,1739502681.5593245,41.8399600982666,4.340003369734488,1739502681.559328,41.8399600982666,1.4555397661354288 +1739502681.5792365,41.859960079193115,42.95414466181501,1739502681.57924,41.859960079193115,3.7049039016101837,1739502681.5792437,41.859960079193115,68.27914949115363,1739502681.5792475,41.859960079193115,40.10495806850803,1739502681.5792491,41.859960079193115,0.2753781765883212,1739502681.5792515,41.859960079193115,-2.2640267233198945,1739502681.5792532,41.859960079193115,-1.4061153603287375,1739502681.579255,41.859960079193115,-0.5373980544903364,1739502681.5792568,41.859960079193115,0.8117185953072014,1739502681.579259,41.859960079193115,0.0,1739502681.5792603,41.859960079193115,-0.6438211708282274,1739502681.5792623,41.859960079193115,4.340003369734488,1739502681.579264,41.859960079193115,1.4555397661354288 +1739502681.5991635,41.87996006011963,42.89734261908269,1739502681.5991666,41.87996006011963,3.559409600818748,1739502681.5991704,41.87996006011963,68.28185010243801,1739502681.5991743,41.87996006011963,40.24477790319495,1739502681.599176,41.87996006011963,0.3191289290223857,1739502681.599178,41.87996006011963,-2.2567893934420646,1739502681.59918,41.87996006011963,-1.292469253614125,1739502681.599182,41.87996006011963,-0.5594826619231604,1739502681.5991833,41.87996006011963,0.8889763284241763,1739502681.5991855,41.87996006011963,0.0,1739502681.5991871,41.87996006011963,-0.4229299283232433,1739502681.599189,41.87996006011963,4.3401653135963665,1739502681.5991907,41.87996006011963,1.380934815288877 +1739502681.6192114,41.89996004104614,42.89734261908269,1739502681.6192148,41.89996004104614,3.559409600818748,1739502681.6192193,41.89996004104614,68.28185010243801,1739502681.6192229,41.89996004104614,40.24477790319495,1739502681.619225,41.89996004104614,0.3191289290223857,1739502681.6192274,41.89996004104614,-2.2567893934420646,1739502681.619229,41.89996004104614,-1.292469253614125,1739502681.619231,41.89996004104614,-0.5594826619231604,1739502681.6192327,41.89996004104614,0.8889763284241763,1739502681.619235,41.89996004104614,0.0,1739502681.6192372,41.89996004104614,-0.4919584868647007,1739502681.6192389,41.89996004104614,4.3401653135963665,1739502681.6192408,41.89996004104614,1.380934815288877 +1739502681.6392558,41.919960021972656,42.89734261908269,1739502681.6392589,41.919960021972656,3.559409600818748,1739502681.6392627,41.919960021972656,68.28185010243801,1739502681.6392663,41.919960021972656,40.24477790319495,1739502681.639268,41.919960021972656,0.3191289290223857,1739502681.63927,41.919960021972656,-2.2567893934420646,1739502681.639272,41.919960021972656,-1.292469253614125,1739502681.6392736,41.919960021972656,-0.5594826619231604,1739502681.6392753,41.919960021972656,0.8889763284241763,1739502681.6392772,41.919960021972656,0.0,1739502681.6392791,41.919960021972656,-0.4919584868647007,1739502681.639281,41.919960021972656,4.3401653135963665,1739502681.639283,41.919960021972656,1.380934815288877 +1739502681.6592524,41.93996000289917,42.89734261908269,1739502681.6592555,41.93996000289917,3.559409600818748,1739502681.6592593,41.93996000289917,68.28185010243801,1739502681.6592631,41.93996000289917,40.24477790319495,1739502681.659265,41.93996000289917,0.3191289290223857,1739502681.6592672,41.93996000289917,-2.2567893934420646,1739502681.6592689,41.93996000289917,-1.292469253614125,1739502681.6592708,41.93996000289917,-0.5594826619231604,1739502681.6592722,41.93996000289917,0.8889763284241763,1739502681.6592743,41.93996000289917,0.0,1739502681.659276,41.93996000289917,-0.4919584868647007,1739502681.659278,41.93996000289917,4.3401653135963665,1739502681.6592796,41.93996000289917,1.380934815288877 +1739502681.6794488,41.959959983825684,42.89734261908269,1739502681.6794517,41.959959983825684,3.559409600818748,1739502681.6794553,41.959959983825684,68.28185010243801,1739502681.6794589,41.959959983825684,40.24477790319495,1739502681.6794605,41.959959983825684,0.3191289290223857,1739502681.6794627,41.959959983825684,-2.2567893934420646,1739502681.6794643,41.959959983825684,-1.292469253614125,1739502681.6794662,41.959959983825684,-0.5594826619231604,1739502681.6794677,41.959959983825684,0.8889763284241763,1739502681.6794698,41.959959983825684,0.0,1739502681.6794713,41.959959983825684,-0.4919584868647007,1739502681.6794734,41.959959983825684,4.3401653135963665,1739502681.6794748,41.959959983825684,1.380934815288877 +1739502681.6997323,41.9799599647522,42.84303533288678,1739502681.699736,41.9799599647522,3.4204713203572474,1739502681.69974,41.9799599647522,68.70435562471584,1739502681.6997437,41.9799599647522,39.94331340741879,1739502681.6997452,41.9799599647522,0.22952961728722776,1739502681.6997478,41.9799599647522,-2.3084167485095697,1739502681.6997495,41.9799599647522,-1.5362238867525442,1739502681.6997514,41.9799599647522,-0.6108,1739502681.699753,41.9799599647522,0.7314778219833772,1739502681.699755,41.9799599647522,0.0,1739502681.699757,41.9799599647522,-0.6425247733748723,1739502681.6997588,41.9799599647522,4.339067596757311,1739502681.6997607,41.9799599647522,1.3269505999741287 +1739502681.719181,41.99995994567871,42.84303533288678,1739502681.719184,41.99995994567871,3.4204713203572474,1739502681.7191873,41.99995994567871,68.70435562471584,1739502681.7191904,41.99995994567871,39.94331340741879,1739502681.719192,41.99995994567871,0.22952961728722776,1739502681.719194,41.99995994567871,-2.3084167485095697,1739502681.7191954,41.99995994567871,-1.5362238867525442,1739502681.7191973,41.99995994567871,-0.6108,1739502681.7191985,41.99995994567871,0.7314778219833772,1739502681.7192004,41.99995994567871,0.0,1739502681.7192018,41.99995994567871,-0.5954727779907515,1739502681.7192035,41.99995994567871,4.339067596757311,1739502681.7192051,41.99995994567871,1.3269505999741287 +1739502681.7390282,42.019959926605225,42.84303533288678,1739502681.7390306,42.019959926605225,3.4204713203572474,1739502681.7390335,42.019959926605225,68.70435562471584,1739502681.739036,42.019959926605225,39.94331340741879,1739502681.7390378,42.019959926605225,0.22952961728722776,1739502681.7390392,42.019959926605225,-2.3084167485095697,1739502681.7390406,42.019959926605225,-1.5362238867525442,1739502681.739042,42.019959926605225,-0.6108,1739502681.739043,42.019959926605225,0.7314778219833772,1739502681.7390447,42.019959926605225,0.0,1739502681.7390459,42.019959926605225,-0.5954727779907515,1739502681.7390475,42.019959926605225,4.339067596757311,1739502681.739049,42.019959926605225,1.3269505999741287 +1739502681.7586625,42.03995990753174,42.84303533288678,1739502681.7586656,42.03995990753174,3.4204713203572474,1739502681.7586694,42.03995990753174,68.70435562471584,1739502681.7586722,42.03995990753174,39.94331340741879,1739502681.7586737,42.03995990753174,0.22952961728722776,1739502681.7586753,42.03995990753174,-2.3084167485095697,1739502681.758677,42.03995990753174,-1.5362238867525442,1739502681.7586782,42.03995990753174,-0.6108,1739502681.7586796,42.03995990753174,0.7314778219833772,1739502681.7586813,42.03995990753174,0.0,1739502681.7586827,42.03995990753174,-0.5954727779907515,1739502681.7586842,42.03995990753174,4.339067596757311,1739502681.7586856,42.03995990753174,1.3269505999741287 +1739502681.7787676,42.05995988845825,42.84303533288678,1739502681.778771,42.05995988845825,3.4204713203572474,1739502681.7787745,42.05995988845825,68.70435562471584,1739502681.7787774,42.05995988845825,39.94331340741879,1739502681.7787786,42.05995988845825,0.22952961728722776,1739502681.7787805,42.05995988845825,-2.3084167485095697,1739502681.778782,42.05995988845825,-1.5362238867525442,1739502681.7787833,42.05995988845825,-0.6108,1739502681.7787845,42.05995988845825,0.7314778219833772,1739502681.7787864,42.05995988845825,0.0,1739502681.7787876,42.05995988845825,-0.5954727779907515,1739502681.778789,42.05995988845825,4.339067596757311,1739502681.7787907,42.05995988845825,1.3269505999741287 +1739502681.7987773,42.079959869384766,42.84303533288678,1739502681.7987797,42.079959869384766,3.4204713203572474,1739502681.7987828,42.079959869384766,68.70435562471584,1739502681.7987852,42.079959869384766,39.94331340741879,1739502681.7987869,42.079959869384766,0.22952961728722776,1739502681.7987885,42.079959869384766,-2.3084167485095697,1739502681.7987902,42.079959869384766,-1.5362238867525442,1739502681.7987914,42.079959869384766,-0.6108,1739502681.7987924,42.079959869384766,0.7314778219833772,1739502681.798794,42.079959869384766,0.0,1739502681.7987952,42.079959869384766,-0.5954727779907515,1739502681.798797,42.079959869384766,4.339067596757311,1739502681.7987983,42.079959869384766,1.3269505999741287 +1739502681.8186681,42.09995985031128,42.790895977750374,1739502681.8186707,42.09995985031128,3.2877367232804158,1739502681.818674,42.09995985031128,68.86843204714204,1739502681.8186772,42.09995985031128,39.9126092982924,1739502681.8186786,42.09995985031128,0.2216523245731002,1739502681.8186803,42.09995985031128,-2.3246124650084004,1739502681.818682,42.09995985031128,-1.5524274451388824,1739502681.8186834,42.09995985031128,-0.6108,1739502681.8186848,42.09995985031128,0.722056979493667,1739502681.8186867,42.09995985031128,0.0,1739502681.818688,42.09995985031128,-0.5129030054099115,1739502681.8186896,42.09995985031128,4.336667922003423,1739502681.818691,42.09995985031128,1.2607630557529026 +1739502681.8392112,42.11995983123779,42.790895977750374,1739502681.8392134,42.11995983123779,3.2877367232804158,1739502681.8392167,42.11995983123779,68.86843204714204,1739502681.839219,42.11995983123779,39.9126092982924,1739502681.8392208,42.11995983123779,0.2216523245731002,1739502681.8392224,42.11995983123779,-2.3246124650084004,1739502681.8392239,42.11995983123779,-1.5524274451388824,1739502681.839225,42.11995983123779,-0.6108,1739502681.8392265,42.11995983123779,0.722056979493667,1739502681.8392282,42.11995983123779,0.0,1739502681.8392293,42.11995983123779,-0.5387060762592356,1739502681.8392308,42.11995983123779,4.336667922003423,1739502681.839232,42.11995983123779,1.2607630557529026 +1739502681.8595712,42.13995981216431,42.790895977750374,1739502681.8595748,42.13995981216431,3.2877367232804158,1739502681.8595781,42.13995981216431,68.86843204714204,1739502681.8595812,42.13995981216431,39.9126092982924,1739502681.859583,42.13995981216431,0.2216523245731002,1739502681.859585,42.13995981216431,-2.3246124650084004,1739502681.8595865,42.13995981216431,-1.5524274451388824,1739502681.859588,42.13995981216431,-0.6108,1739502681.859589,42.13995981216431,0.722056979493667,1739502681.859591,42.13995981216431,0.0,1739502681.8595924,42.13995981216431,-0.5387060762592356,1739502681.8595936,42.13995981216431,4.336667922003423,1739502681.8595953,42.13995981216431,1.2607630557529026 +1739502681.878831,42.15995979309082,42.790895977750374,1739502681.8788338,42.15995979309082,3.2877367232804158,1739502681.878837,42.15995979309082,68.86843204714204,1739502681.8788397,42.15995979309082,39.9126092982924,1739502681.8788414,42.15995979309082,0.2216523245731002,1739502681.878843,42.15995979309082,-2.3246124650084004,1739502681.878845,42.15995979309082,-1.5524274451388824,1739502681.8788466,42.15995979309082,-0.6108,1739502681.8788483,42.15995979309082,0.722056979493667,1739502681.8788497,42.15995979309082,0.0,1739502681.8788512,42.15995979309082,-0.5387060762592356,1739502681.8788526,42.15995979309082,4.336667922003423,1739502681.8788538,42.15995979309082,1.2607630557529026 +1739502681.8988597,42.179959774017334,42.790895977750374,1739502681.8988621,42.179959774017334,3.2877367232804158,1739502681.898865,42.179959774017334,68.86843204714204,1739502681.8988676,42.179959774017334,39.9126092982924,1739502681.898869,42.179959774017334,0.2216523245731002,1739502681.8988707,42.179959774017334,-2.3246124650084004,1739502681.8988724,42.179959774017334,-1.5524274451388824,1739502681.8988736,42.179959774017334,-0.6108,1739502681.898875,42.179959774017334,0.722056979493667,1739502681.8988764,42.179959774017334,0.0,1739502681.8988776,42.179959774017334,-0.5387060762592356,1739502681.8988793,42.179959774017334,4.336667922003423,1739502681.8988807,42.179959774017334,1.2607630557529026 +1739502681.9189558,42.19995975494385,42.7408958853888,1739502681.9189582,42.19995975494385,3.161562816098746,1739502681.9189608,42.19995975494385,68.9551784645873,1739502681.9189637,42.19995975494385,39.9429546710575,1739502681.9189653,42.19995975494385,0.22942634469836984,1739502681.9189668,42.19995975494385,-2.3327793222924567,1739502681.9189684,42.19995975494385,-1.5127952544529952,1739502681.9189699,42.19995975494385,-0.6108,1739502681.918971,42.19995975494385,0.7453171312201596,1739502681.9189732,42.19995975494385,0.0,1739502681.9189744,42.19995975494385,-0.41900076831441657,1739502681.9189758,42.19995975494385,4.332930317907047,1739502681.9189773,42.19995975494385,1.2017258327938845 +1739502681.9393947,42.21995973587036,42.7408958853888,1739502681.9393973,42.21995973587036,3.161562816098746,1739502681.9394007,42.21995973587036,68.9551784645873,1739502681.9394035,42.21995973587036,39.9429546710575,1739502681.9394047,42.21995973587036,0.22942634469836984,1739502681.9394066,42.21995973587036,-2.3327793222924567,1739502681.939408,42.21995973587036,-1.5127952544529952,1739502681.9394097,42.21995973587036,-0.6108,1739502681.939411,42.21995973587036,0.7453171312201596,1739502681.9394128,42.21995973587036,0.0,1739502681.9394143,42.21995973587036,-0.4564087015737248,1739502681.9394155,42.21995973587036,4.332930317907047,1739502681.9394171,42.21995973587036,1.2017258327938845 +1739502681.958976,42.239959716796875,42.7408958853888,1739502681.9589787,42.239959716796875,3.161562816098746,1739502681.958982,42.239959716796875,68.9551784645873,1739502681.9589849,42.239959716796875,39.9429546710575,1739502681.9589863,42.239959716796875,0.22942634469836984,1739502681.9589882,42.239959716796875,-2.3327793222924567,1739502681.9589899,42.239959716796875,-1.5127952544529952,1739502681.958991,42.239959716796875,-0.6108,1739502681.9589927,42.239959716796875,0.7453171312201596,1739502681.9589942,42.239959716796875,0.0,1739502681.9589958,42.239959716796875,-0.4564087015737248,1739502681.9589975,42.239959716796875,4.332930317907047,1739502681.9589992,42.239959716796875,1.2017258327938845 +1739502681.978933,42.25995969772339,42.7408958853888,1739502681.9789367,42.25995969772339,3.161562816098746,1739502681.9789405,42.25995969772339,68.9551784645873,1739502681.9789438,42.25995969772339,39.9429546710575,1739502681.9789453,42.25995969772339,0.22942634469836984,1739502681.9789476,42.25995969772339,-2.3327793222924567,1739502681.9789493,42.25995969772339,-1.5127952544529952,1739502681.978951,42.25995969772339,-0.6108,1739502681.9789524,42.25995969772339,0.7453171312201596,1739502681.9789543,42.25995969772339,0.0,1739502681.9789555,42.25995969772339,-0.4564087015737248,1739502681.9789574,42.25995969772339,4.332930317907047,1739502681.9789586,42.25995969772339,1.2017258327938845 +1739502681.9991128,42.2799596786499,42.7408958853888,1739502681.9991155,42.2799596786499,3.161562816098746,1739502681.9991188,42.2799596786499,68.9551784645873,1739502681.999122,42.2799596786499,39.9429546710575,1739502681.9991236,42.2799596786499,0.22942634469836984,1739502681.9991252,42.2799596786499,-2.3327793222924567,1739502681.9991267,42.2799596786499,-1.5127952544529952,1739502681.9991283,42.2799596786499,-0.6108,1739502681.9991295,42.2799596786499,0.7453171312201596,1739502681.9991314,42.2799596786499,0.0,1739502681.9991326,42.2799596786499,-0.4564087015737248,1739502681.9991345,42.2799596786499,4.332930317907047,1739502681.999136,42.2799596786499,1.2017258327938845 +1739502682.018873,42.299959659576416,42.7408958853888,1739502682.018877,42.299959659576416,3.161562816098746,1739502682.0188806,42.299959659576416,68.9551784645873,1739502682.0188844,42.299959659576416,39.9429546710575,1739502682.018886,42.299959659576416,0.22942634469836984,1739502682.0188882,42.299959659576416,-2.3327793222924567,1739502682.01889,42.299959659576416,-1.5127952544529952,1739502682.0188916,42.299959659576416,-0.6108,1739502682.018893,42.299959659576416,0.7453171312201596,1739502682.0188951,42.299959659576416,0.0,1739502682.0188966,42.299959659576416,-0.4564087015737248,1739502682.0188982,42.299959659576416,4.332930317907047,1739502682.0189004,42.299959659576416,1.2017258327938845 +1739502682.0392594,42.31995964050293,42.692569220431736,1739502682.0392616,42.31995964050293,3.041142232904061,1739502682.039265,42.31995964050293,69.11120795870492,1739502682.0392678,42.31995964050293,39.887243251212894,1739502682.0392694,42.31995964050293,0.21531081280322406,1739502682.039271,42.31995964050293,-2.352553078874743,1739502682.0392728,42.31995964050293,-1.540388864314363,1739502682.0392742,42.31995964050293,-0.6108,1739502682.0392754,42.31995964050293,0.7290446069764669,1739502682.0392773,42.31995964050293,0.0,1739502682.0392785,42.31995964050293,-0.4084016368634655,1739502682.0392804,42.31995964050293,4.327847551997605,1739502682.0392816,42.31995964050293,1.1524484613981087 +1739502682.0593514,42.33995962142944,42.692569220431736,1739502682.059354,42.33995962142944,3.041142232904061,1739502682.0593574,42.33995962142944,69.11120795870492,1739502682.0593603,42.33995962142944,39.887243251212894,1739502682.0593617,42.33995962142944,0.21531081280322406,1739502682.059364,42.33995962142944,-2.352553078874743,1739502682.0593657,42.33995962142944,-1.540388864314363,1739502682.0593672,42.33995962142944,-0.6108,1739502682.0593686,42.33995962142944,0.7290446069764669,1739502682.0593703,42.33995962142944,0.0,1739502682.0593717,42.33995962142944,-0.42340385442164186,1739502682.0593734,42.33995962142944,4.327847551997605,1739502682.0593748,42.33995962142944,1.1524484613981087 +1739502682.0819237,42.35995960235596,42.692569220431736,1739502682.0819278,42.35995960235596,3.041142232904061,1739502682.0819328,42.35995960235596,69.11120795870492,1739502682.0819387,42.35995960235596,39.887243251212894,1739502682.0819418,42.35995960235596,0.21531081280322406,1739502682.0819461,42.35995960235596,-2.352553078874743,1739502682.0819497,42.35995960235596,-1.540388864314363,1739502682.0819535,42.35995960235596,-0.6108,1739502682.081957,42.35995960235596,0.7290446069764669,1739502682.081961,42.35995960235596,0.0,1739502682.0819647,42.35995960235596,-0.42340385442164186,1739502682.0819685,42.35995960235596,4.327847551997605,1739502682.0819726,42.35995960235596,1.1524484613981087 +1739502682.0992446,42.37995958328247,42.692569220431736,1739502682.0992467,42.37995958328247,3.041142232904061,1739502682.09925,42.37995958328247,69.11120795870492,1739502682.0992532,42.37995958328247,39.887243251212894,1739502682.0992546,42.37995958328247,0.21531081280322406,1739502682.0992563,42.37995958328247,-2.352553078874743,1739502682.0992577,42.37995958328247,-1.540388864314363,1739502682.0992591,42.37995958328247,-0.6108,1739502682.0992603,42.37995958328247,0.7290446069764669,1739502682.0992622,42.37995958328247,0.0,1739502682.0992637,42.37995958328247,-0.42340385442164186,1739502682.099265,42.37995958328247,4.327847551997605,1739502682.0992665,42.37995958328247,1.1524484613981087 +1739502682.1194477,42.399959564208984,42.692569220431736,1739502682.119452,42.399959564208984,3.041142232904061,1739502682.1194563,42.399959564208984,69.11120795870492,1739502682.1194594,42.399959564208984,39.887243251212894,1739502682.1194608,42.399959564208984,0.21531081280322406,1739502682.1194627,42.399959564208984,-2.352553078874743,1739502682.1194644,42.399959564208984,-1.540388864314363,1739502682.1194665,42.399959564208984,-0.6108,1739502682.119468,42.399959564208984,0.7290446069764669,1739502682.11947,42.399959564208984,0.0,1739502682.1194713,42.399959564208984,-0.42340385442164186,1739502682.1194732,42.399959564208984,4.327847551997605,1739502682.1194746,42.399959564208984,1.1524484613981087 +1739502682.1393003,42.4199595451355,42.64556500541736,1739502682.139303,42.4199595451355,2.9259193043541565,1739502682.139306,42.4199595451355,69.11317132370824,1739502682.1393087,42.4199595451355,39.975012325649224,1739502682.1393104,42.4199595451355,0.23865506344447426,1739502682.1393123,42.4199595451355,-2.353075401355433,1739502682.139314,42.4199595451355,-1.4449227795801929,1739502682.1393154,42.4199595451355,-0.6108,1739502682.1393168,42.4199595451355,0.7869052027255286,1739502682.1393185,42.4199595451355,0.0,1739502682.13932,42.4199595451355,-0.2717536992884376,1739502682.1393213,42.4199595451355,4.3214097260357205,1739502682.139323,42.4199595451355,1.1060496065648597 +1739502682.1589298,42.43995952606201,42.64556500541736,1739502682.1589324,42.43995952606201,2.9259193043541565,1739502682.1589358,42.43995952606201,69.11317132370824,1739502682.1589386,42.43995952606201,39.975012325649224,1739502682.1589403,42.43995952606201,0.23865506344447426,1739502682.1589422,42.43995952606201,-2.353075401355433,1739502682.1589437,42.43995952606201,-1.4449227795801929,1739502682.1589453,42.43995952606201,-0.6108,1739502682.1589465,42.43995952606201,0.7869052027255286,1739502682.1589484,42.43995952606201,0.0,1739502682.1589496,42.43995952606201,-0.3191444038393312,1739502682.1589513,42.43995952606201,4.3214097260357205,1739502682.158953,42.43995952606201,1.1060496065648597 +1739502682.179307,42.459959506988525,42.64556500541736,1739502682.1793103,42.459959506988525,2.9259193043541565,1739502682.1793146,42.459959506988525,69.11317132370824,1739502682.1793182,42.459959506988525,39.975012325649224,1739502682.17932,42.459959506988525,0.23865506344447426,1739502682.1793218,42.459959506988525,-2.353075401355433,1739502682.1793237,42.459959506988525,-1.4449227795801929,1739502682.1793253,42.459959506988525,-0.6108,1739502682.1793272,42.459959506988525,0.7869052027255286,1739502682.179329,42.459959506988525,0.0,1739502682.1793306,42.459959506988525,-0.3191444038393312,1739502682.1793323,42.459959506988525,4.3214097260357205,1739502682.179334,42.459959506988525,1.1060496065648597 +1739502682.1992002,42.47995948791504,42.64556500541736,1739502682.1992028,42.47995948791504,2.9259193043541565,1739502682.199206,42.47995948791504,69.11317132370824,1739502682.1992092,42.47995948791504,39.975012325649224,1739502682.1992106,42.47995948791504,0.23865506344447426,1739502682.1992126,42.47995948791504,-2.353075401355433,1739502682.199214,42.47995948791504,-1.4449227795801929,1739502682.1992157,42.47995948791504,-0.6108,1739502682.1992168,42.47995948791504,0.7869052027255286,1739502682.1992185,42.47995948791504,0.0,1739502682.19922,42.47995948791504,-0.3191444038393312,1739502682.1992216,42.47995948791504,4.3214097260357205,1739502682.199223,42.47995948791504,1.1060496065648597 +1739502682.2197855,42.49995946884155,42.64556500541736,1739502682.2197883,42.49995946884155,2.9259193043541565,1739502682.219792,42.49995946884155,69.11317132370824,1739502682.219795,42.49995946884155,39.975012325649224,1739502682.2197964,42.49995946884155,0.23865506344447426,1739502682.2197986,42.49995946884155,-2.353075401355433,1739502682.2198,42.49995946884155,-1.4449227795801929,1739502682.2198017,42.49995946884155,-0.6108,1739502682.2198029,42.49995946884155,0.7869052027255286,1739502682.2198048,42.49995946884155,0.0,1739502682.2198062,42.49995946884155,-0.3191444038393312,1739502682.219808,42.49995946884155,4.3214097260357205,1739502682.2198095,42.49995946884155,1.1060496065648597 +1739502682.2396636,42.519959449768066,42.64556500541736,1739502682.239666,42.519959449768066,2.9259193043541565,1739502682.2396693,42.519959449768066,69.11317132370824,1739502682.239672,42.519959449768066,39.975012325649224,1739502682.2396736,42.519959449768066,0.23865506344447426,1739502682.2396753,42.519959449768066,-2.353075401355433,1739502682.239677,42.519959449768066,-1.4449227795801929,1739502682.2396786,42.519959449768066,-0.6108,1739502682.23968,42.519959449768066,0.7869052027255286,1739502682.2396817,42.519959449768066,0.0,1739502682.2396832,42.519959449768066,-0.3191444038393312,1739502682.2396846,42.519959449768066,4.3214097260357205,1739502682.2396865,42.519959449768066,1.1060496065648597 +1739502682.2590213,42.53995943069458,42.59937923100498,1739502682.259024,42.53995943069458,2.814950095671179,1739502682.259027,42.53995943069458,69.27686164629493,1739502682.25903,42.53995943069458,39.873458195643,1739502682.2590315,42.53995943069458,0.2118645489107514,1739502682.2590334,42.53995943069458,-2.379240763208871,1739502682.2590349,42.53995943069458,-1.5012527630215402,1739502682.2590363,42.53995943069458,-0.6108,1739502682.2590377,42.53995943069458,0.7522312578712508,1739502682.2590394,42.53995943069458,0.0,1739502682.2590408,42.53995943069458,-0.32692711294237436,1739502682.2590423,42.53995943069458,4.313604198251807,1739502682.259044,42.53995943069458,1.0767262726243163 +1739502682.2792416,42.559959411621094,42.59937923100498,1739502682.279245,42.559959411621094,2.814950095671179,1739502682.2792482,42.559959411621094,69.27686164629493,1739502682.2792518,42.559959411621094,39.873458195643,1739502682.2792532,42.559959411621094,0.2118645489107514,1739502682.2792552,42.559959411621094,-2.379240763208871,1739502682.2792566,42.559959411621094,-1.5012527630215402,1739502682.279258,42.559959411621094,-0.6108,1739502682.2792594,42.559959411621094,0.7522312578712508,1739502682.2792614,42.559959411621094,0.0,1739502682.279263,42.559959411621094,-0.3244950147530655,1739502682.279265,42.559959411621094,4.313604198251807,1739502682.2792666,42.559959411621094,1.0767262726243163 +1739502682.2993538,42.57995939254761,42.59937923100498,1739502682.2993567,42.57995939254761,2.814950095671179,1739502682.2993596,42.57995939254761,69.27686164629493,1739502682.299363,42.57995939254761,39.873458195643,1739502682.2993643,42.57995939254761,0.2118645489107514,1739502682.2993662,42.57995939254761,-2.379240763208871,1739502682.2993677,42.57995939254761,-1.5012527630215402,1739502682.2993693,42.57995939254761,-0.6108,1739502682.2993708,42.57995939254761,0.7522312578712508,1739502682.2993724,42.57995939254761,0.0,1739502682.2993739,42.57995939254761,-0.3244950147530655,1739502682.2993755,42.57995939254761,4.313604198251807,1739502682.2993772,42.57995939254761,1.0767262726243163 +1739502682.319273,42.59995937347412,42.59937923100498,1739502682.3192763,42.59995937347412,2.814950095671179,1739502682.3192801,42.59995937347412,69.27686164629493,1739502682.3192832,42.59995937347412,39.873458195643,1739502682.3192847,42.59995937347412,0.2118645489107514,1739502682.3192866,42.59995937347412,-2.379240763208871,1739502682.319288,42.59995937347412,-1.5012527630215402,1739502682.31929,42.59995937347412,-0.6108,1739502682.3192914,42.59995937347412,0.7522312578712508,1739502682.3192935,42.59995937347412,0.0,1739502682.3192952,42.59995937347412,-0.3244950147530655,1739502682.319297,42.59995937347412,4.313604198251807,1739502682.3192987,42.59995937347412,1.0767262726243163 +1739502682.3393953,42.619959354400635,42.59937923100498,1739502682.3393977,42.619959354400635,2.814950095671179,1739502682.3394012,42.619959354400635,69.27686164629493,1739502682.3394043,42.619959354400635,39.873458195643,1739502682.3394055,42.619959354400635,0.2118645489107514,1739502682.3394074,42.619959354400635,-2.379240763208871,1739502682.339409,42.619959354400635,-1.5012527630215402,1739502682.3394108,42.619959354400635,-0.6108,1739502682.3394122,42.619959354400635,0.7522312578712508,1739502682.3394141,42.619959354400635,0.0,1739502682.3394153,42.619959354400635,-0.3244950147530655,1739502682.339417,42.619959354400635,4.313604198251807,1739502682.3394186,42.619959354400635,1.0767262726243163 +1739502682.3597093,42.63995933532715,42.55351971062796,1739502682.3597128,42.63995933532715,2.7073310108479145,1739502682.3597167,42.63995933532715,69.49298906302849,1739502682.3597198,42.63995933532715,39.719872955558905,1739502682.3597212,42.63995933532715,0.17510655873111608,1739502682.3597233,42.63995933532715,-2.412309488613126,1739502682.3597248,42.63995933532715,-1.596420118541001,1739502682.359727,42.63995933532715,-0.6108,1739502682.359728,42.63995933532715,0.6970867855708064,1739502682.3597302,42.63995933532715,0.0,1739502682.3597317,42.63995933532715,-0.3623875958293445,1739502682.3597336,42.63995933532715,4.304415482793127,1739502682.3597353,42.63995933532715,1.047632942049961 +1739502682.3789208,42.65995931625366,42.55351971062796,1739502682.378924,42.65995931625366,2.7073310108479145,1739502682.378927,42.65995931625366,69.49298906302849,1739502682.37893,42.65995931625366,39.719872955558905,1739502682.378932,42.65995931625366,0.17510655873111608,1739502682.3789337,42.65995931625366,-2.412309488613126,1739502682.3789356,42.65995931625366,-1.596420118541001,1739502682.3789372,42.65995931625366,-0.6108,1739502682.378939,42.65995931625366,0.6970867855708064,1739502682.3789403,42.65995931625366,0.0,1739502682.378942,42.65995931625366,-0.35054615647915466,1739502682.3789437,42.65995931625366,4.304415482793127,1739502682.3789454,42.65995931625366,1.047632942049961 +1739502682.4002059,42.679959297180176,42.55351971062796,1739502682.4002087,42.679959297180176,2.7073310108479145,1739502682.4002118,42.679959297180176,69.49298906302849,1739502682.4002147,42.679959297180176,39.719872955558905,1739502682.4002163,42.679959297180176,0.17510655873111608,1739502682.4002185,42.679959297180176,-2.412309488613126,1739502682.40022,42.679959297180176,-1.596420118541001,1739502682.4002213,42.679959297180176,-0.6108,1739502682.400223,42.679959297180176,0.6970867855708064,1739502682.4002247,42.679959297180176,0.0,1739502682.400226,42.679959297180176,-0.35054615647915466,1739502682.4002278,42.679959297180176,4.304415482793127,1739502682.4002295,42.679959297180176,1.047632942049961 +1739502682.419499,42.69995927810669,42.55351971062796,1739502682.4195018,42.69995927810669,2.7073310108479145,1739502682.419505,42.69995927810669,69.49298906302849,1739502682.4195077,42.69995927810669,39.719872955558905,1739502682.4195092,42.69995927810669,0.17510655873111608,1739502682.4195108,42.69995927810669,-2.412309488613126,1739502682.4195123,42.69995927810669,-1.596420118541001,1739502682.4195137,42.69995927810669,-0.6108,1739502682.419515,42.69995927810669,0.6970867855708064,1739502682.4195163,42.69995927810669,0.0,1739502682.4195178,42.69995927810669,-0.35054615647915466,1739502682.4195192,42.69995927810669,4.304415482793127,1739502682.4195206,42.69995927810669,1.047632942049961 +1739502682.4396334,42.7199592590332,42.55351971062796,1739502682.4396358,42.7199592590332,2.7073310108479145,1739502682.4396389,42.7199592590332,69.49298906302849,1739502682.4396412,42.7199592590332,39.719872955558905,1739502682.439643,42.7199592590332,0.17510655873111608,1739502682.4396446,42.7199592590332,-2.412309488613126,1739502682.439646,42.7199592590332,-1.596420118541001,1739502682.4396472,42.7199592590332,-0.6108,1739502682.4396486,42.7199592590332,0.6970867855708064,1739502682.4396498,42.7199592590332,0.0,1739502682.4396513,42.7199592590332,-0.35054615647915466,1739502682.4396527,42.7199592590332,4.304415482793127,1739502682.4396539,42.7199592590332,1.047632942049961 +1739502682.459251,42.73995923995972,42.55351971062796,1739502682.4592533,42.73995923995972,2.7073310108479145,1739502682.4592562,42.73995923995972,69.49298906302849,1739502682.459259,42.73995923995972,39.719872955558905,1739502682.4592605,42.73995923995972,0.17510655873111608,1739502682.4592621,42.73995923995972,-2.412309488613126,1739502682.4592636,42.73995923995972,-1.596420118541001,1739502682.4592648,42.73995923995972,-0.6108,1739502682.459266,42.73995923995972,0.6970867855708064,1739502682.459268,42.73995923995972,0.0,1739502682.4592693,42.73995923995972,-0.35054615647915466,1739502682.4592707,42.73995923995972,4.304415482793127,1739502682.4592721,42.73995923995972,1.047632942049961 +1739502682.4790957,42.75995922088623,42.50788445645159,1739502682.4790983,42.75995922088623,2.603088828733065,1739502682.4791012,42.75995922088623,69.63606825417686,1739502682.4791038,42.75995922088623,39.63654945991781,1739502682.4791052,42.75995922088623,0.15667619802719224,1739502682.479107,42.75995922088623,-2.435931525907354,1739502682.4791083,42.75995922088623,-1.6291217398835542,1739502682.4791095,42.75995922088623,-0.6108,1739502682.4791112,42.75995922088623,0.679086572172807,1739502682.4791126,42.75995922088623,0.0,1739502682.4791143,42.75995922088623,-0.3347399445189085,1739502682.4791155,42.75995922088623,4.2938251246562,1739502682.4791172,42.75995922088623,1.0187659611678446 +1739502682.4992154,42.779959201812744,42.50788445645159,1739502682.499218,42.779959201812744,2.603088828733065,1739502682.4992208,42.779959201812744,69.63606825417686,1739502682.4992232,42.779959201812744,39.63654945991781,1739502682.499225,42.779959201812744,0.15667619802719224,1739502682.4992263,42.779959201812744,-2.435931525907354,1739502682.4992278,42.779959201812744,-1.6291217398835542,1739502682.4992292,42.779959201812744,-0.6108,1739502682.4992304,42.779959201812744,0.679086572172807,1739502682.499232,42.779959201812744,0.0,1739502682.4992335,42.779959201812744,-0.3396793889950376,1739502682.499235,42.779959201812744,4.2938251246562,1739502682.4992363,42.779959201812744,1.0187659611678446 +1739502682.518765,42.79995918273926,42.50788445645159,1739502682.5187676,42.79995918273926,2.603088828733065,1739502682.5187707,42.79995918273926,69.63606825417686,1739502682.5187738,42.79995918273926,39.63654945991781,1739502682.5187752,42.79995918273926,0.15667619802719224,1739502682.518777,42.79995918273926,-2.435931525907354,1739502682.5187783,42.79995918273926,-1.6291217398835542,1739502682.51878,42.79995918273926,-0.6108,1739502682.5187812,42.79995918273926,0.679086572172807,1739502682.518783,42.79995918273926,0.0,1739502682.5187843,42.79995918273926,-0.3396793889950376,1739502682.5187857,42.79995918273926,4.2938251246562,1739502682.5187874,42.79995918273926,1.0187659611678446 +1739502682.5392053,42.81995916366577,42.50788445645159,1739502682.539208,42.81995916366577,2.603088828733065,1739502682.539211,42.81995916366577,69.63606825417686,1739502682.5392141,42.81995916366577,39.63654945991781,1739502682.5392156,42.81995916366577,0.15667619802719224,1739502682.5392175,42.81995916366577,-2.435931525907354,1739502682.539219,42.81995916366577,-1.6291217398835542,1739502682.5392206,42.81995916366577,-0.6108,1739502682.5392218,42.81995916366577,0.679086572172807,1739502682.5392237,42.81995916366577,0.0,1739502682.539225,42.81995916366577,-0.3396793889950376,1739502682.5392265,42.81995916366577,4.2938251246562,1739502682.5392282,42.81995916366577,1.0187659611678446 +1739502682.559039,42.839959144592285,42.50788445645159,1739502682.5590422,42.839959144592285,2.603088828733065,1739502682.559046,42.839959144592285,69.63606825417686,1739502682.5590491,42.839959144592285,39.63654945991781,1739502682.559051,42.839959144592285,0.15667619802719224,1739502682.5590527,42.839959144592285,-2.435931525907354,1739502682.5590544,42.839959144592285,-1.6291217398835542,1739502682.5590558,42.839959144592285,-0.6108,1739502682.5590575,42.839959144592285,0.679086572172807,1739502682.5590594,42.839959144592285,0.0,1739502682.559061,42.839959144592285,-0.3396793889950376,1739502682.5590625,42.839959144592285,4.2938251246562,1739502682.5590641,42.839959144592285,1.0187659611678446 +1739502682.5791385,42.8599591255188,42.46238279099186,1739502682.5791414,42.8599591255188,2.50225005188212,1739502682.5791447,42.8599591255188,69.70946059426768,1739502682.5791476,42.8599591255188,39.62081523467361,1739502682.579149,42.8599591255188,0.15324542710928277,1739502682.5791512,42.8599591255188,-2.450806858702237,1739502682.5791523,42.8599591255188,-1.6017389533628854,1739502682.579154,42.8599591255188,-0.6108,1739502682.5791554,42.8599591255188,0.6941269356425978,1739502682.5791574,42.8599591255188,0.0,1739502682.5791585,42.8599591255188,-0.27613816756094983,1739502682.57916,42.8599591255188,4.281811547917533,1739502682.5791616,42.8599591255188,0.9901217479207308 +1739502682.599435,42.87995910644531,42.46238279099186,1739502682.5994375,42.87995910644531,2.50225005188212,1739502682.5994408,42.87995910644531,69.70946059426768,1739502682.599444,42.87995910644531,39.62081523467361,1739502682.5994456,42.87995910644531,0.15324542710928277,1739502682.5994473,42.87995910644531,-2.450806858702237,1739502682.599449,42.87995910644531,-1.6017389533628854,1739502682.5994503,42.87995910644531,-0.6108,1739502682.599452,42.87995910644531,0.6941269356425978,1739502682.5994534,42.87995910644531,0.0,1739502682.5994549,42.87995910644531,-0.29599481227813307,1739502682.5994565,42.87995910644531,4.281811547917533,1739502682.599458,42.87995910644531,0.9901217479207308 +1739502682.6190693,42.899959087371826,42.46238279099186,1739502682.6190722,42.899959087371826,2.50225005188212,1739502682.6190755,42.899959087371826,69.70946059426768,1739502682.6190789,42.899959087371826,39.62081523467361,1739502682.6190805,42.899959087371826,0.15324542710928277,1739502682.6190822,42.899959087371826,-2.450806858702237,1739502682.619084,42.899959087371826,-1.6017389533628854,1739502682.619085,42.899959087371826,-0.6108,1739502682.6190865,42.899959087371826,0.6941269356425978,1739502682.6190884,42.899959087371826,0.0,1739502682.6190898,42.899959087371826,-0.29599481227813307,1739502682.6190915,42.899959087371826,4.281811547917533,1739502682.619093,42.899959087371826,0.9901217479207308 +1739502682.6389377,42.91995906829834,42.46238279099186,1739502682.63894,42.91995906829834,2.50225005188212,1739502682.6389434,42.91995906829834,69.70946059426768,1739502682.6389463,42.91995906829834,39.62081523467361,1739502682.6389477,42.91995906829834,0.15324542710928277,1739502682.6389496,42.91995906829834,-2.450806858702237,1739502682.638951,42.91995906829834,-1.6017389533628854,1739502682.6389525,42.91995906829834,-0.6108,1739502682.638954,42.91995906829834,0.6941269356425978,1739502682.6389556,42.91995906829834,0.0,1739502682.638957,42.91995906829834,-0.29599481227813307,1739502682.6389587,42.91995906829834,4.281811547917533,1739502682.6389601,42.91995906829834,0.9901217479207308 +1739502682.659136,42.93995904922485,42.46238279099186,1739502682.6591392,42.93995904922485,2.50225005188212,1739502682.6591423,42.93995904922485,69.70946059426768,1739502682.659145,42.93995904922485,39.62081523467361,1739502682.6591468,42.93995904922485,0.15324542710928277,1739502682.6591485,42.93995904922485,-2.450806858702237,1739502682.6591504,42.93995904922485,-1.6017389533628854,1739502682.6591518,42.93995904922485,-0.6108,1739502682.6591535,42.93995904922485,0.6941269356425978,1739502682.659155,42.93995904922485,0.0,1739502682.6591566,42.93995904922485,-0.29599481227813307,1739502682.659158,42.93995904922485,4.281811547917533,1739502682.6591597,42.93995904922485,0.9901217479207308 +1739502682.6791584,42.95995903015137,42.46238279099186,1739502682.6791613,42.95995903015137,2.50225005188212,1739502682.6791646,42.95995903015137,69.70946059426768,1739502682.6791677,42.95995903015137,39.62081523467361,1739502682.6791692,42.95995903015137,0.15324542710928277,1739502682.679171,42.95995903015137,-2.450806858702237,1739502682.6791725,42.95995903015137,-1.6017389533628854,1739502682.6791742,42.95995903015137,-0.6108,1739502682.6791754,42.95995903015137,0.6941269356425978,1739502682.6791773,42.95995903015137,0.0,1739502682.6791785,42.95995903015137,-0.29599481227813307,1739502682.6791804,42.95995903015137,4.281811547917533,1739502682.6791818,42.95995903015137,0.9901217479207308 +1739502682.7004185,42.97995901107788,42.41693526074779,1739502682.700421,42.97995901107788,2.4048411884956975,1739502682.7004247,42.97995901107788,69.78299973746775,1739502682.7004278,42.97995901107788,39.604509132238675,1739502682.7004297,42.97995901107788,0.14968996116482375,1739502682.7004316,42.97995901107788,-2.4657230924684495,1739502682.7004333,42.97995901107788,-1.5708966888381117,1739502682.700435,42.97995901107788,-0.6108,1739502682.7004368,42.97995901107788,0.7114667326428291,1739502682.7004385,42.97995901107788,0.0,1739502682.7004402,42.97995901107788,-0.2294278762971455,1739502682.7004418,42.97995901107788,4.2683498745449375,1739502682.7004437,42.97995901107788,0.961696790073006 +1739502682.7192457,42.999958992004395,42.41693526074779,1739502682.7192495,42.999958992004395,2.4048411884956975,1739502682.7192528,42.999958992004395,69.78299973746775,1739502682.7192562,42.999958992004395,39.604509132238675,1739502682.7192576,42.999958992004395,0.14968996116482375,1739502682.7192597,42.999958992004395,-2.4657230924684495,1739502682.7192614,42.999958992004395,-1.5708966888381117,1739502682.719263,42.999958992004395,-0.6108,1739502682.7192645,42.999958992004395,0.7114667326428291,1739502682.7192664,42.999958992004395,0.0,1739502682.7192678,42.999958992004395,-0.2502300574301769,1739502682.7192695,42.999958992004395,4.2683498745449375,1739502682.7192714,42.999958992004395,0.961696790073006 +1739502682.739315,43.01995897293091,42.41693526074779,1739502682.7393177,43.01995897293091,2.4048411884956975,1739502682.739321,43.01995897293091,69.78299973746775,1739502682.7393243,43.01995897293091,39.604509132238675,1739502682.7393262,43.01995897293091,0.14968996116482375,1739502682.7393281,43.01995897293091,-2.4657230924684495,1739502682.7393298,43.01995897293091,-1.5708966888381117,1739502682.7393312,43.01995897293091,-0.6108,1739502682.739333,43.01995897293091,0.7114667326428291,1739502682.7393348,43.01995897293091,0.0,1739502682.7393365,43.01995897293091,-0.2502300574301769,1739502682.7393382,43.01995897293091,4.2683498745449375,1739502682.73934,43.01995897293091,0.961696790073006 +1739502682.759291,43.03995895385742,42.41693526074779,1739502682.7592943,43.03995895385742,2.4048411884956975,1739502682.759298,43.03995895385742,69.78299973746775,1739502682.7593017,43.03995895385742,39.604509132238675,1739502682.759303,43.03995895385742,0.14968996116482375,1739502682.7593055,43.03995895385742,-2.4657230924684495,1739502682.7593071,43.03995895385742,-1.5708966888381117,1739502682.7593088,43.03995895385742,-0.6108,1739502682.7593105,43.03995895385742,0.7114667326428291,1739502682.7593126,43.03995895385742,0.0,1739502682.7593145,43.03995895385742,-0.2502300574301769,1739502682.759316,43.03995895385742,4.2683498745449375,1739502682.7593179,43.03995895385742,0.961696790073006 +1739502682.7792158,43.059958934783936,42.41693526074779,1739502682.7792218,43.059958934783936,2.4048411884956975,1739502682.7792287,43.059958934783936,69.78299973746775,1739502682.7792366,43.059958934783936,39.604509132238675,1739502682.7792408,43.059958934783936,0.14968996116482375,1739502682.7792473,43.059958934783936,-2.4657230924684495,1739502682.7792525,43.059958934783936,-1.5708966888381117,1739502682.7792578,43.059958934783936,-0.6108,1739502682.779263,43.059958934783936,0.7114667326428291,1739502682.7792683,43.059958934783936,0.0,1739502682.7792735,43.059958934783936,-0.2502300574301769,1739502682.7792785,43.059958934783936,4.2683498745449375,1739502682.7792835,43.059958934783936,0.961696790073006 +1739502682.7997253,43.07995891571045,42.371473581054296,1739502682.799728,43.07995891571045,2.310888970568799,1739502682.7997315,43.07995891571045,69.87378518472171,1739502682.7997348,43.07995891571045,39.57088113851196,1739502682.7997363,43.07995891571045,0.14260811944314963,1739502682.7997384,43.07995891571045,-2.482768701472569,1739502682.79974,43.07995891571045,-1.5501314978900531,1739502682.7997417,43.07995891571045,-0.6108,1739502682.7997432,43.07995891571045,0.7233844420224937,1739502682.7997453,43.07995891571045,0.0,1739502682.7997468,43.07995891571045,-0.19186370405915099,1739502682.7997484,43.07995891571045,4.253411710455373,1739502682.7997503,43.07995891571045,0.9334876434688367 +1739502682.8196,43.09995889663696,42.371473581054296,1739502682.8196032,43.09995889663696,2.310888970568799,1739502682.819607,43.09995889663696,69.87378518472171,1739502682.8196106,43.09995889663696,39.57088113851196,1739502682.8196125,43.09995889663696,0.14260811944314963,1739502682.8196146,43.09995889663696,-2.482768701472569,1739502682.8196166,43.09995889663696,-1.5501314978900531,1739502682.8196182,43.09995889663696,-0.6108,1739502682.8196201,43.09995889663696,0.7233844420224937,1739502682.8196235,43.09995889663696,0.0,1739502682.8196251,43.09995889663696,-0.21010320144634298,1739502682.819627,43.09995889663696,4.253411710455373,1739502682.8196287,43.09995889663696,0.9334876434688367 +1739502682.8392508,43.11995887756348,42.371473581054296,1739502682.8392534,43.11995887756348,2.310888970568799,1739502682.8392572,43.11995887756348,69.87378518472171,1739502682.8392608,43.11995887756348,39.57088113851196,1739502682.8392625,43.11995887756348,0.14260811944314963,1739502682.8392644,43.11995887756348,-2.482768701472569,1739502682.8392663,43.11995887756348,-1.5501314978900531,1739502682.8392677,43.11995887756348,-0.6108,1739502682.8392694,43.11995887756348,0.7233844420224937,1739502682.8392718,43.11995887756348,0.0,1739502682.8392732,43.11995887756348,-0.21010320144634298,1739502682.8392751,43.11995887756348,4.253411710455373,1739502682.8392768,43.11995887756348,0.9334876434688367 +1739502682.8591137,43.13995885848999,42.371473581054296,1739502682.8591173,43.13995885848999,2.310888970568799,1739502682.859121,43.13995885848999,69.87378518472171,1739502682.8591244,43.13995885848999,39.57088113851196,1739502682.8591263,43.13995885848999,0.14260811944314963,1739502682.8591282,43.13995885848999,-2.482768701472569,1739502682.8591301,43.13995885848999,-1.5501314978900531,1739502682.8591316,43.13995885848999,-0.6108,1739502682.8591335,43.13995885848999,0.7233844420224937,1739502682.8591352,43.13995885848999,0.0,1739502682.859137,43.13995885848999,-0.21010320144634298,1739502682.8591387,43.13995885848999,4.253411710455373,1739502682.8591406,43.13995885848999,0.9334876434688367 +1739502682.8791544,43.159958839416504,42.371473581054296,1739502682.879158,43.159958839416504,2.310888970568799,1739502682.879162,43.159958839416504,69.87378518472171,1739502682.8791656,43.159958839416504,39.57088113851196,1739502682.8791676,43.159958839416504,0.14260811944314963,1739502682.8791697,43.159958839416504,-2.482768701472569,1739502682.8791716,43.159958839416504,-1.5501314978900531,1739502682.8791733,43.159958839416504,-0.6108,1739502682.879175,43.159958839416504,0.7233844420224937,1739502682.8791769,43.159958839416504,0.0,1739502682.8791792,43.159958839416504,-0.21010320144634298,1739502682.8791811,43.159958839416504,4.253411710455373,1739502682.8791828,43.159958839416504,0.9334876434688367 +1739502682.8998616,43.17995882034302,42.371473581054296,1739502682.8998644,43.17995882034302,2.310888970568799,1739502682.899868,43.17995882034302,69.87378518472171,1739502682.8998716,43.17995882034302,39.57088113851196,1739502682.899873,43.17995882034302,0.14260811944314963,1739502682.8998752,43.17995882034302,-2.482768701472569,1739502682.8998768,43.17995882034302,-1.5501314978900531,1739502682.8998785,43.17995882034302,-0.6108,1739502682.89988,43.17995882034302,0.7233844420224937,1739502682.899882,43.17995882034302,0.0,1739502682.8998835,43.17995882034302,-0.21010320144634298,1739502682.8998854,43.17995882034302,4.253411710455373,1739502682.899887,43.17995882034302,0.9334876434688367 +1739502682.919412,43.19995880126953,42.325940612849635,1739502682.9194148,43.19995880126953,2.220420509127849,1739502682.919418,43.19995880126953,70.0510394031479,1739502682.9194214,43.19995880126953,39.452070260548275,1739502682.9194229,43.19995880126953,0.11840549002526943,1739502682.919425,43.19995880126953,-2.5100871867317176,1739502682.919427,43.19995880126953,-1.5930294239392788,1739502682.9194286,43.19995880126953,-0.6108,1739502682.9194303,43.19995880126953,0.6989802391795957,1739502682.919432,43.19995880126953,0.0,1739502682.9194334,43.19995880126953,-0.2048777303847483,1739502682.9194353,43.19995880126953,4.236964894760447,1739502682.9194372,43.19995880126953,0.9054909303417449 +1739502682.9398148,43.219958782196045,42.325940612849635,1739502682.9398177,43.219958782196045,2.220420509127849,1739502682.9398212,43.219958782196045,70.0510394031479,1739502682.9398246,43.219958782196045,39.452070260548275,1739502682.9398263,43.219958782196045,0.11840549002526943,1739502682.9398282,43.219958782196045,-2.5100871867317176,1739502682.93983,43.219958782196045,-1.5930294239392788,1739502682.9398315,43.219958782196045,-0.6108,1739502682.9398332,43.219958782196045,0.6989802391795957,1739502682.9398348,43.219958782196045,0.0,1739502682.9398365,43.219958782196045,-0.20651069116214915,1739502682.9398382,43.219958782196045,4.236964894760447,1739502682.9398398,43.219958782196045,0.9054909303417449 +1739502682.9594123,43.23995876312256,42.325940612849635,1739502682.9594152,43.23995876312256,2.220420509127849,1739502682.9594195,43.23995876312256,70.0510394031479,1739502682.9594228,43.23995876312256,39.452070260548275,1739502682.9594247,43.23995876312256,0.11840549002526943,1739502682.9594269,43.23995876312256,-2.5100871867317176,1739502682.9594288,43.23995876312256,-1.5930294239392788,1739502682.9594305,43.23995876312256,-0.6108,1739502682.959432,43.23995876312256,0.6989802391795957,1739502682.9594343,43.23995876312256,0.0,1739502682.959436,43.23995876312256,-0.20651069116214915,1739502682.9594383,43.23995876312256,4.236964894760447,1739502682.9594402,43.23995876312256,0.9054909303417449 +1739502682.9797864,43.25995874404907,42.325940612849635,1739502682.9797897,43.25995874404907,2.220420509127849,1739502682.9797943,43.25995874404907,70.0510394031479,1739502682.9797978,43.25995874404907,39.452070260548275,1739502682.9797993,43.25995874404907,0.11840549002526943,1739502682.9798014,43.25995874404907,-2.5100871867317176,1739502682.979803,43.25995874404907,-1.5930294239392788,1739502682.979805,43.25995874404907,-0.6108,1739502682.9798064,43.25995874404907,0.6989802391795957,1739502682.979809,43.25995874404907,0.0,1739502682.9798107,43.25995874404907,-0.20651069116214915,1739502682.9798129,43.25995874404907,4.236964894760447,1739502682.979815,43.25995874404907,0.9054909303417449 +1739502682.9994934,43.279958724975586,42.325940612849635,1739502682.9994965,43.279958724975586,2.220420509127849,1739502682.9994998,43.279958724975586,70.0510394031479,1739502682.9995031,43.279958724975586,39.452070260548275,1739502682.9995046,43.279958724975586,0.11840549002526943,1739502682.9995065,43.279958724975586,-2.5100871867317176,1739502682.9995081,43.279958724975586,-1.5930294239392788,1739502682.9995098,43.279958724975586,-0.6108,1739502682.999511,43.279958724975586,0.6989802391795957,1739502682.9995131,43.279958724975586,0.0,1739502682.9995146,43.279958724975586,-0.20651069116214915,1739502682.9995167,43.279958724975586,4.236964894760447,1739502682.9995182,43.279958724975586,0.9054909303417449 +1739502683.0192904,43.2999587059021,42.280290371822886,1739502683.019294,43.2999587059021,2.1334633866650874,1739502683.0192978,43.2999587059021,70.05499590725464,1739502683.0193012,43.2999587059021,39.50258258212052,1739502683.0193028,43.2999587059021,0.1290025185433429,1739502683.0193052,43.2999587059021,-2.5165008150804873,1739502683.019307,43.2999587059021,-1.4969964543827776,1739502683.0193088,43.2999587059021,-0.6108,1739502683.0193102,43.2999587059021,0.7547970063602,1739502683.0193126,43.2999587059021,0.0,1739502683.0193143,43.2999587059021,-0.08490431332274723,1739502683.019316,43.2999587059021,4.218973207279142,1739502683.019318,43.2999587059021,0.8777033376738249 +1739502683.0395029,43.31995868682861,42.280290371822886,1739502683.039506,43.31995868682861,2.1334633866650874,1739502683.0395098,43.31995868682861,70.05499590725464,1739502683.0395129,43.31995868682861,39.50258258212052,1739502683.0395145,43.31995868682861,0.1290025185433429,1739502683.0395164,43.31995868682861,-2.5165008150804873,1739502683.039518,43.31995868682861,-1.4969964543827776,1739502683.03952,43.31995868682861,-0.6108,1739502683.0395212,43.31995868682861,0.7547970063602,1739502683.0395234,43.31995868682861,0.0,1739502683.0395248,43.31995868682861,-0.12290633131362494,1739502683.0395267,43.31995868682861,4.218973207279142,1739502683.0395281,43.31995868682861,0.8777033376738249 +1739502683.0592213,43.33995866775513,42.280290371822886,1739502683.0592244,43.33995866775513,2.1334633866650874,1739502683.059228,43.33995866775513,70.05499590725464,1739502683.0592313,43.33995866775513,39.50258258212052,1739502683.0592327,43.33995866775513,0.1290025185433429,1739502683.0592349,43.33995866775513,-2.5165008150804873,1739502683.0592365,43.33995866775513,-1.4969964543827776,1739502683.0592384,43.33995866775513,-0.6108,1739502683.0592399,43.33995866775513,0.7547970063602,1739502683.0592422,43.33995866775513,0.0,1739502683.0592437,43.33995866775513,-0.12290633131362494,1739502683.0592456,43.33995866775513,4.218973207279142,1739502683.0592473,43.33995866775513,0.8777033376738249 +1739502683.0794032,43.35995864868164,42.280290371822886,1739502683.0794065,43.35995864868164,2.1334633866650874,1739502683.0794108,43.35995864868164,70.05499590725464,1739502683.0794141,43.35995864868164,39.50258258212052,1739502683.0794158,43.35995864868164,0.1290025185433429,1739502683.079418,43.35995864868164,-2.5165008150804873,1739502683.0794196,43.35995864868164,-1.4969964543827776,1739502683.0794215,43.35995864868164,-0.6108,1739502683.079423,43.35995864868164,0.7547970063602,1739502683.0794253,43.35995864868164,0.0,1739502683.0794272,43.35995864868164,-0.12290633131362494,1739502683.0794291,43.35995864868164,4.218973207279142,1739502683.0794308,43.35995864868164,0.8777033376738249 +1739502683.0995703,43.379958629608154,42.280290371822886,1739502683.0995727,43.379958629608154,2.1334633866650874,1739502683.0995765,43.379958629608154,70.05499590725464,1739502683.0995796,43.379958629608154,39.50258258212052,1739502683.0995815,43.379958629608154,0.1290025185433429,1739502683.0995836,43.379958629608154,-2.5165008150804873,1739502683.0995853,43.379958629608154,-1.4969964543827776,1739502683.0995867,43.379958629608154,-0.6108,1739502683.0995884,43.379958629608154,0.7547970063602,1739502683.0995903,43.379958629608154,0.0,1739502683.099592,43.379958629608154,-0.12290633131362494,1739502683.0995936,43.379958629608154,4.218973207279142,1739502683.0995953,43.379958629608154,0.8777033376738249 +1739502683.1191707,43.39995861053467,42.280290371822886,1739502683.1191735,43.39995861053467,2.1334633866650874,1739502683.1191778,43.39995861053467,70.05499590725464,1739502683.1191812,43.39995861053467,39.50258258212052,1739502683.1191828,43.39995861053467,0.1290025185433429,1739502683.1191852,43.39995861053467,-2.5165008150804873,1739502683.1191866,43.39995861053467,-1.4969964543827776,1739502683.1191885,43.39995861053467,-0.6108,1739502683.11919,43.39995861053467,0.7547970063602,1739502683.1191921,43.39995861053467,0.0,1739502683.1191936,43.39995861053467,-0.12290633131362494,1739502683.1191955,43.39995861053467,4.218973207279142,1739502683.1191971,43.39995861053467,0.8777033376738249 +1739502683.1397052,43.41995859146118,42.23411116520935,1739502683.1397078,43.41995859146118,2.0493647198407343,1739502683.1397111,43.41995859146118,70.25094854922669,1739502683.1397145,43.41995859146118,39.33529405350185,1739502683.1397161,43.41995859146118,0.09605513503159689,1739502683.1397178,43.41995859146118,-2.5486472844135113,1739502683.1397197,43.41995859146118,-1.5670207296011813,1739502683.1397212,43.41995859146118,-0.6108,1739502683.1397226,43.41995859146118,0.7136762493144442,1739502683.1397245,43.41995859146118,0.0,1739502683.1397262,43.41995859146118,-0.16421799772234927,1739502683.139728,43.41995859146118,4.199396028363092,1739502683.1397297,43.41995859146118,0.8649843428196743 +1739502683.1591256,43.439958572387695,42.23411116520935,1739502683.1591287,43.439958572387695,2.0493647198407343,1739502683.1591327,43.439958572387695,70.25094854922669,1739502683.1591363,43.439958572387695,39.33529405350185,1739502683.1591377,43.439958572387695,0.09605513503159689,1739502683.15914,43.439958572387695,-2.5486472844135113,1739502683.1591423,43.439958572387695,-1.5670207296011813,1739502683.1591437,43.439958572387695,-0.6108,1739502683.159145,43.439958572387695,0.7136762493144442,1739502683.1591473,43.439958572387695,0.0,1739502683.1591492,43.439958572387695,-0.1513080935052301,1739502683.1591506,43.439958572387695,4.199396028363092,1739502683.1591523,43.439958572387695,0.8649843428196743 +1739502683.1791706,43.45995855331421,42.23411116520935,1739502683.1791737,43.45995855331421,2.0493647198407343,1739502683.1791773,43.45995855331421,70.25094854922669,1739502683.1791804,43.45995855331421,39.33529405350185,1739502683.179182,43.45995855331421,0.09605513503159689,1739502683.1791842,43.45995855331421,-2.5486472844135113,1739502683.1791856,43.45995855331421,-1.5670207296011813,1739502683.1791873,43.45995855331421,-0.6108,1739502683.179189,43.45995855331421,0.7136762493144442,1739502683.1791909,43.45995855331421,0.0,1739502683.1791923,43.45995855331421,-0.1513080935052301,1739502683.1791942,43.45995855331421,4.199396028363092,1739502683.179196,43.45995855331421,0.8649843428196743 +1739502683.1997597,43.47995853424072,42.23411116520935,1739502683.1997626,43.47995853424072,2.0493647198407343,1739502683.199766,43.47995853424072,70.25094854922669,1739502683.1997693,43.47995853424072,39.33529405350185,1739502683.199771,43.47995853424072,0.09605513503159689,1739502683.1997728,43.47995853424072,-2.5486472844135113,1739502683.1997745,43.47995853424072,-1.5670207296011813,1739502683.1997762,43.47995853424072,-0.6108,1739502683.1997776,43.47995853424072,0.7136762493144442,1739502683.1997793,43.47995853424072,0.0,1739502683.1997812,43.47995853424072,-0.1513080935052301,1739502683.1997826,43.47995853424072,4.199396028363092,1739502683.1997843,43.47995853424072,0.8649843428196743 +1739502683.2193215,43.499958515167236,42.23411116520935,1739502683.2193244,43.499958515167236,2.0493647198407343,1739502683.2193282,43.499958515167236,70.25094854922669,1739502683.2193315,43.499958515167236,39.33529405350185,1739502683.2193334,43.499958515167236,0.09605513503159689,1739502683.2193353,43.499958515167236,-2.5486472844135113,1739502683.2193372,43.499958515167236,-1.5670207296011813,1739502683.219339,43.499958515167236,-0.6108,1739502683.2193406,43.499958515167236,0.7136762493144442,1739502683.2193422,43.499958515167236,0.0,1739502683.219344,43.499958515167236,-0.1513080935052301,1739502683.2193456,43.499958515167236,4.199396028363092,1739502683.2193475,43.499958515167236,0.8649843428196743 +1739502683.2400305,43.51995849609375,42.1872560304227,1739502683.240033,43.51995849609375,1.9679918604176265,1739502683.2400367,43.51995849609375,70.37869054360104,1739502683.2400398,43.51995849609375,39.26123687682892,1739502683.2400415,43.51995849609375,0.08231254661240535,1739502683.2400432,43.51995849609375,-2.5691274003472127,1739502683.240045,43.51995849609375,-1.5582532567841996,1739502683.2400465,43.51995849609375,-0.6108,1739502683.2400482,43.51995849609375,0.7186995550921622,1739502683.2400498,43.51995849609375,0.0,1739502683.2400515,43.51995849609375,-0.10587806800667052,1739502683.240053,43.51995849609375,4.178187943827709,1739502683.2400546,43.51995849609375,0.8387745153753405 +1739502683.2594428,43.539958477020264,42.1872560304227,1739502683.259446,43.539958477020264,1.9679918604176265,1739502683.2594502,43.539958477020264,70.37869054360104,1739502683.2594538,43.539958477020264,39.26123687682892,1739502683.2594552,43.539958477020264,0.08231254661240535,1739502683.2594576,43.539958477020264,-2.5691274003472127,1739502683.259459,43.539958477020264,-1.5582532567841996,1739502683.259461,43.539958477020264,-0.6108,1739502683.2594624,43.539958477020264,0.7186995550921622,1739502683.2594643,43.539958477020264,0.0,1739502683.2594657,43.539958477020264,-0.12007496028317832,1739502683.2594676,43.539958477020264,4.178187943827709,1739502683.2594693,43.539958477020264,0.8387745153753405 +1739502683.2794943,43.55995845794678,42.1872560304227,1739502683.2794974,43.55995845794678,1.9679918604176265,1739502683.2795024,43.55995845794678,70.37869054360104,1739502683.2795057,43.55995845794678,39.26123687682892,1739502683.2795074,43.55995845794678,0.08231254661240535,1739502683.2795095,43.55995845794678,-2.5691274003472127,1739502683.2795115,43.55995845794678,-1.5582532567841996,1739502683.2795131,43.55995845794678,-0.6108,1739502683.2795148,43.55995845794678,0.7186995550921622,1739502683.2795167,43.55995845794678,0.0,1739502683.2795184,43.55995845794678,-0.12007496028317832,1739502683.2795215,43.55995845794678,4.178187943827709,1739502683.2795231,43.55995845794678,0.8387745153753405 +1739502683.2998116,43.57995843887329,42.1872560304227,1739502683.2998145,43.57995843887329,1.9679918604176265,1739502683.299818,43.57995843887329,70.37869054360104,1739502683.2998216,43.57995843887329,39.26123687682892,1739502683.2998233,43.57995843887329,0.08231254661240535,1739502683.2998254,43.57995843887329,-2.5691274003472127,1739502683.2998269,43.57995843887329,-1.5582532567841996,1739502683.2998285,43.57995843887329,-0.6108,1739502683.29983,43.57995843887329,0.7186995550921622,1739502683.2998319,43.57995843887329,0.0,1739502683.2998335,43.57995843887329,-0.12007496028317832,1739502683.2998352,43.57995843887329,4.178187943827709,1739502683.2998369,43.57995843887329,0.8387745153753405 +1739502683.3193543,43.599958419799805,42.1872560304227,1739502683.3193574,43.599958419799805,1.9679918604176265,1739502683.3193614,43.599958419799805,70.37869054360104,1739502683.3193648,43.599958419799805,39.26123687682892,1739502683.3193667,43.599958419799805,0.08231254661240535,1739502683.3193686,43.599958419799805,-2.5691274003472127,1739502683.3193705,43.599958419799805,-1.5582532567841996,1739502683.3193722,43.599958419799805,-0.6108,1739502683.319375,43.599958419799805,0.7186995550921622,1739502683.3193772,43.599958419799805,0.0,1739502683.3193789,43.599958419799805,-0.12007496028317832,1739502683.3193808,43.599958419799805,4.178187943827709,1739502683.3193824,43.599958419799805,0.8387745153753405 +1739502683.339873,43.61995840072632,42.1872560304227,1739502683.339876,43.61995840072632,1.9679918604176265,1739502683.3398793,43.61995840072632,70.37869054360104,1739502683.3398826,43.61995840072632,39.26123687682892,1739502683.3398843,43.61995840072632,0.08231254661240535,1739502683.3398864,43.61995840072632,-2.5691274003472127,1739502683.3398879,43.61995840072632,-1.5582532567841996,1739502683.3398895,43.61995840072632,-0.6108,1739502683.339891,43.61995840072632,0.7186995550921622,1739502683.339893,43.61995840072632,0.0,1739502683.3398945,43.61995840072632,-0.12007496028317832,1739502683.3398962,43.61995840072632,4.178187943827709,1739502683.3398979,43.61995840072632,0.8387745153753405 +1739502683.3593462,43.63995838165283,42.139797136358645,1739502683.359349,43.63995838165283,1.889608830573974,1739502683.359352,43.63995838165283,70.44484749950819,1739502683.3593554,43.63995838165283,39.221434354768334,1739502683.359357,43.63995838165283,0.07543309835502113,1739502683.3593593,43.63995838165283,-2.585412007726218,1739502683.3593607,43.63995838165283,-1.517908068800869,1739502683.3593624,43.63995838165283,-0.6108,1739502683.3593638,43.63995838165283,0.7422748228670277,1739502683.3593657,43.63995838165283,0.0,1739502683.3593671,43.63995838165283,-0.06704598144802526,1739502683.359369,43.63995838165283,4.155298286254579,1739502683.3593705,43.63995838165283,0.8258923710662042 +1739502683.379229,43.659958362579346,42.139797136358645,1739502683.3792324,43.659958362579346,1.889608830573974,1739502683.3792365,43.659958362579346,70.44484749950819,1739502683.3792398,43.659958362579346,39.221434354768334,1739502683.3792412,43.659958362579346,0.07543309835502113,1739502683.3792436,43.659958362579346,-2.585412007726218,1739502683.3792453,43.659958362579346,-1.517908068800869,1739502683.379247,43.659958362579346,-0.6108,1739502683.3792484,43.659958362579346,0.7422748228670277,1739502683.3792508,43.659958362579346,0.0,1739502683.3792524,43.659958362579346,-0.08361754819917644,1739502683.3792543,43.659958362579346,4.155298286254579,1739502683.3792558,43.659958362579346,0.8258923710662042 +1739502683.3995545,43.67995834350586,42.139797136358645,1739502683.3995574,43.67995834350586,1.889608830573974,1739502683.3995607,43.67995834350586,70.44484749950819,1739502683.399564,43.67995834350586,39.221434354768334,1739502683.399566,43.67995834350586,0.07543309835502113,1739502683.3995678,43.67995834350586,-2.585412007726218,1739502683.3995695,43.67995834350586,-1.517908068800869,1739502683.399571,43.67995834350586,-0.6108,1739502683.3995724,43.67995834350586,0.7422748228670277,1739502683.3995743,43.67995834350586,0.0,1739502683.399576,43.67995834350586,-0.08361754819917644,1739502683.3995779,43.67995834350586,4.155298286254579,1739502683.3995798,43.67995834350586,0.8258923710662042 +1739502683.4191577,43.69995832443237,42.139797136358645,1739502683.4191613,43.69995832443237,1.889608830573974,1739502683.4191663,43.69995832443237,70.44484749950819,1739502683.4191694,43.69995832443237,39.221434354768334,1739502683.4191716,43.69995832443237,0.07543309835502113,1739502683.4191742,43.69995832443237,-2.585412007726218,1739502683.4191756,43.69995832443237,-1.517908068800869,1739502683.4191775,43.69995832443237,-0.6108,1739502683.419179,43.69995832443237,0.7422748228670277,1739502683.419181,43.69995832443237,0.0,1739502683.4191825,43.69995832443237,-0.08361754819917644,1739502683.4191844,43.69995832443237,4.155298286254579,1739502683.419186,43.69995832443237,0.8258923710662042 +1739502683.439707,43.71995830535889,42.139797136358645,1739502683.4397097,43.71995830535889,1.889608830573974,1739502683.4397135,43.71995830535889,70.44484749950819,1739502683.4397168,43.71995830535889,39.221434354768334,1739502683.4397187,43.71995830535889,0.07543309835502113,1739502683.4397206,43.71995830535889,-2.585412007726218,1739502683.4397223,43.71995830535889,-1.517908068800869,1739502683.439724,43.71995830535889,-0.6108,1739502683.4397256,43.71995830535889,0.7422748228670277,1739502683.4397273,43.71995830535889,0.0,1739502683.4397292,43.71995830535889,-0.08361754819917644,1739502683.4397306,43.71995830535889,4.155298286254579,1739502683.4397326,43.71995830535889,0.8258923710662042 +1739502683.459155,43.7399582862854,42.091168825634995,1739502683.4591582,43.7399582862854,1.8134264939966158,1739502683.4591625,43.7399582862854,70.52558802189715,1739502683.459166,43.7399582862854,39.159918574582974,1739502683.4591677,43.7399582862854,0.06523099353144722,1739502683.4591699,43.7399582862854,-2.603824957618797,1739502683.4591718,43.7399582862854,-1.4885529892716358,1739502683.4591734,43.7399582862854,-0.6108,1739502683.459175,43.7399582862854,0.7599127464895922,1739502683.459177,43.7399582862854,0.0,1739502683.4591787,43.7399582862854,-0.04459293106541343,1739502683.4591806,43.7399582862854,4.130670602052144,1739502683.4591823,43.7399582862854,0.8167008784051033 +1739502683.4792218,43.759958267211914,42.091168825634995,1739502683.4792254,43.759958267211914,1.8134264939966158,1739502683.4792295,43.759958267211914,70.52558802189715,1739502683.4792328,43.759958267211914,39.159918574582974,1739502683.4792342,43.759958267211914,0.06523099353144722,1739502683.4792364,43.759958267211914,-2.603824957618797,1739502683.4792387,43.759958267211914,-1.4885529892716358,1739502683.4792404,43.759958267211914,-0.6108,1739502683.479242,43.759958267211914,0.7599127464895922,1739502683.479244,43.759958267211914,0.0,1739502683.4792457,43.759958267211914,-0.05678813191551113,1739502683.4792473,43.759958267211914,4.130670602052144,1739502683.479249,43.759958267211914,0.8167008784051033 +1739502683.499682,43.77995824813843,42.091168825634995,1739502683.499685,43.77995824813843,1.8134264939966158,1739502683.4996886,43.77995824813843,70.52558802189715,1739502683.499692,43.77995824813843,39.159918574582974,1739502683.4996936,43.77995824813843,0.06523099353144722,1739502683.4996955,43.77995824813843,-2.603824957618797,1739502683.4996974,43.77995824813843,-1.4885529892716358,1739502683.499699,43.77995824813843,-0.6108,1739502683.4997008,43.77995824813843,0.7599127464895922,1739502683.4997025,43.77995824813843,0.0,1739502683.4997041,43.77995824813843,-0.05678813191551113,1739502683.4997058,43.77995824813843,4.130670602052144,1739502683.4997077,43.77995824813843,0.8167008784051033 +1739502683.5191422,43.79995822906494,42.091168825634995,1739502683.5191453,43.79995822906494,1.8134264939966158,1739502683.5191488,43.79995822906494,70.52558802189715,1739502683.5191524,43.79995822906494,39.159918574582974,1739502683.519154,43.79995822906494,0.06523099353144722,1739502683.5191562,43.79995822906494,-2.603824957618797,1739502683.5191581,43.79995822906494,-1.4885529892716358,1739502683.5191598,43.79995822906494,-0.6108,1739502683.5191615,43.79995822906494,0.7599127464895922,1739502683.5191634,43.79995822906494,0.0,1739502683.5191653,43.79995822906494,-0.05678813191551113,1739502683.519167,43.79995822906494,4.130670602052144,1739502683.5191689,43.79995822906494,0.8167008784051033 +1739502683.5387838,43.819958209991455,42.091168825634995,1739502683.538786,43.819958209991455,1.8134264939966158,1739502683.5387888,43.819958209991455,70.52558802189715,1739502683.5387914,43.819958209991455,39.159918574582974,1739502683.5387926,43.819958209991455,0.06523099353144722,1739502683.5387943,43.819958209991455,-2.603824957618797,1739502683.5387955,43.819958209991455,-1.4885529892716358,1739502683.538797,43.819958209991455,-0.6108,1739502683.538798,43.819958209991455,0.7599127464895922,1739502683.5387993,43.819958209991455,0.0,1739502683.5388007,43.819958209991455,-0.05678813191551113,1739502683.538802,43.819958209991455,4.130670602052144,1739502683.538803,43.819958209991455,0.8167008784051033 +1739502683.5592532,43.83995819091797,42.091168825634995,1739502683.5592563,43.83995819091797,1.8134264939966158,1739502683.5592597,43.83995819091797,70.52558802189715,1739502683.5592628,43.83995819091797,39.159918574582974,1739502683.5592642,43.83995819091797,0.06523099353144722,1739502683.559266,43.83995819091797,-2.603824957618797,1739502683.5592678,43.83995819091797,-1.4885529892716358,1739502683.5592697,43.83995819091797,-0.6108,1739502683.5592709,43.83995819091797,0.7599127464895922,1739502683.5592728,43.83995819091797,0.0,1739502683.5592742,43.83995819091797,-0.05678813191551113,1739502683.559276,43.83995819091797,4.130670602052144,1739502683.5592775,43.83995819091797,0.8167008784051033 +1739502683.5803003,43.85995817184448,42.04108412913952,1739502683.5803044,43.85995817184448,1.7391971538715492,1739502683.580309,43.85995817184448,70.53599548387423,1739502683.5803137,43.85995817184448,39.16145918566727,1739502683.5803158,43.85995817184448,0.06547523675212849,1739502683.5803187,43.85995817184448,-2.615089614262872,1739502683.580321,43.85995817184448,-1.4070546491981544,1739502683.5803237,43.85995817184448,-0.6108,1739502683.5803256,43.85995817184448,0.8111088738243954,1739502683.5803282,43.85995817184448,0.0,1739502683.580331,43.85995817184448,0.026382488018039187,1739502683.5803332,43.85995817184448,4.104242031335271,1739502683.5803359,43.85995817184448,0.8107172215765106 +1739502683.600714,43.879958152770996,42.04108412913952,1739502683.6007178,43.879958152770996,1.7391971538715492,1739502683.600722,43.879958152770996,70.53599548387423,1739502683.6007266,43.879958152770996,39.16145918566727,1739502683.6007285,43.879958152770996,0.06547523675212849,1739502683.6007314,43.879958152770996,-2.615089614262872,1739502683.600734,43.879958152770996,-1.4070546491981544,1739502683.6007361,43.879958152770996,-0.6108,1739502683.6007385,43.879958152770996,0.8111088738243954,1739502683.6007411,43.879958152770996,0.0,1739502683.6007435,43.879958152770996,0.0003916522478848439,1739502683.600746,43.879958152770996,4.104242031335271,1739502683.600748,43.879958152770996,0.8107172215765106 +1739502683.6202703,43.89995813369751,42.04108412913952,1739502683.6202748,43.89995813369751,1.7391971538715492,1739502683.620279,43.89995813369751,70.53599548387423,1739502683.6202836,43.89995813369751,39.16145918566727,1739502683.6202862,43.89995813369751,0.06547523675212849,1739502683.620289,43.89995813369751,-2.615089614262872,1739502683.6202915,43.89995813369751,-1.4070546491981544,1739502683.620294,43.89995813369751,-0.6108,1739502683.6202965,43.89995813369751,0.8111088738243954,1739502683.620299,43.89995813369751,0.0,1739502683.6203017,43.89995813369751,0.0003916522478848439,1739502683.620304,43.89995813369751,4.104242031335271,1739502683.6203067,43.89995813369751,0.8107172215765106 +1739502683.640349,43.91995811462402,42.04108412913952,1739502683.640353,43.91995811462402,1.7391971538715492,1739502683.6403575,43.91995811462402,70.53599548387423,1739502683.640362,43.91995811462402,39.16145918566727,1739502683.6403642,43.91995811462402,0.06547523675212849,1739502683.6403673,43.91995811462402,-2.615089614262872,1739502683.6403697,43.91995811462402,-1.4070546491981544,1739502683.6403718,43.91995811462402,-0.6108,1739502683.640374,43.91995811462402,0.8111088738243954,1739502683.6403766,43.91995811462402,0.0,1739502683.6403792,43.91995811462402,0.0003916522478848439,1739502683.640382,43.91995811462402,4.104242031335271,1739502683.6403844,43.91995811462402,0.8107172215765106 +1739502683.6601365,43.93995809555054,42.04108412913952,1739502683.6601405,43.93995809555054,1.7391971538715492,1739502683.660145,43.93995809555054,70.53599548387423,1739502683.6601498,43.93995809555054,39.16145918566727,1739502683.660152,43.93995809555054,0.06547523675212849,1739502683.660155,43.93995809555054,-2.615089614262872,1739502683.6601577,43.93995809555054,-1.4070546491981544,1739502683.6601603,43.93995809555054,-0.6108,1739502683.6601632,43.93995809555054,0.8111088738243954,1739502683.6601658,43.93995809555054,0.0,1739502683.6601682,43.93995809555054,0.0003916522478848439,1739502683.6601713,43.93995809555054,4.104242031335271,1739502683.660174,43.93995809555054,0.8107172215765106 +1739502683.6788714,43.95995807647705,41.989226203077486,1739502683.6788735,43.95995807647705,1.6666624922343134,1739502683.6788769,43.95995807647705,70.70373542274764,1739502683.6788795,43.95995807647705,38.99575675937817,1739502683.678881,43.95995807647705,0.03952594631294354,1739502683.6788826,43.95995807647705,-2.6437055987572586,1739502683.6788838,43.95995807647705,-1.4424963819058618,1739502683.6788855,43.95995807647705,-0.6108,1739502683.6788864,43.95995807647705,0.7884341621539332,1739502683.678888,43.95995807647705,0.0,1739502683.6788895,43.95995807647705,-0.03258358062244392,1739502683.678891,43.95995807647705,4.076650089916402,1739502683.6788926,43.95995807647705,0.8107129757480677 +1739502683.7020788,43.979958057403564,41.989226203077486,1739502683.702083,43.979958057403564,1.6666624922343134,1739502683.702088,43.979958057403564,70.70373542274764,1739502683.702095,43.979958057403564,38.99575675937817,1739502683.702098,43.979958057403564,0.03952594631294354,1739502683.7021024,43.979958057403564,-2.6437055987572586,1739502683.7021058,43.979958057403564,-1.4424963819058618,1739502683.7021105,43.979958057403564,-0.6108,1739502683.7021143,43.979958057403564,0.7884341621539332,1739502683.7021182,43.979958057403564,0.0,1739502683.7021222,43.979958057403564,-0.022278813594134417,1739502683.702125,43.979958057403564,4.076650089916402,1739502683.7021298,43.979958057403564,0.8107129757480677 +1739502683.7188435,43.99995803833008,41.989226203077486,1739502683.7188454,43.99995803833008,1.6666624922343134,1739502683.7188485,43.99995803833008,70.70373542274764,1739502683.718851,43.99995803833008,38.99575675937817,1739502683.7188523,43.99995803833008,0.03952594631294354,1739502683.718854,43.99995803833008,-2.6437055987572586,1739502683.7188551,43.99995803833008,-1.4424963819058618,1739502683.7188563,43.99995803833008,-0.6108,1739502683.7188578,43.99995803833008,0.7884341621539332,1739502683.7188592,43.99995803833008,0.0,1739502683.7188609,43.99995803833008,-0.022278813594134417,1739502683.718862,43.99995803833008,4.076650089916402,1739502683.7188632,43.99995803833008,0.8107129757480677 +1739502683.7391036,44.01995801925659,41.989226203077486,1739502683.739106,44.01995801925659,1.6666624922343134,1739502683.7391086,44.01995801925659,70.70373542274764,1739502683.7391114,44.01995801925659,38.99575675937817,1739502683.7391126,44.01995801925659,0.03952594631294354,1739502683.7391143,44.01995801925659,-2.6437055987572586,1739502683.7391155,44.01995801925659,-1.4424963819058618,1739502683.7391171,44.01995801925659,-0.6108,1739502683.739118,44.01995801925659,0.7884341621539332,1739502683.7391195,44.01995801925659,0.0,1739502683.7391212,44.01995801925659,-0.022278813594134417,1739502683.7391224,44.01995801925659,4.076650089916402,1739502683.7391238,44.01995801925659,0.8107129757480677 +1739502683.769672,44.02995800971985,41.989226203077486,1739502683.7696798,44.02995800971985,1.6666624922343134,1739502683.76969,44.02995800971985,70.70373542274764,1739502683.7697,44.02995800971985,38.99575675937817,1739502683.769705,44.02995800971985,0.03952594631294354,1739502683.7697105,44.02995800971985,-2.6437055987572586,1739502683.7697155,44.02995800971985,-1.4424963819058618,1739502683.7697203,44.02995800971985,-0.6108,1739502683.7697248,44.02995800971985,0.7884341621539332,1739502683.7697308,44.02995800971985,0.0,1739502683.7697356,44.02995800971985,-0.022278813594134417,1739502683.7697408,44.02995800971985,4.076650089916402,1739502683.7697458,44.02995800971985,0.8107129757480677 +1739502683.7879155,44.04995799064636,41.989226203077486,1739502683.7879243,44.04995799064636,1.6666624922343134,1739502683.7879353,44.04995799064636,70.70373542274764,1739502683.787945,44.04995799064636,38.99575675937817,1739502683.78795,44.04995799064636,0.03952594631294354,1739502683.7879565,44.04995799064636,-2.6437055987572586,1739502683.7879612,44.04995799064636,-1.4424963819058618,1739502683.7879663,44.04995799064636,-0.6108,1739502683.787971,44.04995799064636,0.7884341621539332,1739502683.7879765,44.04995799064636,0.0,1739502683.7879813,44.04995799064636,-0.022278813594134417,1739502683.7879868,44.04995799064636,4.076650089916402,1739502683.7879915,44.04995799064636,0.8107129757480677 +1739502683.8134394,44.069957971572876,41.93546611141185,1739502683.8134458,44.069957971572876,1.5956915711390813,1739502683.813453,44.069957971572876,70.85273912737594,1739502683.81346,44.069957971572876,38.85337779574783,1739502683.813464,44.069957971572876,0.020163494280576524,1739502683.8134682,44.069957971572876,-2.6690343670772716,1739502683.813472,44.069957971572876,-1.4583462433771959,1739502683.8134754,44.069957971572876,-0.6108,1739502683.813479,44.069957971572876,0.7785000193694558,1739502683.813483,44.069957971572876,0.0,1739502683.8134866,44.069957971572876,-0.03287774859359821,1739502683.8134904,44.069957971572876,4.049042636466195,1739502683.813494,44.069957971572876,0.8080655986040941 +1739502683.832316,44.09995794296265,41.93546611141185,1739502683.832322,44.09995794296265,1.5956915711390813,1739502683.8323288,44.09995794296265,70.85273912737594,1739502683.832336,44.09995794296265,38.85337779574783,1739502683.8323393,44.09995794296265,0.020163494280576524,1739502683.8323433,44.09995794296265,-2.6690343670772716,1739502683.832347,44.09995794296265,-1.4583462433771959,1739502683.8323505,44.09995794296265,-0.6108,1739502683.8323536,44.09995794296265,0.7785000193694558,1739502683.8323574,44.09995794296265,0.0,1739502683.8323607,44.09995794296265,-0.029565579234638317,1739502683.8323646,44.09995794296265,4.049042636466195,1739502683.8323681,44.09995794296265,0.8080655986040941 +1739502683.852268,44.11995792388916,41.93546611141185,1739502683.852274,44.11995792388916,1.5956915711390813,1739502683.852281,44.11995792388916,70.85273912737594,1739502683.852288,44.11995792388916,38.85337779574783,1739502683.8522913,44.11995792388916,0.020163494280576524,1739502683.8522954,44.11995792388916,-2.6690343670772716,1739502683.852299,44.11995792388916,-1.4583462433771959,1739502683.8523023,44.11995792388916,-0.6108,1739502683.8523057,44.11995792388916,0.7785000193694558,1739502683.8523097,44.11995792388916,0.0,1739502683.852313,44.11995792388916,-0.029565579234638317,1739502683.8523169,44.11995792388916,4.049042636466195,1739502683.8523207,44.11995792388916,0.8080655986040941 +1739502683.8724408,44.139957904815674,41.93546611141185,1739502683.872447,44.139957904815674,1.5956915711390813,1739502683.8724544,44.139957904815674,70.85273912737594,1739502683.8724616,44.139957904815674,38.85337779574783,1739502683.872465,44.139957904815674,0.020163494280576524,1739502683.8724692,44.139957904815674,-2.6690343670772716,1739502683.8724725,44.139957904815674,-1.4583462433771959,1739502683.8724759,44.139957904815674,-0.6108,1739502683.8724792,44.139957904815674,0.7785000193694558,1739502683.872483,44.139957904815674,0.0,1739502683.8724864,44.139957904815674,-0.029565579234638317,1739502683.8724902,44.139957904815674,4.049042636466195,1739502683.872494,44.139957904815674,0.8080655986040941 +1739502683.893665,44.15995788574219,41.93546611141185,1739502683.8936713,44.15995788574219,1.5956915711390813,1739502683.8936784,44.15995788574219,70.85273912737594,1739502683.8936853,44.15995788574219,38.85337779574783,1739502683.893689,44.15995788574219,0.020163494280576524,1739502683.8936934,44.15995788574219,-2.6690343670772716,1739502683.893697,44.15995788574219,-1.4583462433771959,1739502683.8937006,44.15995788574219,-0.6108,1739502683.8937037,44.15995788574219,0.7785000193694558,1739502683.893708,44.15995788574219,0.0,1739502683.8937113,44.15995788574219,-0.029565579234638317,1739502683.893715,44.15995788574219,4.049042636466195,1739502683.8937182,44.15995788574219,0.8080655986040941 +1739502683.9138248,44.1799578666687,41.87996140548262,1739502683.9138334,44.1799578666687,1.5264733075513623,1739502683.913845,44.1799578666687,70.8616767395576,1739502683.913859,44.1799578666687,38.85092522716748,1739502683.9138665,44.1799578666687,0.0198609046505337,1739502683.9138763,44.1799578666687,-2.680035197713781,1739502683.9138849,44.1799578666687,-1.3741693482835464,1739502683.9138937,44.1799578666687,-0.6108,1739502683.9139023,44.1799578666687,0.8327308929000864,1739502683.9139113,44.1799578666687,0.0,1739502683.9139202,44.1799578666687,0.05401858743323856,1739502683.9139292,44.1799578666687,4.0214351830159885,1739502683.9139383,44.1799578666687,0.8048323746762113 +1739502683.9338596,44.199957847595215,41.87996140548262,1739502683.933869,44.199957847595215,1.5264733075513623,1739502683.9338806,44.199957847595215,70.8616767395576,1739502683.9338942,44.199957847595215,38.85092522716748,1739502683.9339015,44.199957847595215,0.0198609046505337,1739502683.9339113,44.199957847595215,-2.680035197713781,1739502683.9339201,44.199957847595215,-1.3741693482835464,1739502683.933929,44.199957847595215,-0.6108,1739502683.9339373,44.199957847595215,0.8327308929000864,1739502683.9339466,44.199957847595215,0.0,1739502683.9339554,44.199957847595215,0.027898518223875124,1739502683.9339645,44.199957847595215,4.0214351830159885,1739502683.9339733,44.199957847595215,0.8048323746762113 +1739502683.9529243,44.21995782852173,41.87996140548262,1739502683.952931,44.21995782852173,1.5264733075513623,1739502683.9529383,44.21995782852173,70.8616767395576,1739502683.9529452,44.21995782852173,38.85092522716748,1739502683.9529488,44.21995782852173,0.0198609046505337,1739502683.9529533,44.21995782852173,-2.680035197713781,1739502683.9529572,44.21995782852173,-1.3741693482835464,1739502683.9529607,44.21995782852173,-0.6108,1739502683.9529638,44.21995782852173,0.8327308929000864,1739502683.9529676,44.21995782852173,0.0,1739502683.9529712,44.21995782852173,0.027898518223875124,1739502683.9529748,44.21995782852173,4.0214351830159885,1739502683.9529781,44.21995782852173,0.8048323746762113 +1739502683.972217,44.23995780944824,41.87996140548262,1739502683.972223,44.23995780944824,1.5264733075513623,1739502683.9722297,44.23995780944824,70.8616767395576,1739502683.9722366,44.23995780944824,38.85092522716748,1739502683.9722402,44.23995780944824,0.0198609046505337,1739502683.972244,44.23995780944824,-2.680035197713781,1739502683.9722478,44.23995780944824,-1.3741693482835464,1739502683.9722512,44.23995780944824,-0.6108,1739502683.9722545,44.23995780944824,0.8327308929000864,1739502683.9722583,44.23995780944824,0.0,1739502683.9722617,44.23995780944824,0.027898518223875124,1739502683.9722652,44.23995780944824,4.0214351830159885,1739502683.9722686,44.23995780944824,0.8048323746762113 +1739502683.995456,44.259957790374756,41.87996140548262,1739502683.9954607,44.259957790374756,1.5264733075513623,1739502683.9954665,44.259957790374756,70.8616767395576,1739502683.9954724,44.259957790374756,38.85092522716748,1739502683.995475,44.259957790374756,0.0198609046505337,1739502683.9954782,44.259957790374756,-2.680035197713781,1739502683.995481,44.259957790374756,-1.3741693482835464,1739502683.9954836,44.259957790374756,-0.6108,1739502683.995486,44.259957790374756,0.8327308929000864,1739502683.9954891,44.259957790374756,0.0,1739502683.9954915,44.259957790374756,0.027898518223875124,1739502683.9954944,44.259957790374756,4.0214351830159885,1739502683.995497,44.259957790374756,0.8048323746762113 +1739502684.0115635,44.27995777130127,41.87996140548262,1739502684.0115693,44.27995777130127,1.5264733075513623,1739502684.0115747,44.27995777130127,70.8616767395576,1739502684.0115802,44.27995777130127,38.85092522716748,1739502684.0115826,44.27995777130127,0.0198609046505337,1739502684.0115862,44.27995777130127,-2.680035197713781,1739502684.0115893,44.27995777130127,-1.3741693482835464,1739502684.011592,44.27995777130127,-0.6108,1739502684.0115945,44.27995777130127,0.8327308929000864,1739502684.0115979,44.27995777130127,0.0,1739502684.0116005,44.27995777130127,0.027898518223875124,1739502684.0116034,44.27995777130127,4.0214351830159885,1739502684.0116062,44.27995777130127,0.8048323746762113 +1739502684.0313585,44.29995775222778,41.822561060291235,1739502684.031362,44.29995775222778,1.4588089851540094,1739502684.0313663,44.29995775222778,71.01631756685256,1739502684.031371,44.29995775222778,38.690166096562166,1739502684.031373,44.29995775222778,0.001637872058155401,1739502684.0313756,44.29995775222778,-2.706175542878591,1739502684.031378,44.29995775222778,-1.398662571434282,1739502684.03138,44.29995775222778,-0.6108,1739502684.031382,44.29995775222778,0.8165727054569462,1739502684.0313845,44.29995775222778,0.0,1739502684.0313866,44.29995775222778,-0.0008084402850497188,1739502684.031389,44.29995775222778,3.993827729565783,1739502684.031391,44.29995775222778,0.8084102153261565 +1739502684.0502279,44.3199577331543,41.822561060291235,1739502684.0502305,44.3199577331543,1.4588089851540094,1739502684.050234,44.3199577331543,71.01631756685256,1739502684.0502372,44.3199577331543,38.690166096562166,1739502684.0502386,44.3199577331543,0.001637872058155401,1739502684.0502408,44.3199577331543,-2.706175542878591,1739502684.0502422,44.3199577331543,-1.398662571434282,1739502684.0502439,44.3199577331543,-0.6108,1739502684.0502453,44.3199577331543,0.8165727054569462,1739502684.0502472,44.3199577331543,0.0,1739502684.0502486,44.3199577331543,0.008162490130789624,1739502684.0502505,44.3199577331543,3.993827729565783,1739502684.050252,44.3199577331543,0.8084102153261565 +1739502684.0699034,44.33995771408081,41.822561060291235,1739502684.069906,44.33995771408081,1.4588089851540094,1739502684.0699093,44.33995771408081,71.01631756685256,1739502684.069912,44.33995771408081,38.690166096562166,1739502684.0699136,44.33995771408081,0.001637872058155401,1739502684.0699155,44.33995771408081,-2.706175542878591,1739502684.0699172,44.33995771408081,-1.398662571434282,1739502684.0699189,44.33995771408081,-0.6108,1739502684.0699208,44.33995771408081,0.8165727054569462,1739502684.0699222,44.33995771408081,0.0,1739502684.069924,44.33995771408081,0.008162490130789624,1739502684.0699255,44.33995771408081,3.993827729565783,1739502684.0699275,44.33995771408081,0.8084102153261565 +1739502684.0901535,44.359957695007324,41.822561060291235,1739502684.0901563,44.359957695007324,1.4588089851540094,1739502684.0901597,44.359957695007324,71.01631756685256,1739502684.0901625,44.359957695007324,38.690166096562166,1739502684.090164,44.359957695007324,0.001637872058155401,1739502684.0901659,44.359957695007324,-2.706175542878591,1739502684.0901678,44.359957695007324,-1.398662571434282,1739502684.0901694,44.359957695007324,-0.6108,1739502684.0901706,44.359957695007324,0.8165727054569462,1739502684.0901728,44.359957695007324,0.0,1739502684.0901742,44.359957695007324,0.008162490130789624,1739502684.0901763,44.359957695007324,3.993827729565783,1739502684.0901778,44.359957695007324,0.8084102153261565 +1739502684.1100128,44.37995767593384,41.822561060291235,1739502684.110015,44.37995767593384,1.4588089851540094,1739502684.1100178,44.37995767593384,71.01631756685256,1739502684.1100209,44.37995767593384,38.690166096562166,1739502684.110022,44.37995767593384,0.001637872058155401,1739502684.110024,44.37995767593384,-2.706175542878591,1739502684.1100254,44.37995767593384,-1.398662571434282,1739502684.1100268,44.37995767593384,-0.6108,1739502684.110028,44.37995767593384,0.8165727054569462,1739502684.11003,44.37995767593384,0.0,1739502684.1100311,44.37995767593384,0.008162490130789624,1739502684.1100326,44.37995767593384,3.993827729565783,1739502684.110034,44.37995767593384,0.8084102153261565 +1739502684.130175,44.39995765686035,41.763155053355334,1739502684.1301777,44.39995765686035,1.3925758488359978,1739502684.1301808,44.39995765686035,71.02179311027818,1739502684.1301837,44.39995765686035,38.682908741525125,1739502684.130185,44.39995765686035,0.0008883940196151774,1739502684.1301868,44.39995765686035,-2.7172341809144474,1739502684.1301882,44.39995765686035,-1.3170898078048825,1739502684.1301897,44.39995765686035,-0.6108,1739502684.1301908,44.39995765686035,0.871637969066928,1739502684.130192,44.39995765686035,0.0,1739502684.1301937,44.39995765686035,0.08693350833313625,1739502684.130195,44.39995765686035,3.966220276115581,1739502684.130197,44.39995765686035,0.8093204200615057 +1739502684.1499927,44.419957637786865,41.763155053355334,1739502684.149996,44.419957637786865,1.3925758488359978,1739502684.149999,44.419957637786865,71.02179311027818,1739502684.1500018,44.419957637786865,38.682908741525125,1739502684.1500032,44.419957637786865,0.0008883940196151774,1739502684.1500053,44.419957637786865,-2.7172341809144474,1739502684.1500065,44.419957637786865,-1.3170898078048825,1739502684.1500082,44.419957637786865,-0.6108,1739502684.1500096,44.419957637786865,0.871637969066928,1739502684.1500113,44.419957637786865,0.0,1739502684.1500127,44.419957637786865,0.0623175490054223,1739502684.1500142,44.419957637786865,3.966220276115581,1739502684.1500158,44.419957637786865,0.8093204200615057 +1739502684.169849,44.43995761871338,41.763155053355334,1739502684.169852,44.43995761871338,1.3925758488359978,1739502684.169855,44.43995761871338,71.02179311027818,1739502684.1698582,44.43995761871338,38.682908741525125,1739502684.16986,44.43995761871338,0.0008883940196151774,1739502684.1698618,44.43995761871338,-2.7172341809144474,1739502684.1698632,44.43995761871338,-1.3170898078048825,1739502684.169865,44.43995761871338,-0.6108,1739502684.1698663,44.43995761871338,0.871637969066928,1739502684.1698678,44.43995761871338,0.0,1739502684.1698694,44.43995761871338,0.0623175490054223,1739502684.1698709,44.43995761871338,3.966220276115581,1739502684.1698723,44.43995761871338,0.8093204200615057 +1739502684.1899257,44.45995759963989,41.763155053355334,1739502684.1899288,44.45995759963989,1.3925758488359978,1739502684.1899319,44.45995759963989,71.02179311027818,1739502684.1899345,44.45995759963989,38.682908741525125,1739502684.1899362,44.45995759963989,0.0008883940196151774,1739502684.1899378,44.45995759963989,-2.7172341809144474,1739502684.1899395,44.45995759963989,-1.3170898078048825,1739502684.189941,44.45995759963989,-0.6108,1739502684.1899424,44.45995759963989,0.871637969066928,1739502684.189944,44.45995759963989,0.0,1739502684.1899457,44.45995759963989,0.0623175490054223,1739502684.1899471,44.45995759963989,3.966220276115581,1739502684.1899486,44.45995759963989,0.8093204200615057 +1739502684.2150238,44.479957580566406,41.763155053355334,1739502684.215032,44.479957580566406,1.3925758488359978,1739502684.2150426,44.479957580566406,71.02179311027818,1739502684.2150528,44.479957580566406,38.682908741525125,1739502684.2150576,44.479957580566406,0.0008883940196151774,1739502684.215064,44.479957580566406,-2.7172341809144474,1739502684.2150688,44.479957580566406,-1.3170898078048825,1739502684.2150738,44.479957580566406,-0.6108,1739502684.2150784,44.479957580566406,0.871637969066928,1739502684.2150843,44.479957580566406,0.0,1739502684.215089,44.479957580566406,0.0623175490054223,1739502684.2150946,44.479957580566406,3.966220276115581,1739502684.2150996,44.479957580566406,0.8093204200615057 +1739502684.2388115,44.49995756149292,41.763155053355334,1739502684.238819,44.49995756149292,1.3925758488359978,1739502684.2388282,44.49995756149292,71.02179311027818,1739502684.2388391,44.49995756149292,38.682908741525125,1739502684.2388446,44.49995756149292,0.0008883940196151774,1739502684.2388523,44.49995756149292,-2.7172341809144474,1739502684.2388592,44.49995756149292,-1.3170898078048825,1739502684.2388659,44.49995756149292,-0.6108,1739502684.2388725,44.49995756149292,0.871637969066928,1739502684.2388794,44.49995756149292,0.0,1739502684.2388864,44.49995756149292,0.0623175490054223,1739502684.2388933,44.49995756149292,3.966220276115581,1739502684.2389,44.49995756149292,0.8093204200615057 +1739502684.2561085,44.50995755195618,41.70163966210803,1739502684.256114,44.50995755195618,1.3276897348499883,1739502684.2561214,44.50995755195618,71.13753061428001,1739502684.2561297,44.50995755195618,38.55315431080618,1739502684.2561347,44.50995755195618,-0.011851297905062506,1739502684.2561405,44.50995755195618,-2.739336089174861,1739502684.2561462,44.50995755195618,-1.3159121757666585,1739502684.256152,44.50995755195618,-0.6108,1739502684.2561572,44.50995755195618,0.872459531043729,1739502684.256163,44.50995755195618,0.0,1739502684.2561684,44.50995755195618,0.052863084835189034,1739502684.256174,44.50995755195618,3.938612822665379,1739502684.2561796,44.50995755195618,0.8166419242182065 +1739502684.2734163,44.53995752334595,41.70163966210803,1739502684.2734194,44.53995752334595,1.3276897348499883,1739502684.2734232,44.53995752334595,71.13753061428001,1739502684.273427,44.53995752334595,38.55315431080618,1739502684.2734287,44.53995752334595,-0.011851297905062506,1739502684.273431,44.53995752334595,-2.739336089174861,1739502684.2734327,44.53995752334595,-1.3159121757666585,1739502684.2734349,44.53995752334595,-0.6108,1739502684.2734368,44.53995752334595,0.872459531043729,1739502684.2734387,44.53995752334595,0.0,1739502684.2734406,44.53995752334595,0.0558176068255225,1739502684.2734425,44.53995752334595,3.938612822665379,1739502684.2734447,44.53995752334595,0.8166419242182065 +1739502684.2944605,44.55995750427246,41.70163966210803,1739502684.294465,44.55995750427246,1.3276897348499883,1739502684.2944715,44.55995750427246,71.13753061428001,1739502684.2944784,44.55995750427246,38.55315431080618,1739502684.2944827,44.55995750427246,-0.011851297905062506,1739502684.2944877,44.55995750427246,-2.739336089174861,1739502684.2944925,44.55995750427246,-1.3159121757666585,1739502684.2944968,44.55995750427246,-0.6108,1739502684.2945013,44.55995750427246,0.872459531043729,1739502684.2945063,44.55995750427246,0.0,1739502684.2945108,44.55995750427246,0.0558176068255225,1739502684.2945154,44.55995750427246,3.938612822665379,1739502684.2945204,44.55995750427246,0.8166419242182065 +1739502684.3104815,44.579957485198975,41.70163966210803,1739502684.3104846,44.579957485198975,1.3276897348499883,1739502684.3104885,44.579957485198975,71.13753061428001,1739502684.3104918,44.579957485198975,38.55315431080618,1739502684.3104937,44.579957485198975,-0.011851297905062506,1739502684.310496,44.579957485198975,-2.739336089174861,1739502684.310498,44.579957485198975,-1.3159121757666585,1739502684.3105,44.579957485198975,-0.6108,1739502684.3105016,44.579957485198975,0.872459531043729,1739502684.3105037,44.579957485198975,0.0,1739502684.3105054,44.579957485198975,0.0558176068255225,1739502684.3105073,44.579957485198975,3.938612822665379,1739502684.310509,44.579957485198975,0.8166419242182065 +1739502684.3335025,44.59995746612549,41.70163966210803,1739502684.3335059,44.59995746612549,1.3276897348499883,1739502684.3335097,44.59995746612549,71.13753061428001,1739502684.3335135,44.59995746612549,38.55315431080618,1739502684.3335152,44.59995746612549,-0.011851297905062506,1739502684.3335176,44.59995746612549,-2.739336089174861,1739502684.3335195,44.59995746612549,-1.3159121757666585,1739502684.3335211,44.59995746612549,-0.6108,1739502684.333523,44.59995746612549,0.872459531043729,1739502684.333525,44.59995746612549,0.0,1739502684.3335268,44.59995746612549,0.0558176068255225,1739502684.3335285,44.59995746612549,3.938612822665379,1739502684.3335307,44.59995746612549,0.8166419242182065 +1739502684.3506272,44.619957447052,41.63785070163154,1739502684.3506298,44.619957447052,1.2640210525143996,1739502684.350634,44.619957447052,71.13861406438298,1739502684.3506377,44.619957447052,38.540060663385255,1739502684.3506393,44.619957447052,-0.013028254976606143,1739502684.3506417,44.619957447052,-2.750574778258286,1739502684.3506434,44.619957447052,-1.2378450919417423,1739502684.3506453,44.619957447052,-0.6108,1739502684.350647,44.619957447052,0.928685306708628,1739502684.350649,44.619957447052,0.0,1739502684.3506505,44.619957447052,0.12882749293643214,1739502684.3506527,44.619957447052,3.911005369215177,1739502684.3506544,44.619957447052,0.8226734181409311 +1739502684.3734381,44.639957427978516,41.63785070163154,1739502684.3734412,44.639957427978516,1.2640210525143996,1739502684.3734453,44.639957427978516,71.13861406438298,1739502684.3734493,44.639957427978516,38.540060663385255,1739502684.373451,44.639957427978516,-0.013028254976606143,1739502684.3734534,44.639957427978516,-2.750574778258286,1739502684.3734553,44.639957427978516,-1.2378450919417423,1739502684.373457,44.639957427978516,-0.6108,1739502684.3734586,44.639957427978516,0.928685306708628,1739502684.3734608,44.639957427978516,0.0,1739502684.3734624,44.639957427978516,0.10601188856769694,1739502684.3734643,44.639957427978516,3.911005369215177,1739502684.3734663,44.639957427978516,0.8226734181409311 +1739502684.3907394,44.65995740890503,41.63785070163154,1739502684.3907425,44.65995740890503,1.2640210525143996,1739502684.3907464,44.65995740890503,71.13861406438298,1739502684.3907502,44.65995740890503,38.540060663385255,1739502684.390752,44.65995740890503,-0.013028254976606143,1739502684.3907542,44.65995740890503,-2.750574778258286,1739502684.3907561,44.65995740890503,-1.2378450919417423,1739502684.3907578,44.65995740890503,-0.6108,1739502684.3907597,44.65995740890503,0.928685306708628,1739502684.3907616,44.65995740890503,0.0,1739502684.3907635,44.65995740890503,0.10601188856769694,1739502684.3907657,44.65995740890503,3.911005369215177,1739502684.3907673,44.65995740890503,0.8226734181409311 +1739502684.4106023,44.67995738983154,41.63785070163154,1739502684.410605,44.67995738983154,1.2640210525143996,1739502684.410609,44.67995738983154,71.13861406438298,1739502684.4106128,44.67995738983154,38.540060663385255,1739502684.4106147,44.67995738983154,-0.013028254976606143,1739502684.4106169,44.67995738983154,-2.750574778258286,1739502684.4106188,44.67995738983154,-1.2378450919417423,1739502684.4106205,44.67995738983154,-0.6108,1739502684.4106221,44.67995738983154,0.928685306708628,1739502684.4106243,44.67995738983154,0.0,1739502684.4106264,44.67995738983154,0.10601188856769694,1739502684.410628,44.67995738983154,3.911005369215177,1739502684.41063,44.67995738983154,0.8226734181409311 +1739502684.4315686,44.69995737075806,41.63785070163154,1739502684.4315724,44.69995737075806,1.2640210525143996,1739502684.4315763,44.69995737075806,71.13861406438298,1739502684.43158,44.69995737075806,38.540060663385255,1739502684.4315822,44.69995737075806,-0.013028254976606143,1739502684.4315846,44.69995737075806,-2.750574778258286,1739502684.4315865,44.69995737075806,-1.2378450919417423,1739502684.4315884,44.69995737075806,-0.6108,1739502684.43159,44.69995737075806,0.928685306708628,1739502684.4315922,44.69995737075806,0.0,1739502684.431594,44.69995737075806,0.10601188856769694,1739502684.431596,44.69995737075806,3.911005369215177,1739502684.4315982,44.69995737075806,0.8226734181409311 +1739502684.4509778,44.71995735168457,41.63785070163154,1739502684.4509816,44.71995735168457,1.2640210525143996,1739502684.450986,44.71995735168457,71.13861406438298,1739502684.4509895,44.71995735168457,38.540060663385255,1739502684.4509916,44.71995735168457,-0.013028254976606143,1739502684.450994,44.71995735168457,-2.750574778258286,1739502684.4509957,44.71995735168457,-1.2378450919417423,1739502684.4509978,44.71995735168457,-0.6108,1739502684.4509993,44.71995735168457,0.928685306708628,1739502684.451002,44.71995735168457,0.0,1739502684.4510036,44.71995735168457,0.10601188856769694,1739502684.4510057,44.71995735168457,3.911005369215177,1739502684.4510076,44.71995735168457,0.8226734181409311 +1739502684.4704907,44.739957332611084,41.57160770546459,1739502684.470494,44.739957332611084,1.20145866495381,1739502684.4704978,44.739957332611084,71.13971075044897,1739502684.470502,44.739957332611084,38.51491330711485,1739502684.4705036,44.739957332611084,-0.015288691495294169,1739502684.470506,44.739957332611084,-2.7627599256557644,1739502684.4705079,44.739957332611084,-1.1681165930839421,1739502684.4705095,44.739957332611084,-0.6108,1739502684.4705112,44.739957332611084,0.9819621230605471,1739502684.4705133,44.739957332611084,0.0,1739502684.4705153,44.739957332611084,0.16594032405235942,1739502684.4705172,44.739957332611084,3.883397915764975,1739502684.4705193,44.739957332611084,0.8347494473759478 +1739502684.4904912,44.7599573135376,41.57160770546459,1739502684.4904945,44.7599573135376,1.20145866495381,1739502684.4904983,44.7599573135376,71.13971075044897,1739502684.490502,44.7599573135376,38.51491330711485,1739502684.4905043,44.7599573135376,-0.015288691495294169,1739502684.4905064,44.7599573135376,-2.7627599256557644,1739502684.4905083,44.7599573135376,-1.1681165930839421,1739502684.49051,44.7599573135376,-0.6108,1739502684.4905117,44.7599573135376,0.9819621230605471,1739502684.4905136,44.7599573135376,0.0,1739502684.4905155,44.7599573135376,0.14721267568459928,1739502684.4905176,44.7599573135376,3.883397915764975,1739502684.4905193,44.7599573135376,0.8347494473759478 +1739502684.5111024,44.77995729446411,41.57160770546459,1739502684.511106,44.77995729446411,1.20145866495381,1739502684.5111098,44.77995729446411,71.13971075044897,1739502684.5111136,44.77995729446411,38.51491330711485,1739502684.5111156,44.77995729446411,-0.015288691495294169,1739502684.511118,44.77995729446411,-2.7627599256557644,1739502684.5111198,44.77995729446411,-1.1681165930839421,1739502684.5111217,44.77995729446411,-0.6108,1739502684.5111237,44.77995729446411,0.9819621230605471,1739502684.5111258,44.77995729446411,0.0,1739502684.5111275,44.77995729446411,0.14721267568459928,1739502684.5111296,44.77995729446411,3.883397915764975,1739502684.5111313,44.77995729446411,0.8347494473759478 +1739502684.5344627,44.78995728492737,41.57160770546459,1739502684.534468,44.78995728492737,1.20145866495381,1739502684.534474,44.78995728492737,71.13971075044897,1739502684.534481,44.78995728492737,38.51491330711485,1739502684.5344853,44.78995728492737,-0.015288691495294169,1739502684.5344903,44.78995728492737,-2.7627599256557644,1739502684.5344949,44.78995728492737,-1.1681165930839421,1739502684.5344996,44.78995728492737,-0.6108,1739502684.5345042,44.78995728492737,0.9819621230605471,1739502684.534509,44.78995728492737,0.0,1739502684.5345137,44.78995728492737,0.14721267568459928,1739502684.5345182,44.78995728492737,3.883397915764975,1739502684.5345232,44.78995728492737,0.8347494473759478 +1739502684.5534377,44.81995725631714,41.57160770546459,1739502684.5534408,44.81995725631714,1.20145866495381,1739502684.5534444,44.81995725631714,71.13971075044897,1739502684.5534482,44.81995725631714,38.51491330711485,1739502684.5534499,44.81995725631714,-0.015288691495294169,1739502684.5534523,44.81995725631714,-2.7627599256557644,1739502684.5534542,44.81995725631714,-1.1681165930839421,1739502684.5534558,44.81995725631714,-0.6108,1739502684.5534577,44.81995725631714,0.9819621230605471,1739502684.5534596,44.81995725631714,0.0,1739502684.5534613,44.81995725631714,0.14721267568459928,1739502684.5534632,44.81995725631714,3.883397915764975,1739502684.5534654,44.81995725631714,0.8347494473759478 +1739502684.5708935,44.83995723724365,41.50254291420188,1739502684.5708973,44.83995723724365,1.1397492913788705,1739502684.5709012,44.83995723724365,71.14082600855893,1739502684.570905,44.83995723724365,38.481766606844694,1739502684.5709069,44.83995723724365,-0.01852333931553053,1739502684.5709093,44.83995723724365,-2.775447133688037,1739502684.570911,44.83995723724365,-1.1034304251412541,1739502684.5709128,44.83995723724365,-0.6108,1739502684.5709143,44.83995723724365,1.0341154170489175,1739502684.5709167,44.83995723724365,0.0,1739502684.5709183,44.83995723724365,0.19966170083947493,1739502684.5709202,44.83995723724365,3.855790462314773,1739502684.5709221,44.83995723724365,0.8508440473166797 +1739502684.5904834,44.859957218170166,41.50254291420188,1739502684.5904865,44.859957218170166,1.1397492913788705,1739502684.5904903,44.859957218170166,71.14082600855893,1739502684.5904942,44.859957218170166,38.481766606844694,1739502684.590496,44.859957218170166,-0.01852333931553053,1739502684.5904982,44.859957218170166,-2.775447133688037,1739502684.5905,44.859957218170166,-1.1034304251412541,1739502684.5905018,44.859957218170166,-0.6108,1739502684.5905035,44.859957218170166,1.0341154170489175,1739502684.5905058,44.859957218170166,0.0,1739502684.5905073,44.859957218170166,0.1832713697322378,1739502684.5905094,44.859957218170166,3.855790462314773,1739502684.5905108,44.859957218170166,0.8508440473166797 +1739502684.6148913,44.86995720863342,41.50254291420188,1739502684.614896,44.86995720863342,1.1397492913788705,1739502684.6149025,44.86995720863342,71.14082600855893,1739502684.6149096,44.86995720863342,38.481766606844694,1739502684.6149135,44.86995720863342,-0.01852333931553053,1739502684.6149187,44.86995720863342,-2.775447133688037,1739502684.6149235,44.86995720863342,-1.1034304251412541,1739502684.6149282,44.86995720863342,-0.6108,1739502684.6149328,44.86995720863342,1.0341154170489175,1739502684.6149375,44.86995720863342,0.0,1739502684.6149423,44.86995720863342,0.1832713697322378,1739502684.6149468,44.86995720863342,3.855790462314773,1739502684.6149516,44.86995720863342,0.8508440473166797 +1739502684.6320379,44.89995718002319,41.50254291420188,1739502684.6320407,44.89995718002319,1.1397492913788705,1739502684.6320448,44.89995718002319,71.14082600855893,1739502684.6320484,44.89995718002319,38.481766606844694,1739502684.6320503,44.89995718002319,-0.01852333931553053,1739502684.6320524,44.89995718002319,-2.775447133688037,1739502684.6320543,44.89995718002319,-1.1034304251412541,1739502684.632056,44.89995718002319,-0.6108,1739502684.632058,44.89995718002319,1.0341154170489175,1739502684.6320598,44.89995718002319,0.0,1739502684.6320617,44.89995718002319,0.1832713697322378,1739502684.6320636,44.89995718002319,3.855790462314773,1739502684.6320655,44.89995718002319,0.8508440473166797 +1739502684.6535296,44.91995716094971,41.50254291420188,1739502684.6535327,44.91995716094971,1.1397492913788705,1739502684.6535366,44.91995716094971,71.14082600855893,1739502684.6535404,44.91995716094971,38.481766606844694,1739502684.653542,44.91995716094971,-0.01852333931553053,1739502684.6535444,44.91995716094971,-2.775447133688037,1739502684.6535463,44.91995716094971,-1.1034304251412541,1739502684.653548,44.91995716094971,-0.6108,1739502684.65355,44.91995716094971,1.0341154170489175,1739502684.6535518,44.91995716094971,0.0,1739502684.6535537,44.91995716094971,0.1832713697322378,1739502684.6535554,44.91995716094971,3.855790462314773,1739502684.6535575,44.91995716094971,0.8508440473166797 +1739502684.6734097,44.93995714187622,41.50254291420188,1739502684.6734133,44.93995714187622,1.1397492913788705,1739502684.6734176,44.93995714187622,71.14082600855893,1739502684.6734211,44.93995714187622,38.481766606844694,1739502684.673423,44.93995714187622,-0.01852333931553053,1739502684.6734252,44.93995714187622,-2.775447133688037,1739502684.673427,44.93995714187622,-1.1034304251412541,1739502684.673429,44.93995714187622,-0.6108,1739502684.6734307,44.93995714187622,1.0341154170489175,1739502684.673433,44.93995714187622,0.0,1739502684.673435,44.93995714187622,0.1832713697322378,1739502684.6734366,44.93995714187622,3.855790462314773,1739502684.6734388,44.93995714187622,0.8508440473166797 +1739502684.6908462,44.959957122802734,41.43026560860449,1739502684.6908493,44.959957122802734,1.0786736151624252,1739502684.690853,44.959957122802734,71.14196510971904,1739502684.6908567,44.959957122802734,38.43999977193919,1739502684.6908586,44.959957122802734,-0.02270002280608107,1739502684.6908607,44.959957122802734,-2.788691560842811,1739502684.6908627,44.959957122802734,-1.0437254431439529,1739502684.6908643,44.959957122802734,-0.6108,1739502684.690866,44.959957122802734,1.0847075129781594,1739502684.690868,44.959957122802734,0.0,1739502684.6908698,44.959957122802734,0.22716094167037904,1739502684.6908715,44.959957122802734,3.828183008864571,1739502684.6908734,44.959957122802734,0.8712620715310322 +1739502684.7104962,44.97995710372925,41.43026560860449,1739502684.7104993,44.97995710372925,1.0786736151624252,1739502684.7105033,44.97995710372925,71.14196510971904,1739502684.710507,44.97995710372925,38.43999977193919,1739502684.7105088,44.97995710372925,-0.02270002280608107,1739502684.7105112,44.97995710372925,-2.788691560842811,1739502684.7105129,44.97995710372925,-1.0437254431439529,1739502684.7105148,44.97995710372925,-0.6108,1739502684.7105165,44.97995710372925,1.0847075129781594,1739502684.7105186,44.97995710372925,0.0,1739502684.7105203,44.97995710372925,0.21344544144712718,1739502684.7105222,44.97995710372925,3.828183008864571,1739502684.7105238,44.97995710372925,0.8712620715310322 +1739502684.7305205,44.99995708465576,41.43026560860449,1739502684.730524,44.99995708465576,1.0786736151624252,1739502684.730528,44.99995708465576,71.14196510971904,1739502684.7305317,44.99995708465576,38.43999977193919,1739502684.7305334,44.99995708465576,-0.02270002280608107,1739502684.7305362,44.99995708465576,-2.788691560842811,1739502684.7305381,44.99995708465576,-1.0437254431439529,1739502684.73054,44.99995708465576,-0.6108,1739502684.7305417,44.99995708465576,1.0847075129781594,1739502684.7305439,44.99995708465576,0.0,1739502684.7305458,44.99995708465576,0.21344544144712718,1739502684.7305477,44.99995708465576,3.828183008864571,1739502684.7305498,44.99995708465576,0.8712620715310322 +1739502684.750702,45.019957065582275,41.43026560860449,1739502684.7507055,45.019957065582275,1.0786736151624252,1739502684.7507093,45.019957065582275,71.14196510971904,1739502684.7507129,45.019957065582275,38.43999977193919,1739502684.7507145,45.019957065582275,-0.02270002280608107,1739502684.7507172,45.019957065582275,-2.788691560842811,1739502684.750719,45.019957065582275,-1.0437254431439529,1739502684.750721,45.019957065582275,-0.6108,1739502684.7507226,45.019957065582275,1.0847075129781594,1739502684.750725,45.019957065582275,0.0,1739502684.7507272,45.019957065582275,0.21344544144712718,1739502684.7507288,45.019957065582275,3.828183008864571,1739502684.750731,45.019957065582275,0.8712620715310322 +1739502684.7705157,45.03995704650879,41.43026560860449,1739502684.7705193,45.03995704650879,1.0786736151624252,1739502684.7705233,45.03995704650879,71.14196510971904,1739502684.770527,45.03995704650879,38.43999977193919,1739502684.7705288,45.03995704650879,-0.02270002280608107,1739502684.7705312,45.03995704650879,-2.788691560842811,1739502684.7705328,45.03995704650879,-1.0437254431439529,1739502684.770535,45.03995704650879,-0.6108,1739502684.7705364,45.03995704650879,1.0847075129781594,1739502684.7705388,45.03995704650879,0.0,1739502684.7705405,45.03995704650879,0.21344544144712718,1739502684.7705424,45.03995704650879,3.828183008864571,1739502684.7705443,45.03995704650879,0.8712620715310322 +1739502684.7905004,45.0599570274353,41.35447594427345,1739502684.7905037,45.0599570274353,1.0181363318166774,1739502684.7905078,45.0599570274353,71.66300767393192,1739502684.7905116,45.0599570274353,37.87396681247373,1739502684.7905138,45.0599570274353,-0.06644839018524817,1739502684.7905161,45.0599570274353,-2.839512714609292,1739502684.790518,45.0599570274353,-1.2736717024129964,1739502684.79052,45.0599570274353,-0.6108,1739502684.7905216,45.0599570274353,0.9024458143704738,1739502684.7905235,45.0599570274353,0.0,1739502684.7905254,45.0599570274353,-0.0856396317998923,1739502684.7905273,45.0599570274353,3.800575555414369,1739502684.7905293,45.0599570274353,0.8946212995008026 +1739502684.8141656,45.079957008361816,41.35447594427345,1739502684.8141706,45.079957008361816,1.0181363318166774,1739502684.814177,45.079957008361816,71.66300767393192,1739502684.8141842,45.079957008361816,37.87396681247373,1739502684.814188,45.079957008361816,-0.06644839018524817,1739502684.8141932,45.079957008361816,-2.839512714609292,1739502684.8141978,45.079957008361816,-1.2736717024129964,1739502684.8142025,45.079957008361816,-0.6108,1739502684.8142073,45.079957008361816,0.9024458143704738,1739502684.814212,45.079957008361816,0.0,1739502684.8142166,45.079957008361816,0.007824514869671173,1739502684.8142214,45.079957008361816,3.800575555414369,1739502684.8142262,45.079957008361816,0.8946212995008026 +1739502684.8339376,45.09995698928833,41.35447594427345,1739502684.8339422,45.09995698928833,1.0181363318166774,1739502684.8339486,45.09995698928833,71.66300767393192,1739502684.8339558,45.09995698928833,37.87396681247373,1739502684.8339596,45.09995698928833,-0.06644839018524817,1739502684.833965,45.09995698928833,-2.839512714609292,1739502684.8339696,45.09995698928833,-1.2736717024129964,1739502684.8339741,45.09995698928833,-0.6108,1739502684.8339787,45.09995698928833,0.9024458143704738,1739502684.8339834,45.09995698928833,0.0,1739502684.8339884,45.09995698928833,0.007824514869671173,1739502684.833993,45.09995698928833,3.800575555414369,1739502684.8339975,45.09995698928833,0.8946212995008026 +1739502684.8524883,45.119956970214844,41.35447594427345,1739502684.8524919,45.119956970214844,1.0181363318166774,1739502684.8524966,45.119956970214844,71.66300767393192,1739502684.852502,45.119956970214844,37.87396681247373,1739502684.8525047,45.119956970214844,-0.06644839018524817,1739502684.852509,45.119956970214844,-2.839512714609292,1739502684.8525126,45.119956970214844,-1.2736717024129964,1739502684.8525162,45.119956970214844,-0.6108,1739502684.8525198,45.119956970214844,0.9024458143704738,1739502684.8525233,45.119956970214844,0.0,1739502684.852527,45.119956970214844,0.007824514869671173,1739502684.8525302,45.119956970214844,3.800575555414369,1739502684.8525338,45.119956970214844,0.8946212995008026 +1739502684.8702686,45.13995695114136,41.35447594427345,1739502684.8702714,45.13995695114136,1.0181363318166774,1739502684.870275,45.13995695114136,71.66300767393192,1739502684.870278,45.13995695114136,37.87396681247373,1739502684.8702788,45.13995695114136,-0.06644839018524817,1739502684.870281,45.13995695114136,-2.839512714609292,1739502684.8702822,45.13995695114136,-1.2736717024129964,1739502684.8702836,45.13995695114136,-0.6108,1739502684.8702848,45.13995695114136,0.9024458143704738,1739502684.8702862,45.13995695114136,0.0,1739502684.8702877,45.13995695114136,0.007824514869671173,1739502684.870289,45.13995695114136,3.800575555414369,1739502684.870291,45.13995695114136,0.8946212995008026 +1739502684.8901813,45.15995693206787,41.35447594427345,1739502684.8901842,45.15995693206787,1.0181363318166774,1739502684.8901873,45.15995693206787,71.66300767393192,1739502684.8901896,45.15995693206787,37.87396681247373,1739502684.890191,45.15995693206787,-0.06644839018524817,1739502684.8901927,45.15995693206787,-2.839512714609292,1739502684.890194,45.15995693206787,-1.2736717024129964,1739502684.8901951,45.15995693206787,-0.6108,1739502684.8901966,45.15995693206787,0.9024458143704738,1739502684.890198,45.15995693206787,0.0,1739502684.8901992,45.15995693206787,0.007824514869671173,1739502684.8902009,45.15995693206787,3.800575555414369,1739502684.890202,45.15995693206787,0.8946212995008026 +1739502684.9100995,45.179956912994385,41.27603238275469,1739502684.9101021,45.179956912994385,0.9589432434433913,1739502684.910105,45.179956912994385,71.73657152080781,1739502684.9101079,45.179956912994385,37.80253201970867,1739502684.9101093,45.179956912994385,-0.07076047407671233,1739502684.9101107,45.179956912994385,-2.8534000062349043,1739502684.9101121,45.179956912994385,-1.219059308234119,1739502684.9101138,45.179956912994385,-0.6108,1739502684.9101148,45.179956912994385,0.9427475753731753,1739502684.9101167,45.179956912994385,0.0,1739502684.910118,45.179956912994385,0.06789906851839622,1739502684.9101195,45.179956912994385,3.772968101964167,1739502684.910121,45.179956912994385,0.8936218171787471 +1739502684.9298944,45.1999568939209,41.27603238275469,1739502684.929897,45.1999568939209,0.9589432434433913,1739502684.9299002,45.1999568939209,71.73657152080781,1739502684.929903,45.1999568939209,37.80253201970867,1739502684.9299047,45.1999568939209,-0.07076047407671233,1739502684.9299064,45.1999568939209,-2.8534000062349043,1739502684.9299078,45.1999568939209,-1.219059308234119,1739502684.9299092,45.1999568939209,-0.6108,1739502684.9299104,45.1999568939209,0.9427475753731753,1739502684.9299123,45.1999568939209,0.0,1739502684.9299135,45.1999568939209,0.049125758194428215,1739502684.9299154,45.1999568939209,3.772968101964167,1739502684.929917,45.1999568939209,0.8936218171787471 +1739502684.949975,45.21995687484741,41.27603238275469,1739502684.9499779,45.21995687484741,0.9589432434433913,1739502684.949981,45.21995687484741,71.73657152080781,1739502684.9499836,45.21995687484741,37.80253201970867,1739502684.9499853,45.21995687484741,-0.07076047407671233,1739502684.9499872,45.21995687484741,-2.8534000062349043,1739502684.9499886,45.21995687484741,-1.219059308234119,1739502684.9499898,45.21995687484741,-0.6108,1739502684.9499912,45.21995687484741,0.9427475753731753,1739502684.949993,45.21995687484741,0.0,1739502684.9499943,45.21995687484741,0.049125758194428215,1739502684.9499958,45.21995687484741,3.772968101964167,1739502684.9499974,45.21995687484741,0.8936218171787471 +1739502684.9699433,45.239956855773926,41.27603238275469,1739502684.9699466,45.239956855773926,0.9589432434433913,1739502684.9699497,45.239956855773926,71.73657152080781,1739502684.9699528,45.239956855773926,37.80253201970867,1739502684.969954,45.239956855773926,-0.07076047407671233,1739502684.969956,45.239956855773926,-2.8534000062349043,1739502684.9699576,45.239956855773926,-1.219059308234119,1739502684.969959,45.239956855773926,-0.6108,1739502684.9699602,45.239956855773926,0.9427475753731753,1739502684.969962,45.239956855773926,0.0,1739502684.9699633,45.239956855773926,0.049125758194428215,1739502684.9699647,45.239956855773926,3.772968101964167,1739502684.9699667,45.239956855773926,0.8936218171787471 +1739502684.9900446,45.25995683670044,41.27603238275469,1739502684.9900475,45.25995683670044,0.9589432434433913,1739502684.9900508,45.25995683670044,71.73657152080781,1739502684.9900534,45.25995683670044,37.80253201970867,1739502684.9900548,45.25995683670044,-0.07076047407671233,1739502684.9900568,45.25995683670044,-2.8534000062349043,1739502684.9900582,45.25995683670044,-1.219059308234119,1739502684.9900596,45.25995683670044,-0.6108,1739502684.9900608,45.25995683670044,0.9427475753731753,1739502684.9900622,45.25995683670044,0.0,1739502684.9900637,45.25995683670044,0.049125758194428215,1739502684.990065,45.25995683670044,3.772968101964167,1739502684.990067,45.25995683670044,0.8936218171787471 +1739502685.0217886,45.269956827163696,41.27603238275469,1739502685.0217977,45.269956827163696,0.9589432434433913,1739502685.0218086,45.269956827163696,71.73657152080781,1739502685.021819,45.269956827163696,37.80253201970867,1739502685.0218244,45.269956827163696,-0.07076047407671233,1739502685.0218303,45.269956827163696,-2.8534000062349043,1739502685.0218353,45.269956827163696,-1.219059308234119,1739502685.02184,45.269956827163696,-0.6108,1739502685.0218446,45.269956827163696,0.9427475753731753,1739502685.0218503,45.269956827163696,0.0,1739502685.021855,45.269956827163696,0.049125758194428215,1739502685.0218604,45.269956827163696,3.772968101964167,1739502685.0218651,45.269956827163696,0.8936218171787471 +1739502685.0356405,45.28995680809021,41.1957521013195,1739502685.035649,45.28995680809021,0.9017742376943927,1739502685.0356596,45.28995680809021,71.8909113258176,1739502685.0356698,45.28995680809021,37.63772439291592,1739502685.0356748,45.28995680809021,-0.0794502721885475,1739502685.0356805,45.28995680809021,-2.872503614164953,1739502685.0356855,45.28995680809021,-1.2123180808361742,1739502685.0356903,45.28995680809021,-0.6108,1739502685.0356948,45.28995680809021,0.9478455302340844,1739502685.035701,45.28995680809021,0.0,1739502685.0357058,45.28995680809021,0.048760187172411006,1739502685.0357115,45.28995680809021,3.745360648513965,1739502685.0357163,45.28995680809021,0.8989711020423907 +1739502685.0583696,45.31995677947998,41.1957521013195,1739502685.0583777,45.31995677947998,0.9017742376943927,1739502685.058388,45.31995677947998,71.8909113258176,1739502685.0583973,45.31995677947998,37.63772439291592,1739502685.058402,45.31995677947998,-0.0794502721885475,1739502685.058408,45.31995677947998,-2.872503614164953,1739502685.058413,45.31995677947998,-1.2123180808361742,1739502685.058418,45.31995677947998,-0.6108,1739502685.0584226,45.31995677947998,0.9478455302340844,1739502685.058428,45.31995677947998,0.0,1739502685.058433,45.31995677947998,0.04887442819169363,1739502685.058438,45.31995677947998,3.745360648513965,1739502685.0584433,45.31995677947998,0.8989711020423907 +1739502685.076583,45.32995676994324,41.1957521013195,1739502685.0765874,45.32995676994324,0.9017742376943927,1739502685.0765934,45.32995676994324,71.8909113258176,1739502685.0765991,45.32995676994324,37.63772439291592,1739502685.0766017,45.32995676994324,-0.0794502721885475,1739502685.076605,45.32995676994324,-2.872503614164953,1739502685.076608,45.32995676994324,-1.2123180808361742,1739502685.0766106,45.32995676994324,-0.6108,1739502685.0766132,45.32995676994324,0.9478455302340844,1739502685.0766163,45.32995676994324,0.0,1739502685.0766187,45.32995676994324,0.04887442819169363,1739502685.0766215,45.32995676994324,3.745360648513965,1739502685.0766244,45.32995676994324,0.8989711020423907 +1739502685.0949433,45.35995674133301,41.1957521013195,1739502685.0949473,45.35995674133301,0.9017742376943927,1739502685.0949528,45.35995674133301,71.8909113258176,1739502685.094957,45.35995674133301,37.63772439291592,1739502685.0949593,45.35995674133301,-0.0794502721885475,1739502685.0949621,45.35995674133301,-2.872503614164953,1739502685.0949645,45.35995674133301,-1.2123180808361742,1739502685.0949664,45.35995674133301,-0.6108,1739502685.0949686,45.35995674133301,0.9478455302340844,1739502685.0949712,45.35995674133301,0.0,1739502685.094973,45.35995674133301,0.04887442819169363,1739502685.0949752,45.35995674133301,3.745360648513965,1739502685.0949779,45.35995674133301,0.8989711020423907 +1739502685.117623,45.37995672225952,41.1957521013195,1739502685.1176274,45.37995672225952,0.9017742376943927,1739502685.117633,45.37995672225952,71.8909113258176,1739502685.1176398,45.37995672225952,37.63772439291592,1739502685.117643,45.37995672225952,-0.0794502721885475,1739502685.1176474,45.37995672225952,-2.872503614164953,1739502685.1176515,45.37995672225952,-1.2123180808361742,1739502685.1176553,45.37995672225952,-0.6108,1739502685.1176593,45.37995672225952,0.9478455302340844,1739502685.1176634,45.37995672225952,0.0,1739502685.1176677,45.37995672225952,0.04887442819169363,1739502685.1176717,45.37995672225952,3.745360648513965,1739502685.1176758,45.37995672225952,0.8989711020423907 +1739502685.1356418,45.399956703186035,41.1134295898405,1739502685.1356452,45.399956703186035,0.8465108781155077,1739502685.1356494,45.399956703186035,71.98504633621285,1739502685.1356547,45.399956703186035,37.53300008999269,1739502685.1356575,45.399956703186035,-0.08439758710869782,1739502685.1356611,45.399956703186035,-2.887225433431552,1739502685.1356645,45.399956703186035,-1.170024702282587,1739502685.1356676,45.399956703186035,-0.6108,1739502685.135671,45.399956703186035,0.9804643137770747,1739502685.135674,45.399956703186035,0.0,1739502685.1356773,45.399956703186035,0.08853315003840992,1739502685.1356807,45.399956703186035,3.717753195063763,1739502685.135684,45.399956703186035,0.9043245224414828 +1739502685.1558871,45.41995668411255,41.1134295898405,1739502685.1558902,45.41995668411255,0.8465108781155077,1739502685.1558945,45.41995668411255,71.98504633621285,1739502685.155899,45.41995668411255,37.53300008999269,1739502685.1559017,45.41995668411255,-0.08439758710869782,1739502685.1559052,45.41995668411255,-2.887225433431552,1739502685.1559083,45.41995668411255,-1.170024702282587,1739502685.1559114,45.41995668411255,-0.6108,1739502685.1559145,45.41995668411255,0.9804643137770747,1739502685.1559176,45.41995668411255,0.0,1739502685.1559207,45.41995668411255,0.0761397913355919,1739502685.1559236,45.41995668411255,3.717753195063763,1739502685.155927,45.41995668411255,0.9043245224414828 +1739502685.1755223,45.43995666503906,41.1134295898405,1739502685.1755257,45.43995666503906,0.8465108781155077,1739502685.1755297,45.43995666503906,71.98504633621285,1739502685.1755345,45.43995666503906,37.53300008999269,1739502685.175537,45.43995666503906,-0.08439758710869782,1739502685.1755404,45.43995666503906,-2.887225433431552,1739502685.1755438,45.43995666503906,-1.170024702282587,1739502685.1755471,45.43995666503906,-0.6108,1739502685.17555,45.43995666503906,0.9804643137770747,1739502685.1755533,45.43995666503906,0.0,1739502685.1755564,45.43995666503906,0.0761397913355919,1739502685.1755595,45.43995666503906,3.717753195063763,1739502685.1755629,45.43995666503906,0.9043245224414828 +1739502685.1962085,45.459956645965576,41.1134295898405,1739502685.1962113,45.459956645965576,0.8465108781155077,1739502685.1962156,45.459956645965576,71.98504633621285,1739502685.1962204,45.459956645965576,37.53300008999269,1739502685.196223,45.459956645965576,-0.08439758710869782,1739502685.1962264,45.459956645965576,-2.887225433431552,1739502685.1962295,45.459956645965576,-1.170024702282587,1739502685.1962328,45.459956645965576,-0.6108,1739502685.1962354,45.459956645965576,0.9804643137770747,1739502685.1962385,45.459956645965576,0.0,1739502685.1962416,45.459956645965576,0.0761397913355919,1739502685.196245,45.459956645965576,3.717753195063763,1739502685.196248,45.459956645965576,0.9043245224414828 +1739502685.2210073,45.47995662689209,41.1134295898405,1739502685.221012,45.47995662689209,0.8465108781155077,1739502685.2210186,45.47995662689209,71.98504633621285,1739502685.2210264,45.47995662689209,37.53300008999269,1739502685.2210305,45.47995662689209,-0.08439758710869782,1739502685.221036,45.47995662689209,-2.887225433431552,1739502685.221041,45.47995662689209,-1.170024702282587,1739502685.2210455,45.47995662689209,-0.6108,1739502685.2210503,45.47995662689209,0.9804643137770747,1739502685.2210553,45.47995662689209,0.0,1739502685.22106,45.47995662689209,0.0761397913355919,1739502685.221065,45.47995662689209,3.717753195063763,1739502685.2210698,45.47995662689209,0.9043245224414828 +1739502685.2337987,45.4999566078186,41.02899345633571,1739502685.2338014,45.4999566078186,0.7931504064447878,1739502685.2338047,45.4999566078186,72.05698450387749,1739502685.2338078,45.4999566078186,37.44448431200913,1739502685.2338095,45.4999566078186,-0.08766062751963467,1739502685.2338114,45.4999566078186,-2.9006395697376774,1739502685.2338133,45.4999566078186,-1.117575238488683,1739502685.2338147,45.4999566078186,-0.6108,1739502685.2338161,45.4999566078186,1.022479480827616,1739502685.2338178,45.4999566078186,0.0,1739502685.2338192,45.4999566078186,0.12515253343716856,1739502685.2338207,45.4999566078186,3.690145741613561,1739502685.2338223,45.4999566078186,0.9126434393394649 +1739502685.2539308,45.51995658874512,41.02899345633571,1739502685.253933,45.51995658874512,0.7931504064447878,1739502685.2539363,45.51995658874512,72.05698450387749,1739502685.253939,45.51995658874512,37.44448431200913,1739502685.2539406,45.51995658874512,-0.08766062751963467,1739502685.253942,45.51995658874512,-2.9006395697376774,1739502685.2539432,45.51995658874512,-1.117575238488683,1739502685.2539449,45.51995658874512,-0.6108,1739502685.2539458,45.51995658874512,1.022479480827616,1739502685.2539475,45.51995658874512,0.0,1739502685.253949,45.51995658874512,0.10983604148815118,1739502685.25395,45.51995658874512,3.690145741613561,1739502685.253952,45.51995658874512,0.9126434393394649 +1739502685.273427,45.53995656967163,41.02899345633571,1739502685.2734294,45.53995656967163,0.7931504064447878,1739502685.2734325,45.53995656967163,72.05698450387749,1739502685.2734354,45.53995656967163,37.44448431200913,1739502685.2734368,45.53995656967163,-0.08766062751963467,1739502685.2734385,45.53995656967163,-2.9006395697376774,1739502685.2734396,45.53995656967163,-1.117575238488683,1739502685.273441,45.53995656967163,-0.6108,1739502685.273442,45.53995656967163,1.022479480827616,1739502685.2734437,45.53995656967163,0.0,1739502685.273445,45.53995656967163,0.10983604148815118,1739502685.2734463,45.53995656967163,3.690145741613561,1739502685.2734478,45.53995656967163,0.9126434393394649 +1739502685.2943382,45.559956550598145,41.02899345633571,1739502685.2943408,45.559956550598145,0.7931504064447878,1739502685.2943447,45.559956550598145,72.05698450387749,1739502685.2943478,45.559956550598145,37.44448431200913,1739502685.2943497,45.559956550598145,-0.08766062751963467,1739502685.2943516,45.559956550598145,-2.9006395697376774,1739502685.2943532,45.559956550598145,-1.117575238488683,1739502685.2943547,45.559956550598145,-0.6108,1739502685.294356,45.559956550598145,1.022479480827616,1739502685.2943583,45.559956550598145,0.0,1739502685.29436,45.559956550598145,0.10983604148815118,1739502685.2943616,45.559956550598145,3.690145741613561,1739502685.2943635,45.559956550598145,0.9126434393394649 +1739502685.3140929,45.57995653152466,41.02899345633571,1739502685.3140962,45.57995653152466,0.7931504064447878,1739502685.3141005,45.57995653152466,72.05698450387749,1739502685.314104,45.57995653152466,37.44448431200913,1739502685.3141057,45.57995653152466,-0.08766062751963467,1739502685.3141084,45.57995653152466,-2.9006395697376774,1739502685.3141105,45.57995653152466,-1.117575238488683,1739502685.314112,45.57995653152466,-0.6108,1739502685.3141136,45.57995653152466,1.022479480827616,1739502685.3141158,45.57995653152466,0.0,1739502685.3141177,45.57995653152466,0.10983604148815118,1739502685.3141196,45.57995653152466,3.690145741613561,1739502685.3141215,45.57995653152466,0.9126434393394649 +1739502685.3338299,45.59995651245117,41.02899345633571,1739502685.3338327,45.59995651245117,0.7931504064447878,1739502685.3338363,45.59995651245117,72.05698450387749,1739502685.3338394,45.59995651245117,37.44448431200913,1739502685.3338408,45.59995651245117,-0.08766062751963467,1739502685.333843,45.59995651245117,-2.9006395697376774,1739502685.3338444,45.59995651245117,-1.117575238488683,1739502685.3338463,45.59995651245117,-0.6108,1739502685.3338475,45.59995651245117,1.022479480827616,1739502685.3338497,45.59995651245117,0.0,1739502685.3338513,45.59995651245117,0.10983604148815118,1739502685.3338532,45.59995651245117,3.690145741613561,1739502685.333855,45.59995651245117,0.9126434393394649 +1739502685.3541703,45.619956493377686,40.94213976589536,1739502685.3541737,45.619956493377686,0.7415619299783982,1739502685.354177,45.619956493377686,72.12820452459776,1739502685.3541803,45.619956493377686,37.34865069372325,1739502685.3541822,45.619956493377686,-0.09149397225106999,1739502685.3541842,45.619956493377686,-2.913792891773733,1739502685.354186,45.619956493377686,-1.0659313659605256,1739502685.3541875,45.619956493377686,-0.5937457505197937,1739502685.3541892,45.619956493377686,1.0656081180932644,1739502685.3541908,45.619956493377686,0.0,1739502685.3541927,45.619956493377686,0.15461208444214625,1739502685.3541942,45.619956493377686,3.662538288163359,1739502685.3541963,45.619956493377686,0.9249885562484543 +1739502685.373993,45.6399564743042,40.94213976589536,1739502685.3739963,45.6399564743042,0.7415619299783982,1739502685.3739998,45.6399564743042,72.12820452459776,1739502685.3740032,45.6399564743042,37.34865069372325,1739502685.374005,45.6399564743042,-0.09149397225106999,1739502685.374007,45.6399564743042,-2.913792891773733,1739502685.3740091,45.6399564743042,-1.0659313659605256,1739502685.3740106,45.6399564743042,-0.5937457505197937,1739502685.3740122,45.6399564743042,1.0656081180932644,1739502685.3740141,45.6399564743042,0.0,1739502685.3740158,45.6399564743042,0.14061956184481006,1739502685.3740175,45.6399564743042,3.662538288163359,1739502685.3740191,45.6399564743042,0.9249885562484543 +1739502685.3953946,45.65995645523071,40.94213976589536,1739502685.395398,45.65995645523071,0.7415619299783982,1739502685.3954022,45.65995645523071,72.12820452459776,1739502685.3954062,45.65995645523071,37.34865069372325,1739502685.3954086,45.65995645523071,-0.09149397225106999,1739502685.3954113,45.65995645523071,-2.913792891773733,1739502685.3954132,45.65995645523071,-1.0659313659605256,1739502685.3954153,45.65995645523071,-0.5937457505197937,1739502685.3954175,45.65995645523071,1.0656081180932644,1739502685.3954196,45.65995645523071,0.0,1739502685.3954217,45.65995645523071,0.14061956184481006,1739502685.3954237,45.65995645523071,3.662538288163359,1739502685.3954258,45.65995645523071,0.9249885562484543 +1739502685.4161272,45.67995643615723,40.94213976589536,1739502685.4161305,45.67995643615723,0.7415619299783982,1739502685.416135,45.67995643615723,72.12820452459776,1739502685.4161398,45.67995643615723,37.34865069372325,1739502685.4161415,45.67995643615723,-0.09149397225106999,1739502685.4161444,45.67995643615723,-2.913792891773733,1739502685.4161468,45.67995643615723,-1.0659313659605256,1739502685.4161487,45.67995643615723,-0.5937457505197937,1739502685.4161506,45.67995643615723,1.0656081180932644,1739502685.4161534,45.67995643615723,0.0,1739502685.416155,45.67995643615723,0.14061956184481006,1739502685.4161575,45.67995643615723,3.662538288163359,1739502685.41616,45.67995643615723,0.9249885562484543 +1739502685.4374037,45.69995641708374,40.94213976589536,1739502685.4374077,45.69995641708374,0.7415619299783982,1739502685.4374123,45.69995641708374,72.12820452459776,1739502685.4374168,45.69995641708374,37.34865069372325,1739502685.4374187,45.69995641708374,-0.09149397225106999,1739502685.4374216,45.69995641708374,-2.913792891773733,1739502685.4374237,45.69995641708374,-1.0659313659605256,1739502685.4374254,45.69995641708374,-0.5937457505197937,1739502685.4374278,45.69995641708374,1.0656081180932644,1739502685.4374304,45.69995641708374,0.0,1739502685.4374323,45.69995641708374,0.14061956184481006,1739502685.4374344,45.69995641708374,3.662538288163359,1739502685.4374366,45.69995641708374,0.9249885562484543 +1739502685.455437,45.719956398010254,40.852593124490916,1739502685.4554412,45.719956398010254,0.6916660163772317,1739502685.4554458,45.719956398010254,72.24493224486308,1739502685.4554498,45.719956398010254,37.201261410232426,1739502685.455452,45.719956398010254,-0.09681335631417666,1739502685.4554548,45.719956398010254,-2.928915372382859,1739502685.455457,45.719956398010254,-1.0346975644750083,1739502685.4554594,45.719956398010254,-0.5627837492482726,1739502685.4554613,45.719956398010254,1.0925699575346424,1739502685.4554636,45.719956398010254,0.0,1739502685.4554658,45.719956398010254,0.15746687366030163,1739502685.455468,45.719956398010254,3.634930834713157,1739502685.4554706,45.719956398010254,0.9403678722685461 +1739502685.4765453,45.73995637893677,40.852593124490916,1739502685.476549,45.73995637893677,0.6916660163772317,1739502685.4765532,45.73995637893677,72.24493224486308,1739502685.4765573,45.73995637893677,37.201261410232426,1739502685.4765594,45.73995637893677,-0.09681335631417666,1739502685.476562,45.73995637893677,-2.928915372382859,1739502685.476564,45.73995637893677,-1.0346975644750083,1739502685.476566,45.73995637893677,-0.5627837492482726,1739502685.4765677,45.73995637893677,1.0925699575346424,1739502685.4765704,45.73995637893677,0.0,1739502685.4765725,45.73995637893677,0.15220208526609624,1739502685.4765747,45.73995637893677,3.634930834713157,1739502685.4765768,45.73995637893677,0.9403678722685461 +1739502685.4959102,45.75995635986328,40.852593124490916,1739502685.4959135,45.75995635986328,0.6916660163772317,1739502685.4959178,45.75995635986328,72.24493224486308,1739502685.495922,45.75995635986328,37.201261410232426,1739502685.4959242,45.75995635986328,-0.09681335631417666,1739502685.4959269,45.75995635986328,-2.928915372382859,1739502685.4959288,45.75995635986328,-1.0346975644750083,1739502685.495931,45.75995635986328,-0.5627837492482726,1739502685.4959328,45.75995635986328,1.0925699575346424,1739502685.495935,45.75995635986328,0.0,1739502685.495937,45.75995635986328,0.15220208526609624,1739502685.495939,45.75995635986328,3.634930834713157,1739502685.4959412,45.75995635986328,0.9403678722685461 +1739502685.516365,45.779956340789795,40.852593124490916,1739502685.5163684,45.779956340789795,0.6916660163772317,1739502685.5163727,45.779956340789795,72.24493224486308,1739502685.5163765,45.779956340789795,37.201261410232426,1739502685.5163789,45.779956340789795,-0.09681335631417666,1739502685.5163815,45.779956340789795,-2.928915372382859,1739502685.5163834,45.779956340789795,-1.0346975644750083,1739502685.5163856,45.779956340789795,-0.5627837492482726,1739502685.5163877,45.779956340789795,1.0925699575346424,1739502685.5163898,45.779956340789795,0.0,1739502685.5163922,45.779956340789795,0.15220208526609624,1739502685.5163941,45.779956340789795,3.634930834713157,1739502685.5163965,45.779956340789795,0.9403678722685461 +1739502685.534601,45.79995632171631,40.852593124490916,1739502685.5346038,45.79995632171631,0.6916660163772317,1739502685.5346074,45.79995632171631,72.24493224486308,1739502685.534611,45.79995632171631,37.201261410232426,1739502685.5346127,45.79995632171631,-0.09681335631417666,1739502685.5346148,45.79995632171631,-2.928915372382859,1739502685.534617,45.79995632171631,-1.0346975644750083,1739502685.5346184,45.79995632171631,-0.5627837492482726,1739502685.5346198,45.79995632171631,1.0925699575346424,1739502685.534622,45.79995632171631,0.0,1739502685.5346239,45.79995632171631,0.15220208526609624,1739502685.5346258,45.79995632171631,3.634930834713157,1739502685.5346277,45.79995632171631,0.9403678722685461 +1739502685.5538342,45.81995630264282,40.852593124490916,1739502685.553837,45.81995630264282,0.6916660163772317,1739502685.5538406,45.81995630264282,72.24493224486308,1739502685.5538437,45.81995630264282,37.201261410232426,1739502685.5538452,45.81995630264282,-0.09681335631417666,1739502685.553847,45.81995630264282,-2.928915372382859,1739502685.5538485,45.81995630264282,-1.0346975644750083,1739502685.5538504,45.81995630264282,-0.5627837492482726,1739502685.5538516,45.81995630264282,1.0925699575346424,1739502685.5538535,45.81995630264282,0.0,1739502685.553855,45.81995630264282,0.15220208526609624,1739502685.5538568,45.81995630264282,3.634930834713157,1739502685.5538585,45.81995630264282,0.9403678722685461 +1739502685.5791137,45.839956283569336,40.760131135677895,1739502685.5791218,45.839956283569336,0.6434412442258219,1739502685.5791323,45.839956283569336,72.41685591524478,1739502685.579142,45.839956283569336,36.99583263583284,1739502685.579147,45.839956283569336,-0.10200170779762406,1739502685.5791533,45.839956283569336,-2.9460923161890404,1739502685.5791585,45.839956283569336,-1.0244068967932327,1739502685.579163,45.839956283569336,-0.5287257108995822,1739502685.579168,45.839956283569336,1.1016017030829148,1739502685.5791736,45.839956283569336,0.0,1739502685.5791786,45.839956283569336,0.1409184131690075,1739502685.5791836,45.839956283569336,3.607323381262955,1739502685.579189,45.839956283569336,0.9571571400716431 +1739502685.5986512,45.85995626449585,40.760131135677895,1739502685.5986593,45.85995626449585,0.6434412442258219,1739502685.5986695,45.85995626449585,72.41685591524478,1739502685.5986795,45.85995626449585,36.99583263583284,1739502685.5986843,45.85995626449585,-0.10200170779762406,1739502685.5986907,45.85995626449585,-2.9460923161890404,1739502685.598696,45.85995626449585,-1.0244068967932327,1739502685.5987005,45.85995626449585,-0.5287257108995822,1739502685.598705,45.85995626449585,1.1016017030829148,1739502685.5987108,45.85995626449585,0.0,1739502685.598716,45.85995626449585,0.14444456301127173,1739502685.5987208,45.85995626449585,3.607323381262955,1739502685.5987258,45.85995626449585,0.9571571400716431 +1739502685.6198375,45.87995624542236,40.760131135677895,1739502685.6198459,45.87995624542236,0.6434412442258219,1739502685.6198559,45.87995624542236,72.41685591524478,1739502685.6198657,45.87995624542236,36.99583263583284,1739502685.6198704,45.87995624542236,-0.10200170779762406,1739502685.6198766,45.87995624542236,-2.9460923161890404,1739502685.6198816,45.87995624542236,-1.0244068967932327,1739502685.6198866,45.87995624542236,-0.5287257108995822,1739502685.619891,45.87995624542236,1.1016017030829148,1739502685.6198967,45.87995624542236,0.0,1739502685.6199012,45.87995624542236,0.14444456301127173,1739502685.6199062,45.87995624542236,3.607323381262955,1739502685.6199114,45.87995624542236,0.9571571400716431 +1739502685.6436946,45.89995622634888,40.760131135677895,1739502685.643703,45.89995622634888,0.6434412442258219,1739502685.6437135,45.89995622634888,72.41685591524478,1739502685.6437232,45.89995622634888,36.99583263583284,1739502685.6437285,45.89995622634888,-0.10200170779762406,1739502685.6437345,45.89995622634888,-2.9460923161890404,1739502685.6437395,45.89995622634888,-1.0244068967932327,1739502685.6437445,45.89995622634888,-0.5287257108995822,1739502685.6437492,45.89995622634888,1.1016017030829148,1739502685.6437547,45.89995622634888,0.0,1739502685.64376,45.89995622634888,0.14444456301127173,1739502685.643765,45.89995622634888,3.607323381262955,1739502685.6437702,45.89995622634888,0.9571571400716431 +1739502685.6650963,45.91995620727539,40.760131135677895,1739502685.6651044,45.91995620727539,0.6434412442258219,1739502685.665115,45.91995620727539,72.41685591524478,1739502685.6651251,45.91995620727539,36.99583263583284,1739502685.6651301,45.91995620727539,-0.10200170779762406,1739502685.665136,45.91995620727539,-2.9460923161890404,1739502685.6651413,45.91995620727539,-1.0244068967932327,1739502685.6651459,45.91995620727539,-0.5287257108995822,1739502685.6651506,45.91995620727539,1.1016017030829148,1739502685.6651564,45.91995620727539,0.0,1739502685.6651611,45.91995620727539,0.14444456301127173,1739502685.6651666,45.91995620727539,3.607323381262955,1739502685.6651714,45.91995620727539,0.9571571400716431 +1739502685.6844654,45.939956188201904,40.664761838447504,1739502685.6844742,45.939956188201904,0.5969965800014911,1739502685.684485,45.939956188201904,72.53534980959687,1739502685.6844947,45.939956188201904,36.84568768650836,1739502685.6844995,45.939956188201904,-0.10353379911726159,1739502685.684506,45.939956188201904,-2.9601799636324255,1739502685.6845107,45.939956188201904,-0.986331256223291,1739502685.6845152,45.939956188201904,-0.4978328924128429,1739502685.68452,45.939956188201904,1.1356733408684523,1739502685.6845255,45.939956188201904,0.0,1739502685.6845305,45.939956188201904,0.17097868292611243,1739502685.6845357,45.939956188201904,3.5798462131568063,1739502685.6845407,45.939956188201904,0.9729865758523326 +1739502685.7048218,45.95995616912842,40.664761838447504,1739502685.7048302,45.95995616912842,0.5969965800014911,1739502685.7048407,45.95995616912842,72.53534980959687,1739502685.7048514,45.95995616912842,36.84568768650836,1739502685.7048564,45.95995616912842,-0.10353379911726159,1739502685.7048628,45.95995616912842,-2.9601799636324255,1739502685.704868,45.95995616912842,-0.986331256223291,1739502685.7048728,45.95995616912842,-0.4978328924128429,1739502685.7048779,45.95995616912842,1.1356733408684523,1739502685.704883,45.95995616912842,0.0,1739502685.704888,45.95995616912842,0.16268676501611967,1739502685.7048934,45.95995616912842,3.5798462131568063,1739502685.7048988,45.95995616912842,0.9729865758523326 +1739502685.7363067,45.98995614051819,40.664761838447504,1739502685.7363157,45.98995614051819,0.5969965800014911,1739502685.7363267,45.98995614051819,72.53534980959687,1739502685.7363374,45.98995614051819,36.84568768650836,1739502685.7363422,45.98995614051819,-0.10353379911726159,1739502685.7363486,45.98995614051819,-2.9601799636324255,1739502685.7363536,45.98995614051819,-0.986331256223291,1739502685.7363586,45.98995614051819,-0.4978328924128429,1739502685.7363634,45.98995614051819,1.1356733408684523,1739502685.7363691,45.98995614051819,0.0,1739502685.736374,45.98995614051819,0.16268676501611967,1739502685.7363791,45.98995614051819,3.5798462131568063,1739502685.7363842,45.98995614051819,0.9729865758523326 +1739502685.7574406,46.0099561214447,40.664761838447504,1739502685.757448,46.0099561214447,0.5969965800014911,1739502685.7574568,46.0099561214447,72.53534980959687,1739502685.7574675,46.0099561214447,36.84568768650836,1739502685.7574732,46.0099561214447,-0.10353379911726159,1739502685.7574806,46.0099561214447,-2.9601799636324255,1739502685.7574875,46.0099561214447,-0.986331256223291,1739502685.7574942,46.0099561214447,-0.4978328924128429,1739502685.757501,46.0099561214447,1.1356733408684523,1739502685.757508,46.0099561214447,0.0,1739502685.7575147,46.0099561214447,0.16268676501611967,1739502685.7575216,46.0099561214447,3.5798462131568063,1739502685.7575285,46.0099561214447,0.9729865758523326 +1739502685.779313,46.029956102371216,40.664761838447504,1739502685.7793179,46.029956102371216,0.5969965800014911,1739502685.779324,46.029956102371216,72.53534980959687,1739502685.779331,46.029956102371216,36.84568768650836,1739502685.7793353,46.029956102371216,-0.10353379911726159,1739502685.7793403,46.029956102371216,-2.9601799636324255,1739502685.7793448,46.029956102371216,-0.986331256223291,1739502685.7793496,46.029956102371216,-0.4978328924128429,1739502685.7793543,46.029956102371216,1.1356733408684523,1739502685.7793589,46.029956102371216,0.0,1739502685.7793636,46.029956102371216,0.16268676501611967,1739502685.7793684,46.029956102371216,3.5798462131568063,1739502685.7793734,46.029956102371216,0.9729865758523326 +1739502685.7962472,46.059956073760986,40.5664719893891,1739502685.7962508,46.059956073760986,0.5524001289047122,1739502685.7962558,46.059956073760986,72.65491607552364,1739502685.7962599,46.059956073760986,36.69012746795165,1739502685.7962615,46.059956073760986,-0.104,1739502685.7962642,46.059956073760986,-2.973849056872343,1739502685.7962663,46.059956073760986,-0.9491475364714002,1739502685.7962682,46.059956073760986,-0.46777033921313693,1739502685.79627,46.059956073760986,1.169963676612076,1739502685.796272,46.059956073760986,0.0,1739502685.7962742,46.059956073760986,0.18638447414644438,1739502685.7962759,46.059956073760986,3.553164642202006,1739502685.7962778,46.059956073760986,0.9909847414243078 +1739502685.815663,46.0799560546875,40.5664719893891,1739502685.8156667,46.0799560546875,0.5524001289047122,1739502685.8156705,46.0799560546875,72.65491607552364,1739502685.8156745,46.0799560546875,36.69012746795165,1739502685.8156765,46.0799560546875,-0.104,1739502685.8156788,46.0799560546875,-2.973849056872343,1739502685.8156807,46.0799560546875,-0.9491475364714002,1739502685.815683,46.0799560546875,-0.46777033921313693,1739502685.8156846,46.0799560546875,1.169963676612076,1739502685.815687,46.0799560546875,0.0,1739502685.8156886,46.0799560546875,0.1789789351877682,1739502685.8156905,46.0799560546875,3.553164642202006,1739502685.8156927,46.0799560546875,0.9909847414243078 +1739502685.8370776,46.099956035614014,40.5664719893891,1739502685.8370814,46.099956035614014,0.5524001289047122,1739502685.8370857,46.099956035614014,72.65491607552364,1739502685.8370895,46.099956035614014,36.69012746795165,1739502685.8370917,46.099956035614014,-0.104,1739502685.8370938,46.099956035614014,-2.973849056872343,1739502685.837096,46.099956035614014,-0.9491475364714002,1739502685.8370976,46.099956035614014,-0.46777033921313693,1739502685.8370996,46.099956035614014,1.169963676612076,1739502685.8371015,46.099956035614014,0.0,1739502685.8371034,46.099956035614014,0.1789789351877682,1739502685.8371058,46.099956035614014,3.553164642202006,1739502685.8371077,46.099956035614014,0.9909847414243078 +1739502685.8564682,46.11995601654053,40.5664719893891,1739502685.8564742,46.11995601654053,0.5524001289047122,1739502685.8564808,46.11995601654053,72.65491607552364,1739502685.856488,46.11995601654053,36.69012746795165,1739502685.856492,46.11995601654053,-0.104,1739502685.8564975,46.11995601654053,-2.973849056872343,1739502685.856502,46.11995601654053,-0.9491475364714002,1739502685.8565066,46.11995601654053,-0.46777033921313693,1739502685.856511,46.11995601654053,1.169963676612076,1739502685.8565161,46.11995601654053,0.0,1739502685.8565211,46.11995601654053,0.1789789351877682,1739502685.8565261,46.11995601654053,3.553164642202006,1739502685.8565307,46.11995601654053,0.9909847414243078 +1739502685.8755019,46.13995599746704,40.5664719893891,1739502685.8755057,46.13995599746704,0.5524001289047122,1739502685.875511,46.13995599746704,72.65491607552364,1739502685.875515,46.13995599746704,36.69012746795165,1739502685.8755167,46.13995599746704,-0.104,1739502685.8755195,46.13995599746704,-2.973849056872343,1739502685.8755212,46.13995599746704,-0.9491475364714002,1739502685.8755233,46.13995599746704,-0.46777033921313693,1739502685.8755255,46.13995599746704,1.169963676612076,1739502685.8755274,46.13995599746704,0.0,1739502685.8755295,46.13995599746704,0.1789789351877682,1739502685.8755322,46.13995599746704,3.553164642202006,1739502685.875534,46.13995599746704,0.9909847414243078 +1739502685.8957372,46.159955978393555,40.465171754817135,1739502685.895741,46.159955978393555,0.5095692026831458,1739502685.8957458,46.159955978393555,72.7181664331077,1739502685.8957496,46.159955978393555,36.58769316034076,1739502685.8957517,46.159955978393555,-0.104,1739502685.8957543,46.159955978393555,-2.9846546870138075,1739502685.8957562,46.159955978393555,-0.8934043780786645,1739502685.8957584,46.159955978393555,-0.44198906967024787,1739502685.89576,46.159955978393555,1.2233184772792645,1739502685.8957622,46.159955978393555,0.0,1739502685.895764,46.159955978393555,0.22808851441088876,1739502685.8957663,46.159955978393555,3.528119265893799,1739502685.8957684,46.159955978393555,1.0105767164377166 +1739502685.9157147,46.17995595932007,40.465171754817135,1739502685.9157186,46.17995595932007,0.5095692026831458,1739502685.915723,46.17995595932007,72.7181664331077,1739502685.9157271,46.17995595932007,36.58769316034076,1739502685.9157288,46.17995595932007,-0.104,1739502685.9157312,46.17995595932007,-2.9846546870138075,1739502685.9157336,46.17995595932007,-0.8934043780786645,1739502685.9157352,46.17995595932007,-0.44198906967024787,1739502685.9157372,46.17995595932007,1.2233184772792645,1739502685.915739,46.17995595932007,0.0,1739502685.915741,46.17995595932007,0.21274176084154783,1739502685.9157429,46.17995595932007,3.528119265893799,1739502685.915745,46.17995595932007,1.0105767164377166 +1739502685.934761,46.19995594024658,40.465171754817135,1739502685.9347637,46.19995594024658,0.5095692026831458,1739502685.9347665,46.19995594024658,72.7181664331077,1739502685.9347694,46.19995594024658,36.58769316034076,1739502685.934771,46.19995594024658,-0.104,1739502685.934773,46.19995594024658,-2.9846546870138075,1739502685.9347746,46.19995594024658,-0.8934043780786645,1739502685.9347758,46.19995594024658,-0.44198906967024787,1739502685.9347773,46.19995594024658,1.2233184772792645,1739502685.934779,46.19995594024658,0.0,1739502685.9347804,46.19995594024658,0.21274176084154783,1739502685.9347818,46.19995594024658,3.528119265893799,1739502685.9347832,46.19995594024658,1.0105767164377166 +1739502685.9550524,46.219955921173096,40.465171754817135,1739502685.955055,46.219955921173096,0.5095692026831458,1739502685.9550583,46.219955921173096,72.7181664331077,1739502685.955061,46.219955921173096,36.58769316034076,1739502685.9550629,46.219955921173096,-0.104,1739502685.9550643,46.219955921173096,-2.9846546870138075,1739502685.9550662,46.219955921173096,-0.8934043780786645,1739502685.9550674,46.219955921173096,-0.44198906967024787,1739502685.9550688,46.219955921173096,1.2233184772792645,1739502685.9550707,46.219955921173096,0.0,1739502685.955072,46.219955921173096,0.21274176084154783,1739502685.9550736,46.219955921173096,3.528119265893799,1739502685.955075,46.219955921173096,1.0105767164377166 +1739502685.97483,46.23995590209961,40.465171754817135,1739502685.974833,46.23995590209961,0.5095692026831458,1739502685.9748359,46.23995590209961,72.7181664331077,1739502685.9748387,46.23995590209961,36.58769316034076,1739502685.9748406,46.23995590209961,-0.104,1739502685.9748425,46.23995590209961,-2.9846546870138075,1739502685.9748442,46.23995590209961,-0.8934043780786645,1739502685.9748454,46.23995590209961,-0.44198906967024787,1739502685.974847,46.23995590209961,1.2233184772792645,1739502685.9748487,46.23995590209961,0.0,1739502685.97485,46.23995590209961,0.21274176084154783,1739502685.9748516,46.23995590209961,3.528119265893799,1739502685.974853,46.23995590209961,1.0105767164377166 +1739502685.9948523,46.25995588302612,40.465171754817135,1739502685.9948547,46.25995588302612,0.5095692026831458,1739502685.9948575,46.25995588302612,72.7181664331077,1739502685.9948602,46.25995588302612,36.58769316034076,1739502685.9948618,46.25995588302612,-0.104,1739502685.9948635,46.25995588302612,-2.9846546870138075,1739502685.9948652,46.25995588302612,-0.8934043780786645,1739502685.9948664,46.25995588302612,-0.44198906967024787,1739502685.994868,46.25995588302612,1.2233184772792645,1739502685.9948695,46.25995588302612,0.0,1739502685.9948711,46.25995588302612,0.21274176084154783,1739502685.9948726,46.25995588302612,3.528119265893799,1739502685.994874,46.25995588302612,1.0105767164377166 +1739502686.0147362,46.27995586395264,40.36065005336615,1739502686.0147383,46.27995586395264,0.4683450314782247,1739502686.0147417,46.27995586395264,72.84000170974477,1739502686.0147443,46.27995586395264,36.418609229683454,1739502686.014746,46.27995586395264,-0.104,1739502686.0147476,46.27995586395264,-2.9974101185160857,1739502686.0147493,46.27995586395264,-0.8648032034598291,1739502686.0147505,46.27995586395264,-0.4158931114116524,1739502686.0147517,46.27995586395264,1.2516318364700962,1739502686.0147533,46.27995586395264,0.0,1739502686.0147545,46.27995586395264,0.21956217331887062,1739502686.0147562,46.27995586395264,3.5046211102439786,1739502686.0147576,46.27995586395264,1.0342010434478308 +1739502686.035714,46.29995584487915,40.36065005336615,1739502686.0357168,46.29995584487915,0.4683450314782247,1739502686.035721,46.29995584487915,72.84000170974477,1739502686.0357249,46.29995584487915,36.418609229683454,1739502686.0357265,46.29995584487915,-0.104,1739502686.0357292,46.29995584487915,-2.9974101185160857,1739502686.0357308,46.29995584487915,-0.8648032034598291,1739502686.0357327,46.29995584487915,-0.4158931114116524,1739502686.0357342,46.29995584487915,1.2516318364700962,1739502686.0357366,46.29995584487915,0.0,1739502686.0357385,46.29995584487915,0.21743079302226542,1739502686.0357404,46.29995584487915,3.5046211102439786,1739502686.0357423,46.29995584487915,1.0342010434478308 +1739502686.058405,46.319955825805664,40.36065005336615,1739502686.0584087,46.319955825805664,0.4683450314782247,1739502686.0584135,46.319955825805664,72.84000170974477,1739502686.058418,46.319955825805664,36.418609229683454,1739502686.0584202,46.319955825805664,-0.104,1739502686.058423,46.319955825805664,-2.9974101185160857,1739502686.0584252,46.319955825805664,-0.8648032034598291,1739502686.0584273,46.319955825805664,-0.4158931114116524,1739502686.0584292,46.319955825805664,1.2516318364700962,1739502686.058432,46.319955825805664,0.0,1739502686.0584342,46.319955825805664,0.21743079302226542,1739502686.0584366,46.319955825805664,3.5046211102439786,1739502686.058439,46.319955825805664,1.0342010434478308 +1739502686.0774333,46.33995580673218,40.36065005336615,1739502686.0774372,46.33995580673218,0.4683450314782247,1739502686.077442,46.33995580673218,72.84000170974477,1739502686.0774467,46.33995580673218,36.418609229683454,1739502686.0774486,46.33995580673218,-0.104,1739502686.0774515,46.33995580673218,-2.9974101185160857,1739502686.0774536,46.33995580673218,-0.8648032034598291,1739502686.0774555,46.33995580673218,-0.4158931114116524,1739502686.0774577,46.33995580673218,1.2516318364700962,1739502686.07746,46.33995580673218,0.0,1739502686.077462,46.33995580673218,0.21743079302226542,1739502686.0774648,46.33995580673218,3.5046211102439786,1739502686.0774672,46.33995580673218,1.0342010434478308 +1739502686.0955021,46.35995578765869,40.36065005336615,1739502686.0955052,46.35995578765869,0.4683450314782247,1739502686.095509,46.35995578765869,72.84000170974477,1739502686.0955126,46.35995578765869,36.418609229683454,1739502686.0955145,46.35995578765869,-0.104,1739502686.0955167,46.35995578765869,-2.9974101185160857,1739502686.0955188,46.35995578765869,-0.8648032034598291,1739502686.0955203,46.35995578765869,-0.4158931114116524,1739502686.0955222,46.35995578765869,1.2516318364700962,1739502686.095524,46.35995578765869,0.0,1739502686.095526,46.35995578765869,0.21743079302226542,1739502686.095528,46.35995578765869,3.5046211102439786,1739502686.0955298,46.35995578765869,1.0342010434478308 +1739502686.1153395,46.379955768585205,40.25278184086044,1739502686.1153426,46.379955768585205,0.4286204070358064,1739502686.1153464,46.379955768585205,72.90094231808335,1739502686.1153502,46.379955768585205,36.31004433387853,1739502686.1153522,46.379955768585205,-0.104,1739502686.1153543,46.379955768585205,-3.0073165346179853,1739502686.1153564,46.379955768585205,-0.8166357066455258,1739502686.115358,46.379955768585205,-0.3939431110345323,1739502686.11536,46.379955768585205,1.3008035209403852,1739502686.115362,46.379955768585205,0.0,1739502686.1153638,46.379955768585205,0.25431740872387165,1739502686.115366,46.379955768585205,3.482597729519573,1739502686.1153677,46.379955768585205,1.0580131871810048 +1739502686.1361458,46.39995574951172,40.25278184086044,1739502686.136149,46.39995574951172,0.4286204070358064,1739502686.1361535,46.39995574951172,72.90094231808335,1739502686.1361573,46.39995574951172,36.31004433387853,1739502686.136159,46.39995574951172,-0.104,1739502686.1361616,46.39995574951172,-3.0073165346179853,1739502686.1361632,46.39995574951172,-0.8166357066455258,1739502686.1361651,46.39995574951172,-0.3939431110345323,1739502686.1361668,46.39995574951172,1.3008035209403852,1739502686.136169,46.39995574951172,0.0,1739502686.1361709,46.39995574951172,0.24279033375938042,1739502686.1361728,46.39995574951172,3.482597729519573,1739502686.1361747,46.39995574951172,1.0580131871810048 +1739502686.1555927,46.41995573043823,40.25278184086044,1739502686.155596,46.41995573043823,0.4286204070358064,1739502686.1556,46.41995573043823,72.90094231808335,1739502686.1556036,46.41995573043823,36.31004433387853,1739502686.1556056,46.41995573043823,-0.104,1739502686.1556077,46.41995573043823,-3.0073165346179853,1739502686.1556096,46.41995573043823,-0.8166357066455258,1739502686.1556113,46.41995573043823,-0.3939431110345323,1739502686.155613,46.41995573043823,1.3008035209403852,1739502686.1556153,46.41995573043823,0.0,1739502686.1556168,46.41995573043823,0.24279033375938042,1739502686.155619,46.41995573043823,3.482597729519573,1739502686.1556206,46.41995573043823,1.0580131871810048 +1739502686.1753814,46.439955711364746,40.25278184086044,1739502686.1753843,46.439955711364746,0.4286204070358064,1739502686.1753883,46.439955711364746,72.90094231808335,1739502686.1753917,46.439955711364746,36.31004433387853,1739502686.1753938,46.439955711364746,-0.104,1739502686.1753957,46.439955711364746,-3.0073165346179853,1739502686.1753976,46.439955711364746,-0.8166357066455258,1739502686.1753995,46.439955711364746,-0.3939431110345323,1739502686.1754012,46.439955711364746,1.3008035209403852,1739502686.1754034,46.439955711364746,0.0,1739502686.175405,46.439955711364746,0.24279033375938042,1739502686.175407,46.439955711364746,3.482597729519573,1739502686.1754086,46.439955711364746,1.0580131871810048 +1739502686.1961584,46.45995569229126,40.25278184086044,1739502686.1961615,46.45995569229126,0.4286204070358064,1739502686.1961653,46.45995569229126,72.90094231808335,1739502686.1961691,46.45995569229126,36.31004433387853,1739502686.196171,46.45995569229126,-0.104,1739502686.196173,46.45995569229126,-3.0073165346179853,1739502686.1961749,46.45995569229126,-0.8166357066455258,1739502686.1961765,46.45995569229126,-0.3939431110345323,1739502686.1961782,46.45995569229126,1.3008035209403852,1739502686.1961806,46.45995569229126,0.0,1739502686.196182,46.45995569229126,0.24279033375938042,1739502686.196184,46.45995569229126,3.482597729519573,1739502686.1961858,46.45995569229126,1.0580131871810048 +1739502686.2156146,46.47995567321777,40.25278184086044,1739502686.2156174,46.47995567321777,0.4286204070358064,1739502686.215622,46.47995567321777,72.90094231808335,1739502686.2156258,46.47995567321777,36.31004433387853,1739502686.2156277,46.47995567321777,-0.104,1739502686.2156298,46.47995567321777,-3.0073165346179853,1739502686.215632,46.47995567321777,-0.8166357066455258,1739502686.2156336,46.47995567321777,-0.3939431110345323,1739502686.2156355,46.47995567321777,1.3008035209403852,1739502686.2156377,46.47995567321777,0.0,1739502686.2156396,46.47995567321777,0.24279033375938042,1739502686.2156413,46.47995567321777,3.482597729519573,1739502686.2156434,46.47995567321777,1.0580131871810048 +1739502686.2363677,46.49995565414429,40.14145726768009,1739502686.236371,46.49995565414429,0.3903050871907414,1739502686.236375,46.49995565414429,72.9024314742409,1739502686.2363787,46.49995565414429,36.254873434200825,1739502686.2363803,46.49995565414429,-0.104,1739502686.2363825,46.49995565414429,-3.01508940780851,1739502686.2363846,46.49995565414429,-0.7548729563828508,1739502686.2363863,46.49995565414429,-0.3757089048285064,1739502686.2363882,46.49995565414429,1.3666908319054611,1739502686.23639,46.49995565414429,0.0,1739502686.2363918,46.49995565414429,0.2995851713473865,1739502686.2363937,46.49995565414429,3.4619816491805318,1739502686.2363958,46.49995565414429,1.0848540589410833 +1739502686.2552469,46.5199556350708,40.14145726768009,1739502686.25525,46.5199556350708,0.3903050871907414,1739502686.2552538,46.5199556350708,72.9024314742409,1739502686.2552574,46.5199556350708,36.254873434200825,1739502686.255259,46.5199556350708,-0.104,1739502686.2552617,46.5199556350708,-3.01508940780851,1739502686.2552636,46.5199556350708,-0.7548729563828508,1739502686.2552652,46.5199556350708,-0.3757089048285064,1739502686.2552671,46.5199556350708,1.3666908319054611,1739502686.2552693,46.5199556350708,0.0,1739502686.2552712,46.5199556350708,0.2818367729643778,1739502686.255273,46.5199556350708,3.4619816491805318,1739502686.255275,46.5199556350708,1.0848540589410833 +1739502686.2753386,46.539955615997314,40.14145726768009,1739502686.275342,46.539955615997314,0.3903050871907414,1739502686.2753456,46.539955615997314,72.9024314742409,1739502686.2753496,46.539955615997314,36.254873434200825,1739502686.2753513,46.539955615997314,-0.104,1739502686.2753537,46.539955615997314,-3.01508940780851,1739502686.2753553,46.539955615997314,-0.7548729563828508,1739502686.2753572,46.539955615997314,-0.3757089048285064,1739502686.2753587,46.539955615997314,1.3666908319054611,1739502686.2753608,46.539955615997314,0.0,1739502686.2753625,46.539955615997314,0.2818367729643778,1739502686.2753644,46.539955615997314,3.4619816491805318,1739502686.2753663,46.539955615997314,1.0848540589410833 +1739502686.2962534,46.55995559692383,40.14145726768009,1739502686.2962568,46.55995559692383,0.3903050871907414,1739502686.2962608,46.55995559692383,72.9024314742409,1739502686.2962646,46.55995559692383,36.254873434200825,1739502686.2962666,46.55995559692383,-0.104,1739502686.2962687,46.55995559692383,-3.01508940780851,1739502686.2962708,46.55995559692383,-0.7548729563828508,1739502686.2962728,46.55995559692383,-0.3757089048285064,1739502686.2962742,46.55995559692383,1.3666908319054611,1739502686.2962763,46.55995559692383,0.0,1739502686.296278,46.55995559692383,0.2818367729643778,1739502686.29628,46.55995559692383,3.4619816491805318,1739502686.2962816,46.55995559692383,1.0848540589410833 +1739502686.3156621,46.57995557785034,40.14145726768009,1739502686.3156657,46.57995557785034,0.3903050871907414,1739502686.3156698,46.57995557785034,72.9024314742409,1739502686.3156734,46.57995557785034,36.254873434200825,1739502686.3156757,46.57995557785034,-0.104,1739502686.315678,46.57995557785034,-3.01508940780851,1739502686.3156798,46.57995557785034,-0.7548729563828508,1739502686.3156817,46.57995557785034,-0.3757089048285064,1739502686.3156836,46.57995557785034,1.3666908319054611,1739502686.3156857,46.57995557785034,0.0,1739502686.3156874,46.57995557785034,0.2818367729643778,1739502686.3156896,46.57995557785034,3.4619816491805318,1739502686.3156915,46.57995557785034,1.0848540589410833 +1739502686.3359754,46.599955558776855,40.026403470505485,1739502686.335979,46.599955558776855,0.35326837923400145,1739502686.3359833,46.599955558776855,73.2279836176653,1739502686.335987,46.599955558776855,35.86764788725258,1739502686.335989,46.599955558776855,-0.10389949405099594,1739502686.3359914,46.599955558776855,-3.0321032712165437,1739502686.3359933,46.599955558776855,-0.7963727393361062,1739502686.3359952,46.599955558776855,-0.34784180284972466,1739502686.3359969,46.599955558776855,1.322061869693683,1739502686.3359993,46.599955558776855,0.0,1739502686.336001,46.599955558776855,0.17206814692068206,1739502686.336003,46.599955558776855,3.44259700300547,1739502686.336005,46.599955558776855,1.1156910046437314 +1739502686.3556428,46.61995553970337,40.026403470505485,1739502686.3556466,46.61995553970337,0.35326837923400145,1739502686.355651,46.61995553970337,73.2279836176653,1739502686.3556547,46.61995553970337,35.86764788725258,1739502686.3556566,46.61995553970337,-0.10389949405099594,1739502686.355659,46.61995553970337,-3.0321032712165437,1739502686.3556612,46.61995553970337,-0.7963727393361062,1739502686.3556628,46.61995553970337,-0.34784180284972466,1739502686.3556647,46.61995553970337,1.322061869693683,1739502686.3556669,46.61995553970337,0.0,1739502686.3556688,46.61995553970337,0.2063708650499516,1739502686.3556707,46.61995553970337,3.44259700300547,1739502686.3556726,46.61995553970337,1.1156910046437314 +1739502686.375958,46.63995552062988,40.026403470505485,1739502686.3759615,46.63995552062988,0.35326837923400145,1739502686.3759656,46.63995552062988,73.2279836176653,1739502686.3759696,46.63995552062988,35.86764788725258,1739502686.3759716,46.63995552062988,-0.10389949405099594,1739502686.375974,46.63995552062988,-3.0321032712165437,1739502686.3759758,46.63995552062988,-0.7963727393361062,1739502686.3759778,46.63995552062988,-0.34784180284972466,1739502686.3759792,46.63995552062988,1.322061869693683,1739502686.3759818,46.63995552062988,0.0,1739502686.3759837,46.63995552062988,0.2063708650499516,1739502686.3759856,46.63995552062988,3.44259700300547,1739502686.3759878,46.63995552062988,1.1156910046437314 +1739502686.3962421,46.6599555015564,40.026403470505485,1739502686.3962457,46.6599555015564,0.35326837923400145,1739502686.3962495,46.6599555015564,73.2279836176653,1739502686.3962536,46.6599555015564,35.86764788725258,1739502686.3962557,46.6599555015564,-0.10389949405099594,1739502686.396258,46.6599555015564,-3.0321032712165437,1739502686.39626,46.6599555015564,-0.7963727393361062,1739502686.396262,46.6599555015564,-0.34784180284972466,1739502686.3962634,46.6599555015564,1.322061869693683,1739502686.3962657,46.6599555015564,0.0,1739502686.3962674,46.6599555015564,0.2063708650499516,1739502686.3962693,46.6599555015564,3.44259700300547,1739502686.396271,46.6599555015564,1.1156910046437314 +1739502686.4161959,46.67995548248291,40.026403470505485,1739502686.4161992,46.67995548248291,0.35326837923400145,1739502686.4162033,46.67995548248291,73.2279836176653,1739502686.4162073,46.67995548248291,35.86764788725258,1739502686.4162095,46.67995548248291,-0.10389949405099594,1739502686.4162116,46.67995548248291,-3.0321032712165437,1739502686.4162138,46.67995548248291,-0.7963727393361062,1739502686.4162157,46.67995548248291,-0.34784180284972466,1739502686.4162173,46.67995548248291,1.322061869693683,1739502686.4162197,46.67995548248291,0.0,1739502686.4162214,46.67995548248291,0.2063708650499516,1739502686.4162235,46.67995548248291,3.44259700300547,1739502686.4162254,46.67995548248291,1.1156910046437314 +1739502686.4366333,46.699955463409424,40.026403470505485,1739502686.4366372,46.699955463409424,0.35326837923400145,1739502686.4366412,46.699955463409424,73.2279836176653,1739502686.4366453,46.699955463409424,35.86764788725258,1739502686.4366472,46.699955463409424,-0.10389949405099594,1739502686.4366498,46.699955463409424,-3.0321032712165437,1739502686.4366515,46.699955463409424,-0.7963727393361062,1739502686.4366534,46.699955463409424,-0.34784180284972466,1739502686.436655,46.699955463409424,1.322061869693683,1739502686.4366572,46.699955463409424,0.0,1739502686.4366589,46.699955463409424,0.2063708650499516,1739502686.4366608,46.699955463409424,3.44259700300547,1739502686.4366627,46.699955463409424,1.1156910046437314 +1739502686.45578,46.71995544433594,39.907871013459676,1739502686.4557831,46.71995544433594,0.3175684113886854,1739502686.4557865,46.71995544433594,73.23644935925154,1739502686.4557898,46.71995544433594,35.81530983214945,1739502686.4557915,46.71995544433594,-0.10339135759368402,1739502686.4557934,46.71995544433594,-3.0390933868190233,1739502686.4557953,46.71995544433594,-0.7373073992566095,1739502686.4557967,46.71995544433594,-0.3331640532619114,1739502686.4557984,46.71995544433594,1.3860317559815925,1739502686.4558003,46.71995544433594,0.0,1739502686.455802,46.71995544433594,0.26750905958709287,1739502686.4558036,46.71995544433594,3.4242777437042498,1739502686.4558053,46.71995544433594,1.1376283947140282 +1739502686.474754,46.73995542526245,39.907871013459676,1739502686.4747574,46.73995542526245,0.3175684113886854,1739502686.474761,46.73995542526245,73.23644935925154,1739502686.4747639,46.73995542526245,35.81530983214945,1739502686.4747653,46.73995542526245,-0.10339135759368402,1739502686.4747672,46.73995542526245,-3.0390933868190233,1739502686.4747686,46.73995542526245,-0.7373073992566095,1739502686.47477,46.73995542526245,-0.3331640532619114,1739502686.4747715,46.73995542526245,1.3860317559815925,1739502686.4747732,46.73995542526245,0.0,1739502686.474775,46.73995542526245,0.24840336126756424,1739502686.4747763,46.73995542526245,3.4242777437042498,1739502686.474778,46.73995542526245,1.1376283947140282 +1739502686.495637,46.759955406188965,39.907871013459676,1739502686.49564,46.759955406188965,0.3175684113886854,1739502686.4956431,46.759955406188965,73.23644935925154,1739502686.4956462,46.759955406188965,35.81530983214945,1739502686.4956474,46.759955406188965,-0.10339135759368402,1739502686.4956493,46.759955406188965,-3.0390933868190233,1739502686.4956505,46.759955406188965,-0.7373073992566095,1739502686.4956517,46.759955406188965,-0.3331640532619114,1739502686.4956532,46.759955406188965,1.3860317559815925,1739502686.4956548,46.759955406188965,0.0,1739502686.4956563,46.759955406188965,0.24840336126756424,1739502686.4956574,46.759955406188965,3.4242777437042498,1739502686.4956586,46.759955406188965,1.1376283947140282 +1739502686.514776,46.77995538711548,39.907871013459676,1739502686.5147789,46.77995538711548,0.3175684113886854,1739502686.5147817,46.77995538711548,73.23644935925154,1739502686.5147846,46.77995538711548,35.81530983214945,1739502686.5147858,46.77995538711548,-0.10339135759368402,1739502686.5147877,46.77995538711548,-3.0390933868190233,1739502686.5147889,46.77995538711548,-0.7373073992566095,1739502686.51479,46.77995538711548,-0.3331640532619114,1739502686.5147917,46.77995538711548,1.3860317559815925,1739502686.5147932,46.77995538711548,0.0,1739502686.5147946,46.77995538711548,0.24840336126756424,1739502686.514796,46.77995538711548,3.4242777437042498,1739502686.5147974,46.77995538711548,1.1376283947140282 +1739502686.535437,46.79995536804199,39.907871013459676,1739502686.53544,46.79995536804199,0.3175684113886854,1739502686.5354433,46.79995536804199,73.23644935925154,1739502686.5354457,46.79995536804199,35.81530983214945,1739502686.5354474,46.79995536804199,-0.10339135759368402,1739502686.5354488,46.79995536804199,-3.0390933868190233,1739502686.5354502,46.79995536804199,-0.7373073992566095,1739502686.5354517,46.79995536804199,-0.3331640532619114,1739502686.5354528,46.79995536804199,1.3860317559815925,1739502686.5354548,46.79995536804199,0.0,1739502686.535456,46.79995536804199,0.24840336126756424,1739502686.5354574,46.79995536804199,3.4242777437042498,1739502686.5354588,46.79995536804199,1.1376283947140282 +1739502686.5552607,46.819955348968506,39.78612703487878,1739502686.5552633,46.819955348968506,0.2832455713954172,1739502686.5552664,46.819955348968506,73.43843787790074,1739502686.5552688,46.819955348968506,35.55898563607211,1739502686.5552704,46.819955348968506,-0.10172661885759071,1739502686.555272,46.819955348968506,-3.050771671558915,1739502686.555274,46.819955348968506,-0.7380863696233544,1739502686.5552752,46.819955348968506,-0.3134750688674399,1739502686.5552766,46.819955348968506,1.3851682829252843,1739502686.555278,46.819955348968506,0.0,1739502686.5552797,46.819955348968506,0.20762500253556593,1739502686.5552812,46.819955348968506,3.4071889501576296,1739502686.5552826,46.819955348968506,1.164800034930846 +1739502686.580635,46.83995532989502,39.78612703487878,1739502686.580644,46.83995532989502,0.2832455713954172,1739502686.5806549,46.83995532989502,73.43843787790074,1739502686.5806656,46.83995532989502,35.55898563607211,1739502686.5806923,46.83995532989502,-0.10172661885759071,1739502686.580712,46.83995532989502,-3.050771671558915,1739502686.5807195,46.83995532989502,-0.7380863696233544,1739502686.5807242,46.83995532989502,-0.3134750688674399,1739502686.580729,46.83995532989502,1.3851682829252843,1739502686.5807343,46.83995532989502,0.0,1739502686.580739,46.83995532989502,0.22036824799443822,1739502686.5807443,46.83995532989502,3.4071889501576296,1739502686.5807495,46.83995532989502,1.164800034930846 +1739502686.6009107,46.85995531082153,39.78612703487878,1739502686.6009195,46.85995531082153,0.2832455713954172,1739502686.60093,46.85995531082153,73.43843787790074,1739502686.60094,46.85995531082153,35.55898563607211,1739502686.6009452,46.85995531082153,-0.10172661885759071,1739502686.6009514,46.85995531082153,-3.050771671558915,1739502686.6009567,46.85995531082153,-0.7380863696233544,1739502686.6009614,46.85995531082153,-0.3134750688674399,1739502686.6009665,46.85995531082153,1.3851682829252843,1739502686.600972,46.85995531082153,0.0,1739502686.600977,46.85995531082153,0.22036824799443822,1739502686.6009822,46.85995531082153,3.4071889501576296,1739502686.6009877,46.85995531082153,1.164800034930846 +1739502686.646975,46.89995527267456,39.78612703487878,1739502686.646984,46.89995527267456,0.2832455713954172,1739502686.6469963,46.89995527267456,73.43843787790074,1739502686.6470098,46.89995527267456,35.55898563607211,1739502686.6470172,46.89995527267456,-0.10172661885759071,1739502686.647027,46.89995527267456,-3.050771671558915,1739502686.6470358,46.89995527267456,-0.7380863696233544,1739502686.6470447,46.89995527267456,-0.3134750688674399,1739502686.6470532,46.89995527267456,1.3851682829252843,1739502686.6470623,46.89995527267456,0.0,1739502686.647071,46.89995527267456,0.22036824799443822,1739502686.64708,46.89995527267456,3.4071889501576296,1739502686.647089,46.89995527267456,1.164800034930846 +1739502686.6746829,46.92995524406433,39.66109905293996,1739502686.674686,46.92995524406433,0.25023723084488836,1739502686.6746895,46.92995524406433,73.5139753415866,1739502686.6746929,46.92995524406433,35.4356532485243,1739502686.6746943,46.92995524406433,-0.101,1739502686.6746964,46.92995524406433,-3.0586590155647815,1739502686.6746984,46.92995524406433,-0.7025499435991941,1739502686.6746998,46.92995524406433,-0.2991301816967681,1739502686.6747012,46.92995524406433,1.4251125271084109,1739502686.6747031,46.92995524406433,0.0,1739502686.6747046,46.92995524406433,0.2437073880015093,1739502686.6747065,46.92995524406433,3.3909890077633515,1739502686.6747081,46.92995524406433,1.1886986251410934 +1739502686.6940918,46.9599552154541,39.66109905293996,1739502686.6940968,46.9599552154541,0.25023723084488836,1739502686.6941001,46.9599552154541,73.5139753415866,1739502686.694103,46.9599552154541,35.4356532485243,1739502686.6941047,46.9599552154541,-0.101,1739502686.6941068,46.9599552154541,-3.0586590155647815,1739502686.6941085,46.9599552154541,-0.7025499435991941,1739502686.6941102,46.9599552154541,-0.2991301816967681,1739502686.6941123,46.9599552154541,1.4251125271084109,1739502686.694114,46.9599552154541,0.0,1739502686.6941156,46.9599552154541,0.23641390196731749,1739502686.6941173,46.9599552154541,3.3909890077633515,1739502686.69412,46.9599552154541,1.1886986251410934 +1739502686.7159493,46.979955196380615,39.66109905293996,1739502686.7159548,46.979955196380615,0.25023723084488836,1739502686.7159617,46.979955196380615,73.5139753415866,1739502686.7159677,46.979955196380615,35.4356532485243,1739502686.7159703,46.979955196380615,-0.101,1739502686.7159734,46.979955196380615,-3.0586590155647815,1739502686.7159762,46.979955196380615,-0.7025499435991941,1739502686.715979,46.979955196380615,-0.2991301816967681,1739502686.7159815,46.979955196380615,1.4251125271084109,1739502686.7159843,46.979955196380615,0.0,1739502686.7159872,46.979955196380615,0.23641390196731749,1739502686.7159898,46.979955196380615,3.3909890077633515,1739502686.7159922,46.979955196380615,1.1886986251410934 +1739502686.7363565,46.99995517730713,39.66109905293996,1739502686.7363608,46.99995517730713,0.25023723084488836,1739502686.736365,46.99995517730713,73.5139753415866,1739502686.7363694,46.99995517730713,35.4356532485243,1739502686.736372,46.99995517730713,-0.101,1739502686.736375,46.99995517730713,-3.0586590155647815,1739502686.7363777,46.99995517730713,-0.7025499435991941,1739502686.7363799,46.99995517730713,-0.2991301816967681,1739502686.7363825,46.99995517730713,1.4251125271084109,1739502686.736385,46.99995517730713,0.0,1739502686.7363875,46.99995517730713,0.23641390196731749,1739502686.73639,46.99995517730713,3.3909890077633515,1739502686.7363927,46.99995517730713,1.1886986251410934 +1739502686.7559667,47.01995515823364,39.66109905293996,1739502686.7559705,47.01995515823364,0.25023723084488836,1739502686.755975,47.01995515823364,73.5139753415866,1739502686.7559793,47.01995515823364,35.4356532485243,1739502686.755982,47.01995515823364,-0.101,1739502686.7559848,47.01995515823364,-3.0586590155647815,1739502686.7559874,47.01995515823364,-0.7025499435991941,1739502686.7559912,47.01995515823364,-0.2991301816967681,1739502686.7559953,47.01995515823364,1.4251125271084109,1739502686.7559996,47.01995515823364,0.0,1739502686.7560036,47.01995515823364,0.23641390196731749,1739502686.7560077,47.01995515823364,3.3909890077633515,1739502686.7560117,47.01995515823364,1.1886986251410934 +1739502686.77567,47.039955139160156,39.53288483600638,1739502686.775674,47.039955139160156,0.21854679410644007,1739502686.7756784,47.039955139160156,73.73111337486895,1739502686.775683,47.039955139160156,35.16626562258922,1739502686.7756853,47.039955139160156,-0.1,1739502686.7756884,47.039955139160156,-3.0687712100848694,1739502686.7756908,47.039955139160156,-0.702771624713669,1739502686.7756934,47.039955139160156,-0.2807432648521371,1739502686.7756958,47.039955139160156,1.424859813091234,1739502686.775699,47.039955139160156,0.0,1739502686.7757015,47.039955139160156,0.1980434680216233,1739502686.7757044,47.039955139160156,3.3756267670446873,1739502686.7757072,47.039955139160156,1.2148255765998208 +1739502686.7959871,47.05995512008667,39.53288483600638,1739502686.7959921,47.05995512008667,0.21854679410644007,1739502686.7959979,47.05995512008667,73.73111337486895,1739502686.7960045,47.05995512008667,35.16626562258922,1739502686.7960083,47.05995512008667,-0.1,1739502686.7960134,47.05995512008667,-3.0687712100848694,1739502686.7960174,47.05995512008667,-0.702771624713669,1739502686.7960198,47.05995512008667,-0.2807432648521371,1739502686.7960215,47.05995512008667,1.424859813091234,1739502686.7960243,47.05995512008667,0.0,1739502686.796027,47.05995512008667,0.21003423649141317,1739502686.7960293,47.05995512008667,3.3756267670446873,1739502686.7960317,47.05995512008667,1.2148255765998208 +1739502686.8165905,47.079955101013184,39.53288483600638,1739502686.8165944,47.079955101013184,0.21854679410644007,1739502686.816599,47.079955101013184,73.73111337486895,1739502686.8166032,47.079955101013184,35.16626562258922,1739502686.8166053,47.079955101013184,-0.1,1739502686.8166084,47.079955101013184,-3.0687712100848694,1739502686.8166108,47.079955101013184,-0.702771624713669,1739502686.8166132,47.079955101013184,-0.2807432648521371,1739502686.8166156,47.079955101013184,1.424859813091234,1739502686.8166182,47.079955101013184,0.0,1739502686.8166223,47.079955101013184,0.21003423649141317,1739502686.816626,47.079955101013184,3.3756267670446873,1739502686.8166308,47.079955101013184,1.2148255765998208 +1739502686.8356416,47.0999550819397,39.53288483600638,1739502686.835645,47.0999550819397,0.21854679410644007,1739502686.8356488,47.0999550819397,73.73111337486895,1739502686.8356528,47.0999550819397,35.16626562258922,1739502686.8356552,47.0999550819397,-0.1,1739502686.835658,47.0999550819397,-3.0687712100848694,1739502686.8356602,47.0999550819397,-0.702771624713669,1739502686.8356626,47.0999550819397,-0.2807432648521371,1739502686.8356655,47.0999550819397,1.424859813091234,1739502686.8356686,47.0999550819397,0.0,1739502686.8356707,47.0999550819397,0.21003423649141317,1739502686.835673,47.0999550819397,3.3756267670446873,1739502686.8356757,47.0999550819397,1.2148255765998208 +1739502686.8560717,47.11995506286621,39.53288483600638,1739502686.8560753,47.11995506286621,0.21854679410644007,1739502686.8560793,47.11995506286621,73.73111337486895,1739502686.8560834,47.11995506286621,35.16626562258922,1739502686.856086,47.11995506286621,-0.1,1739502686.8560889,47.11995506286621,-3.0687712100848694,1739502686.8560915,47.11995506286621,-0.702771624713669,1739502686.8560936,47.11995506286621,-0.2807432648521371,1739502686.856096,47.11995506286621,1.424859813091234,1739502686.856099,47.11995506286621,0.0,1739502686.8561013,47.11995506286621,0.21003423649141317,1739502686.856104,47.11995506286621,3.3756267670446873,1739502686.8561063,47.11995506286621,1.2148255765998208 +1739502686.8759499,47.139955043792725,39.53288483600638,1739502686.8759546,47.139955043792725,0.21854679410644007,1739502686.8759606,47.139955043792725,73.73111337486895,1739502686.8759673,47.139955043792725,35.16626562258922,1739502686.8759708,47.139955043792725,-0.1,1739502686.8759751,47.139955043792725,-3.0687712100848694,1739502686.8759778,47.139955043792725,-0.702771624713669,1739502686.8759804,47.139955043792725,-0.2807432648521371,1739502686.8759825,47.139955043792725,1.424859813091234,1739502686.8759851,47.139955043792725,0.0,1739502686.8759875,47.139955043792725,0.21003423649141317,1739502686.87599,47.139955043792725,3.3756267670446873,1739502686.8759923,47.139955043792725,1.2148255765998208 +1739502686.8961759,47.15995502471924,39.401591398822156,1739502686.8961806,47.15995502471924,0.18817965227345912,1739502686.896187,47.15995502471924,73.74154718322245,1739502686.8961937,47.15995502471924,35.1102721358609,1739502686.8961968,47.15995502471924,-0.1,1739502686.8962002,47.15995502471924,-3.0745392361111556,1739502686.8962028,47.15995502471924,-0.652883690804454,1739502686.896205,47.15995502471924,-0.27032339136431327,1739502686.8962073,47.15995502471924,1.4828764950819822,1739502686.8962104,47.15995502471924,0.0,1739502686.896213,47.15995502471924,0.261287841298309,1739502686.8962152,47.15995502471924,3.3610338369876334,1739502686.896218,47.15995502471924,1.2376054157872356 +1739502686.9141424,47.17995500564575,39.401591398822156,1739502686.914161,47.17995500564575,0.18817965227345912,1739502686.9141726,47.17995500564575,73.74154718322245,1739502686.914178,47.17995500564575,35.1102721358609,1739502686.9141796,47.17995500564575,-0.1,1739502686.9141817,47.17995500564575,-3.0745392361111556,1739502686.914185,47.17995500564575,-0.652883690804454,1739502686.9141877,47.17995500564575,-0.27032339136431327,1739502686.9141905,47.17995500564575,1.4828764950819822,1739502686.9142027,47.17995500564575,0.0,1739502686.914213,47.17995500564575,0.24527107929474656,1739502686.9142165,47.17995500564575,3.3610338369876334,1739502686.91422,47.17995500564575,1.2376054157872356 +1739502686.933847,47.199954986572266,39.401591398822156,1739502686.9338493,47.199954986572266,0.18817965227345912,1739502686.9338524,47.199954986572266,73.74154718322245,1739502686.933855,47.199954986572266,35.1102721358609,1739502686.9338562,47.199954986572266,-0.1,1739502686.9338582,47.199954986572266,-3.0745392361111556,1739502686.9338593,47.199954986572266,-0.652883690804454,1739502686.9338608,47.199954986572266,-0.27032339136431327,1739502686.9338622,47.199954986572266,1.4828764950819822,1739502686.9338636,47.199954986572266,0.0,1739502686.9338646,47.199954986572266,0.24527107929474656,1739502686.9338663,47.199954986572266,3.3610338369876334,1739502686.9338677,47.199954986572266,1.2376054157872356 +1739502686.9542785,47.21995496749878,39.401591398822156,1739502686.9542809,47.21995496749878,0.18817965227345912,1739502686.9542835,47.21995496749878,73.74154718322245,1739502686.9542866,47.21995496749878,35.1102721358609,1739502686.9542878,47.21995496749878,-0.1,1739502686.9542897,47.21995496749878,-3.0745392361111556,1739502686.9542909,47.21995496749878,-0.652883690804454,1739502686.9542925,47.21995496749878,-0.27032339136431327,1739502686.9542937,47.21995496749878,1.4828764950819822,1739502686.9542954,47.21995496749878,0.0,1739502686.9542966,47.21995496749878,0.24527107929474656,1739502686.9542978,47.21995496749878,3.3610338369876334,1739502686.9542992,47.21995496749878,1.2376054157872356 +1739502686.9744837,47.23995494842529,39.401591398822156,1739502686.9744859,47.23995494842529,0.18817965227345912,1739502686.9744885,47.23995494842529,73.74154718322245,1739502686.9744914,47.23995494842529,35.1102721358609,1739502686.9744928,47.23995494842529,-0.1,1739502686.974494,47.23995494842529,-3.0745392361111556,1739502686.9744954,47.23995494842529,-0.652883690804454,1739502686.9744968,47.23995494842529,-0.27032339136431327,1739502686.974498,47.23995494842529,1.4828764950819822,1739502686.9744997,47.23995494842529,0.0,1739502686.9745011,47.23995494842529,0.24527107929474656,1739502686.9745023,47.23995494842529,3.3610338369876334,1739502686.9745038,47.23995494842529,1.2376054157872356 +1739502686.9996712,47.25995492935181,39.267227254878364,1739502686.9996798,47.25995492935181,0.15911467558427184,1739502686.9996898,47.25995492935181,73.97073769150855,1739502686.9997,47.25995492935181,34.82742162325282,1739502686.9997046,47.25995492935181,-0.09967881729275911,1739502686.999711,47.25995492935181,-3.0833691605561975,1739502686.999716,47.25995492935181,-0.6527079951227887,1739502686.9997213,47.25995492935181,-0.25284196192085046,1739502686.9997258,47.25995492935181,1.4830849377279316,1739502686.9997318,47.25995492935181,0.0,1739502686.9997363,47.25995492935181,0.20654780115015864,1739502686.9997416,47.25995492935181,3.3471118171883303,1739502686.9997466,47.25995492935181,1.2644361042235341 +1739502687.018727,47.27995491027832,39.267227254878364,1739502687.018736,47.27995491027832,0.15911467558427184,1739502687.0187469,47.27995491027832,73.97073769150855,1739502687.018757,47.27995491027832,34.82742162325282,1739502687.0187624,47.27995491027832,-0.09967881729275911,1739502687.0187683,47.27995491027832,-3.0833691605561975,1739502687.0187736,47.27995491027832,-0.6527079951227887,1739502687.0187786,47.27995491027832,-0.25284196192085046,1739502687.0187833,47.27995491027832,1.4830849377279316,1739502687.018789,47.27995491027832,0.0,1739502687.018794,47.27995491027832,0.21864883350439746,1739502687.0187993,47.27995491027832,3.3471118171883303,1739502687.0188043,47.27995491027832,1.2644361042235341 +1739502687.039882,47.299954891204834,39.267227254878364,1739502687.0398912,47.299954891204834,0.15911467558427184,1739502687.0399015,47.299954891204834,73.97073769150855,1739502687.0399108,47.299954891204834,34.82742162325282,1739502687.0399158,47.299954891204834,-0.09967881729275911,1739502687.0399218,47.299954891204834,-3.0833691605561975,1739502687.0399265,47.299954891204834,-0.6527079951227887,1739502687.0399313,47.299954891204834,-0.25284196192085046,1739502687.039936,47.299954891204834,1.4830849377279316,1739502687.0399415,47.299954891204834,0.0,1739502687.0399463,47.299954891204834,0.21864883350439746,1739502687.0399513,47.299954891204834,3.3471118171883303,1739502687.0399566,47.299954891204834,1.2644361042235341 +1739502687.0775151,47.31995487213135,39.267227254878364,1739502687.0775232,47.31995487213135,0.15911467558427184,1739502687.0775342,47.31995487213135,73.97073769150855,1739502687.0775447,47.31995487213135,34.82742162325282,1739502687.0775495,47.31995487213135,-0.09967881729275911,1739502687.0775557,47.31995487213135,-3.0833691605561975,1739502687.0775611,47.31995487213135,-0.6527079951227887,1739502687.077566,47.31995487213135,-0.25284196192085046,1739502687.0775707,47.31995487213135,1.4830849377279316,1739502687.0775762,47.31995487213135,0.0,1739502687.0775812,47.31995487213135,0.21864883350439746,1739502687.0775862,47.31995487213135,3.3471118171883303,1739502687.0775907,47.31995487213135,1.2644361042235341 +1739502687.1000447,47.34995484352112,39.267227254878364,1739502687.1000576,47.34995484352112,0.15911467558427184,1739502687.1000745,47.34995484352112,73.97073769150855,1739502687.1000938,47.34995484352112,34.82742162325282,1739502687.100105,47.34995484352112,-0.09967881729275911,1739502687.100119,47.34995484352112,-3.0833691605561975,1739502687.1001315,47.34995484352112,-0.6527079951227887,1739502687.1001441,47.34995484352112,-0.25284196192085046,1739502687.1001568,47.34995484352112,1.4830849377279316,1739502687.1001694,47.34995484352112,0.0,1739502687.1001823,47.34995484352112,0.21864883350439746,1739502687.1001952,47.34995484352112,3.3471118171883303,1739502687.100208,47.34995484352112,1.2644361042235341 +1739502687.1379764,47.389954805374146,39.129742418660214,1739502687.137982,47.389954805374146,0.13133200631206066,1739502687.1379893,47.389954805374146,74.13267647383114,1739502687.1379962,47.389954805374146,34.61804461436948,1739502687.1379995,47.389954805374146,-0.099,1739502687.138004,47.389954805374146,-3.0905847576828083,1739502687.1380076,47.389954805374146,-0.636009062420492,1739502687.138011,47.389954805374146,-0.23883348117874756,1739502687.1380143,47.389954805374146,1.5030306181757496,1739502687.1380181,47.389954805374146,0.0,1739502687.1380217,47.389954805374146,0.21315809256568283,1739502687.1380253,47.389954805374146,3.333855372020498,1739502687.1380289,47.389954805374146,1.2881566679417145 +1739502687.1590087,47.40995478630066,39.129742418660214,1739502687.1590142,47.40995478630066,0.13133200631206066,1739502687.159021,47.40995478630066,74.13267647383114,1739502687.1590261,47.40995478630066,34.61804461436948,1739502687.159029,47.40995478630066,-0.099,1739502687.1590326,47.40995478630066,-3.0905847576828083,1739502687.1590354,47.40995478630066,-0.636009062420492,1739502687.1590383,47.40995478630066,-0.23883348117874756,1739502687.1590407,47.40995478630066,1.5030306181757496,1739502687.1590443,47.40995478630066,0.0,1739502687.159047,47.40995478630066,0.2148739502340351,1739502687.15905,47.40995478630066,3.333855372020498,1739502687.159053,47.40995478630066,1.2881566679417145 +1739502687.179348,47.42995476722717,39.129742418660214,1739502687.179352,47.42995476722717,0.13133200631206066,1739502687.1793573,47.42995476722717,74.13267647383114,1739502687.1793618,47.42995476722717,34.61804461436948,1739502687.1793642,47.42995476722717,-0.099,1739502687.1793668,47.42995476722717,-3.0905847576828083,1739502687.1793692,47.42995476722717,-0.636009062420492,1739502687.1793718,47.42995476722717,-0.23883348117874756,1739502687.179374,47.42995476722717,1.5030306181757496,1739502687.1793766,47.42995476722717,0.0,1739502687.179379,47.42995476722717,0.2148739502340351,1739502687.1793811,47.42995476722717,3.333855372020498,1739502687.1793835,47.42995476722717,1.2881566679417145 +1739502687.1979082,47.45995473861694,39.129742418660214,1739502687.1979113,47.45995473861694,0.13133200631206066,1739502687.197915,47.45995473861694,74.13267647383114,1739502687.1979184,47.45995473861694,34.61804461436948,1739502687.19792,47.45995473861694,-0.099,1739502687.1979222,47.45995473861694,-3.0905847576828083,1739502687.1979241,47.45995473861694,-0.636009062420492,1739502687.1979256,47.45995473861694,-0.23883348117874756,1739502687.1979272,47.45995473861694,1.5030306181757496,1739502687.1979291,47.45995473861694,0.0,1739502687.1979306,47.45995473861694,0.2148739502340351,1739502687.1979322,47.45995473861694,3.333855372020498,1739502687.1979342,47.45995473861694,1.2881566679417145 +1739502687.2180886,47.47995471954346,38.989339256407206,1739502687.2180917,47.47995471954346,0.10485143839474809,1739502687.2180948,47.47995471954346,74.28290930318713,1739502687.2180974,47.47995471954346,34.420671922262194,1739502687.2180986,47.47995471954346,-0.09822603323951015,1739502687.2181005,47.47995471954346,-3.0971718481653183,1739502687.218102,47.47995471954346,-0.6162682931085965,1739502687.2181036,47.47995471954346,-0.2258775054545868,1739502687.2181048,47.47995471954346,1.526955826286195,1739502687.2181063,47.47995471954346,0.0,1739502687.2181077,47.47995471954346,0.21538833148427747,1739502687.218109,47.47995471954346,3.3211817857354102,1739502687.2181106,47.47995471954346,1.3117282390480105 +1739502687.2378364,47.49995470046997,38.989339256407206,1739502687.2378385,47.49995470046997,0.10485143839474809,1739502687.2378414,47.49995470046997,74.28290930318713,1739502687.2378442,47.49995470046997,34.420671922262194,1739502687.2378452,47.49995470046997,-0.09822603323951015,1739502687.237847,47.49995470046997,-3.0971718481653183,1739502687.2378483,47.49995470046997,-0.6162682931085965,1739502687.2378497,47.49995470046997,-0.2258775054545868,1739502687.237851,47.49995470046997,1.526955826286195,1739502687.2378523,47.49995470046997,0.0,1739502687.2378535,47.49995470046997,0.21522758723818458,1739502687.237855,47.49995470046997,3.3211817857354102,1739502687.2378561,47.49995470046997,1.3117282390480105 +1739502687.2576604,47.519954681396484,38.989339256407206,1739502687.2576632,47.519954681396484,0.10485143839474809,1739502687.257666,47.519954681396484,74.28290930318713,1739502687.257669,47.519954681396484,34.420671922262194,1739502687.2576702,47.519954681396484,-0.09822603323951015,1739502687.2576718,47.519954681396484,-3.0971718481653183,1739502687.2576733,47.519954681396484,-0.6162682931085965,1739502687.2576745,47.519954681396484,-0.2258775054545868,1739502687.2576761,47.519954681396484,1.526955826286195,1739502687.2576776,47.519954681396484,0.0,1739502687.257679,47.519954681396484,0.21522758723818458,1739502687.2576807,47.519954681396484,3.3211817857354102,1739502687.2576818,47.519954681396484,1.3117282390480105 +1739502687.277252,47.539954662323,38.989339256407206,1739502687.277254,47.539954662323,0.10485143839474809,1739502687.277257,47.539954662323,74.28290930318713,1739502687.2772596,47.539954662323,34.420671922262194,1739502687.277261,47.539954662323,-0.09822603323951015,1739502687.277263,47.539954662323,-3.0971718481653183,1739502687.277264,47.539954662323,-0.6162682931085965,1739502687.2772653,47.539954662323,-0.2258775054545868,1739502687.2772667,47.539954662323,1.526955826286195,1739502687.2772682,47.539954662323,0.0,1739502687.2772696,47.539954662323,0.21522758723818458,1739502687.277271,47.539954662323,3.3211817857354102,1739502687.2772725,47.539954662323,1.3117282390480105 +1739502687.2977085,47.55995464324951,38.989339256407206,1739502687.2977107,47.55995464324951,0.10485143839474809,1739502687.2977135,47.55995464324951,74.28290930318713,1739502687.297716,47.55995464324951,34.420671922262194,1739502687.2977176,47.55995464324951,-0.09822603323951015,1739502687.297719,47.55995464324951,-3.0971718481653183,1739502687.2977207,47.55995464324951,-0.6162682931085965,1739502687.2977219,47.55995464324951,-0.2258775054545868,1739502687.297723,47.55995464324951,1.526955826286195,1739502687.2977247,47.55995464324951,0.0,1739502687.2977257,47.55995464324951,0.21522758723818458,1739502687.2977273,47.55995464324951,3.3211817857354102,1739502687.2977285,47.55995464324951,1.3117282390480105 +1739502687.317852,47.579954624176025,38.989339256407206,1739502687.3178546,47.579954624176025,0.10485143839474809,1739502687.3178577,47.579954624176025,74.28290930318713,1739502687.3178604,47.579954624176025,34.420671922262194,1739502687.3178618,47.579954624176025,-0.09822603323951015,1739502687.3178637,47.579954624176025,-3.0971718481653183,1739502687.317865,47.579954624176025,-0.6162682931085965,1739502687.3178668,47.579954624176025,-0.2258775054545868,1739502687.317868,47.579954624176025,1.526955826286195,1739502687.3178697,47.579954624176025,0.0,1739502687.317871,47.579954624176025,0.21522758723818458,1739502687.3178723,47.579954624176025,3.3211817857354102,1739502687.317874,47.579954624176025,1.3117282390480105 +1739502687.3376038,47.59995460510254,38.84606866862808,1739502687.3376062,47.59995460510254,0.07964750689061706,1739502687.337609,47.59995460510254,74.40789819235826,1739502687.3376117,47.59995460510254,34.24850796613658,1739502687.337613,47.59995460510254,-0.098,1739502687.3376148,47.59995460510254,-3.102972353055895,1739502687.3376164,47.59995460510254,-0.5925026508903793,1739502687.3376176,47.59995460510254,-0.21458881322433912,1739502687.3376188,47.59995460510254,1.5562648310257425,1739502687.3376205,47.59995460510254,0.0,1739502687.3376217,47.59995460510254,0.2235490331900613,1739502687.3376231,47.59995460510254,3.3093487336402325,1739502687.3376245,47.59995460510254,1.335316251400633 +1739502687.3588197,47.61995458602905,38.84606866862808,1739502687.3588226,47.61995458602905,0.07964750689061706,1739502687.358826,47.61995458602905,74.40789819235826,1739502687.3588293,47.61995458602905,34.24850796613658,1739502687.358831,47.61995458602905,-0.098,1739502687.3588326,47.61995458602905,-3.102972353055895,1739502687.3588345,47.61995458602905,-0.5925026508903793,1739502687.358836,47.61995458602905,-0.21458881322433912,1739502687.3588376,47.61995458602905,1.5562648310257425,1739502687.3588395,47.61995458602905,0.0,1739502687.3588412,47.61995458602905,0.2209485796251096,1739502687.3588426,47.61995458602905,3.3093487336402325,1739502687.358844,47.61995458602905,1.335316251400633 +1739502687.39165,47.639954566955566,38.84606866862808,1739502687.391659,47.639954566955566,0.07964750689061706,1739502687.3916695,47.639954566955566,74.40789819235826,1739502687.3916795,47.639954566955566,34.24850796613658,1739502687.3916848,47.639954566955566,-0.098,1739502687.391691,47.639954566955566,-3.102972353055895,1739502687.3916965,47.639954566955566,-0.5925026508903793,1739502687.3917012,47.639954566955566,-0.21458881322433912,1739502687.3917058,47.639954566955566,1.5562648310257425,1739502687.3917112,47.639954566955566,0.0,1739502687.391716,47.639954566955566,0.2209485796251096,1739502687.391721,47.639954566955566,3.3093487336402325,1739502687.391726,47.639954566955566,1.335316251400633 +1739502687.406225,47.65995454788208,38.84606866862808,1739502687.406234,47.65995454788208,0.07964750689061706,1739502687.4062443,47.65995454788208,74.40789819235826,1739502687.4062543,47.65995454788208,34.24850796613658,1739502687.406259,47.65995454788208,-0.098,1739502687.4062648,47.65995454788208,-3.102972353055895,1739502687.4062698,47.65995454788208,-0.5925026508903793,1739502687.4062746,47.65995454788208,-0.21458881322433912,1739502687.4062793,47.65995454788208,1.5562648310257425,1739502687.406285,47.65995454788208,0.0,1739502687.4062898,47.65995454788208,0.2209485796251096,1739502687.4062953,47.65995454788208,3.3093487336402325,1739502687.4063008,47.65995454788208,1.335316251400633 +1739502687.42858,47.68995451927185,38.84606866862808,1739502687.428585,47.68995451927185,0.07964750689061706,1739502687.428591,47.68995451927185,74.40789819235826,1739502687.4285967,47.68995451927185,34.24850796613658,1739502687.4285996,47.68995451927185,-0.098,1739502687.428603,47.68995451927185,-3.102972353055895,1739502687.4286058,47.68995451927185,-0.5925026508903793,1739502687.4286084,47.68995451927185,-0.21458881322433912,1739502687.428611,47.68995451927185,1.5562648310257425,1739502687.4286141,47.68995451927185,0.0,1739502687.428617,47.68995451927185,0.2209485796251096,1739502687.4286199,47.68995451927185,3.3093487336402325,1739502687.4286222,47.68995451927185,1.335316251400633 +1739502687.447721,47.709954500198364,38.69992711597581,1739502687.447724,47.709954500198364,0.05568334517649198,1739502687.4477274,47.709954500198364,74.55764491202933,1739502687.44773,47.709954500198364,34.05038760730825,1739502687.4477317,47.709954500198364,-0.09709696809058138,1739502687.4477334,47.709954500198364,-3.1087452368836637,1739502687.447735,47.709954500198364,-0.5733820365728758,1739502687.4477367,47.709954500198364,-0.203166502993384,1739502687.4477382,47.709954500198364,1.580253224101372,1739502687.4477398,47.709954500198364,0.0,1739502687.4477415,47.709954500198364,0.22065801613876088,1739502687.447743,47.709954500198364,3.2980079453194655,1739502687.4477446,47.709954500198364,1.3595044068135933 +1739502687.467158,47.72995448112488,38.69992711597581,1739502687.4671614,47.72995448112488,0.05568334517649198,1739502687.4671655,47.72995448112488,74.55764491202933,1739502687.4671705,47.72995448112488,34.05038760730825,1739502687.4671733,47.72995448112488,-0.09709696809058138,1739502687.467177,47.72995448112488,-3.1087452368836637,1739502687.46718,47.72995448112488,-0.5733820365728758,1739502687.4671834,47.72995448112488,-0.203166502993384,1739502687.4671865,47.72995448112488,1.580253224101372,1739502687.4671898,47.72995448112488,0.0,1739502687.4671931,47.72995448112488,0.22074881728777873,1739502687.4671965,47.72995448112488,3.2980079453194655,1739502687.4671998,47.72995448112488,1.3595044068135933 +1739502687.486409,47.74995446205139,38.69992711597581,1739502687.4864113,47.74995446205139,0.05568334517649198,1739502687.4864142,47.74995446205139,74.55764491202933,1739502687.4864166,47.74995446205139,34.05038760730825,1739502687.486418,47.74995446205139,-0.09709696809058138,1739502687.4864197,47.74995446205139,-3.1087452368836637,1739502687.4864213,47.74995446205139,-0.5733820365728758,1739502687.4864225,47.74995446205139,-0.203166502993384,1739502687.4864237,47.74995446205139,1.580253224101372,1739502687.4864252,47.74995446205139,0.0,1739502687.4864264,47.74995446205139,0.22074881728777873,1739502687.486428,47.74995446205139,3.2980079453194655,1739502687.4864292,47.74995446205139,1.3595044068135933 +1739502687.5066402,47.769954442977905,38.69992711597581,1739502687.5066423,47.769954442977905,0.05568334517649198,1739502687.5066452,47.769954442977905,74.55764491202933,1739502687.5066478,47.769954442977905,34.05038760730825,1739502687.506649,47.769954442977905,-0.09709696809058138,1739502687.506651,47.769954442977905,-3.1087452368836637,1739502687.506652,47.769954442977905,-0.5733820365728758,1739502687.5066535,47.769954442977905,-0.203166502993384,1739502687.5066547,47.769954442977905,1.580253224101372,1739502687.5066564,47.769954442977905,0.0,1739502687.5066578,47.769954442977905,0.22074881728777873,1739502687.5066593,47.769954442977905,3.2980079453194655,1739502687.5066607,47.769954442977905,1.3595044068135933 +1739502687.526589,47.78995442390442,38.69992711597581,1739502687.5265913,47.78995442390442,0.05568334517649198,1739502687.5265942,47.78995442390442,74.55764491202933,1739502687.5265965,47.78995442390442,34.05038760730825,1739502687.526598,47.78995442390442,-0.09709696809058138,1739502687.5266,47.78995442390442,-3.1087452368836637,1739502687.5266013,47.78995442390442,-0.5733820365728758,1739502687.5266027,47.78995442390442,-0.203166502993384,1739502687.5266037,47.78995442390442,1.580253224101372,1739502687.5266054,47.78995442390442,0.0,1739502687.5266068,47.78995442390442,0.22074881728777873,1739502687.5266082,47.78995442390442,3.2980079453194655,1739502687.5266097,47.78995442390442,1.3595044068135933 +1739502687.5469692,47.80995440483093,38.55089770430696,1739502687.546971,47.80995440483093,0.0329439903745099,1739502687.546974,47.80995440483093,74.73148258210695,1739502687.5469766,47.80995440483093,33.82821232246097,1739502687.546978,47.80995440483093,-0.09629682231525385,1739502687.5469797,47.80995440483093,-3.114233523327534,1739502687.5469809,47.80995440483093,-0.5572575835853176,1739502687.546982,47.80995440483093,-0.19148014493250068,1739502687.5469837,47.80995440483093,1.6007698423622727,1739502687.5469851,47.80995440483093,0.0,1739502687.5469866,47.80995440483093,0.2154342360962343,1739502687.546988,47.80995440483093,3.2871787700477575,1739502687.5469892,47.80995440483093,1.3836747985547704 +1739502687.5666654,47.829954385757446,38.55089770430696,1739502687.566668,47.829954385757446,0.0329439903745099,1739502687.5666711,47.829954385757446,74.73148258210695,1739502687.566674,47.829954385757446,33.82821232246097,1739502687.5666754,47.829954385757446,-0.09629682231525385,1739502687.566677,47.829954385757446,-3.114233523327534,1739502687.5666785,47.829954385757446,-0.5572575835853176,1739502687.56668,47.829954385757446,-0.19148014493250068,1739502687.5666814,47.829954385757446,1.6007698423622727,1739502687.5666828,47.829954385757446,0.0,1739502687.5666845,47.829954385757446,0.21709504380750233,1739502687.5666857,47.829954385757446,3.2871787700477575,1739502687.5666873,47.829954385757446,1.3836747985547704 +1739502687.5865362,47.84995436668396,38.55089770430696,1739502687.5865386,47.84995436668396,0.0329439903745099,1739502687.5865414,47.84995436668396,74.73148258210695,1739502687.5865443,47.84995436668396,33.82821232246097,1739502687.5865457,47.84995436668396,-0.09629682231525385,1739502687.5865476,47.84995436668396,-3.114233523327534,1739502687.586549,47.84995436668396,-0.5572575835853176,1739502687.5865505,47.84995436668396,-0.19148014493250068,1739502687.586552,47.84995436668396,1.6007698423622727,1739502687.5865533,47.84995436668396,0.0,1739502687.5865548,47.84995436668396,0.21709504380750233,1739502687.5865564,47.84995436668396,3.2871787700477575,1739502687.5865576,47.84995436668396,1.3836747985547704 +1739502687.6069553,47.869954347610474,38.55089770430696,1739502687.6069577,47.869954347610474,0.0329439903745099,1739502687.6069605,47.869954347610474,74.73148258210695,1739502687.6069634,47.869954347610474,33.82821232246097,1739502687.606965,47.869954347610474,-0.09629682231525385,1739502687.6069667,47.869954347610474,-3.114233523327534,1739502687.6069682,47.869954347610474,-0.5572575835853176,1739502687.6069698,47.869954347610474,-0.19148014493250068,1739502687.606971,47.869954347610474,1.6007698423622727,1739502687.606973,47.869954347610474,0.0,1739502687.6069744,47.869954347610474,0.21709504380750233,1739502687.6069758,47.869954347610474,3.2871787700477575,1739502687.6069775,47.869954347610474,1.3836747985547704 +1739502687.6264892,47.88995432853699,38.55089770430696,1739502687.6264913,47.88995432853699,0.0329439903745099,1739502687.6264946,47.88995432853699,74.73148258210695,1739502687.6264977,47.88995432853699,33.82821232246097,1739502687.6264994,47.88995432853699,-0.09629682231525385,1739502687.6265013,47.88995432853699,-3.114233523327534,1739502687.6265028,47.88995432853699,-0.5572575835853176,1739502687.6265042,47.88995432853699,-0.19148014493250068,1739502687.6265054,47.88995432853699,1.6007698423622727,1739502687.6265073,47.88995432853699,0.0,1739502687.626509,47.88995432853699,0.21709504380750233,1739502687.6265106,47.88995432853699,3.2871787700477575,1739502687.626512,47.88995432853699,1.3836747985547704 +1739502687.6465113,47.9099543094635,38.55089770430696,1739502687.646514,47.9099543094635,0.0329439903745099,1739502687.646517,47.9099543094635,74.73148258210695,1739502687.64652,47.9099543094635,33.82821232246097,1739502687.6465213,47.9099543094635,-0.09629682231525385,1739502687.6465232,47.9099543094635,-3.114233523327534,1739502687.6465247,47.9099543094635,-0.5572575835853176,1739502687.646526,47.9099543094635,-0.19148014493250068,1739502687.6465278,47.9099543094635,1.6007698423622727,1739502687.6465294,47.9099543094635,0.0,1739502687.6465309,47.9099543094635,0.21709504380750233,1739502687.6465323,47.9099543094635,3.2871787700477575,1739502687.6465344,47.9099543094635,1.3836747985547704 +1739502687.6666281,47.929954290390015,38.39902545714323,1739502687.6666305,47.929954290390015,0.011407479089678318,1739502687.6666334,47.929954290390015,74.7451715041948,1739502687.6666365,47.929954290390015,33.76701506602912,1739502687.666638,47.929954290390015,-0.096,1739502687.6666396,47.929954290390015,-3.118408717096844,1739502687.6666412,47.929954290390015,-0.5185158807169912,1739502687.6666427,47.929954290390015,-0.18526705134343224,1739502687.6666439,47.929954290390015,1.651159927505958,1739502687.6666458,47.929954290390015,0.0,1739502687.666647,47.929954290390015,0.25583732406553944,1739502687.6666489,47.929954290390015,3.2769233003450022,1739502687.66665,47.929954290390015,1.4074295739590037 +1739502687.6865206,47.94995427131653,38.39902545714323,1739502687.686523,47.94995427131653,0.011407479089678318,1739502687.686526,47.94995427131653,74.7451715041948,1739502687.686529,47.94995427131653,33.76701506602912,1739502687.6865306,47.94995427131653,-0.096,1739502687.6865323,47.94995427131653,-3.118408717096844,1739502687.6865342,47.94995427131653,-0.5185158807169912,1739502687.6865356,47.94995427131653,-0.18526705134343224,1739502687.686537,47.94995427131653,1.651159927505958,1739502687.6865387,47.94995427131653,0.0,1739502687.6865401,47.94995427131653,0.24373035354695438,1739502687.6865416,47.94995427131653,3.2769233003450022,1739502687.686543,47.94995427131653,1.4074295739590037 +1739502687.7065923,47.96995425224304,38.39902545714323,1739502687.7065947,47.96995425224304,0.011407479089678318,1739502687.7065978,47.96995425224304,74.7451715041948,1739502687.706601,47.96995425224304,33.76701506602912,1739502687.7066026,47.96995425224304,-0.096,1739502687.7066045,47.96995425224304,-3.118408717096844,1739502687.7066061,47.96995425224304,-0.5185158807169912,1739502687.7066073,47.96995425224304,-0.18526705134343224,1739502687.706609,47.96995425224304,1.651159927505958,1739502687.7066107,47.96995425224304,0.0,1739502687.706612,47.96995425224304,0.24373035354695438,1739502687.7066135,47.96995425224304,3.2769233003450022,1739502687.7066152,47.96995425224304,1.4074295739590037 +1739502687.726568,47.989954233169556,38.39902545714323,1739502687.7265706,47.989954233169556,0.011407479089678318,1739502687.7265735,47.989954233169556,74.7451715041948,1739502687.7265766,47.989954233169556,33.76701506602912,1739502687.726578,47.989954233169556,-0.096,1739502687.7265797,47.989954233169556,-3.118408717096844,1739502687.7265813,47.989954233169556,-0.5185158807169912,1739502687.7265828,47.989954233169556,-0.18526705134343224,1739502687.7265844,47.989954233169556,1.651159927505958,1739502687.7265859,47.989954233169556,0.0,1739502687.726587,47.989954233169556,0.24373035354695438,1739502687.7265887,47.989954233169556,3.2769233003450022,1739502687.7265902,47.989954233169556,1.4074295739590037 +1739502687.7537289,48.00995421409607,38.39902545714323,1739502687.7537382,48.00995421409607,0.011407479089678318,1739502687.7537496,48.00995421409607,74.7451715041948,1739502687.75376,48.00995421409607,33.76701506602912,1739502687.753765,48.00995421409607,-0.096,1739502687.7537715,48.00995421409607,-3.118408717096844,1739502687.7537766,48.00995421409607,-0.5185158807169912,1739502687.7537816,48.00995421409607,-0.18526705134343224,1739502687.7537866,48.00995421409607,1.651159927505958,1739502687.7537925,48.00995421409607,0.0,1739502687.753797,48.00995421409607,0.24373035354695438,1739502687.7538025,48.00995421409607,3.2769233003450022,1739502687.753808,48.00995421409607,1.4074295739590037 +1739502687.7744117,48.019954204559326,38.39902545714323,1739502687.7744172,48.019954204559326,0.011407479089678318,1739502687.7744234,48.019954204559326,74.7451715041948,1739502687.774429,48.019954204559326,33.76701506602912,1739502687.774432,48.019954204559326,-0.096,1739502687.774436,48.019954204559326,-3.118408717096844,1739502687.7744389,48.019954204559326,-0.5185158807169912,1739502687.7744415,48.019954204559326,-0.18526705134343224,1739502687.7744443,48.019954204559326,1.651159927505958,1739502687.7744477,48.019954204559326,0.0,1739502687.774451,48.019954204559326,0.24373035354695438,1739502687.7744539,48.019954204559326,3.2769233003450022,1739502687.7744565,48.019954204559326,1.4074295739590037 +1739502687.792605,48.0499541759491,38.24421290988843,1739502687.7926104,48.0499541759491,-0.008956469879717766,1739502687.7926161,48.0499541759491,75.00639260371382,1739502687.7926219,48.0499541759491,33.4524739496682,1739502687.7926245,48.0499541759491,-0.09435562116818198,1739502687.7926278,48.0499541759491,-3.1237723774943364,1739502687.7926304,48.0499541759491,-0.5148503508349451,1739502687.7926333,48.0499541759491,-0.17196575655162394,1739502687.7926362,48.0499541759491,1.6560089345467268,1739502687.7926393,48.0499541759491,0.0,1739502687.7926419,48.0499541759491,0.21200018388531208,1739502687.7926445,48.0499541759491,3.2670489948217805,1739502687.7926474,48.0499541759491,1.4340930661409221 +1739502687.8117602,48.06995415687561,38.24421290988843,1739502687.8117652,48.06995415687561,-0.008956469879717766,1739502687.8117716,48.06995415687561,75.00639260371382,1739502687.811777,48.06995415687561,33.4524739496682,1739502687.8117802,48.06995415687561,-0.09435562116818198,1739502687.8117838,48.06995415687561,-3.1237723774943364,1739502687.8117864,48.06995415687561,-0.5148503508349451,1739502687.8117895,48.06995415687561,-0.17196575655162394,1739502687.8117924,48.06995415687561,1.6560089345467268,1739502687.8117955,48.06995415687561,0.0,1739502687.8117983,48.06995415687561,0.22191586840580468,1739502687.8118014,48.06995415687561,3.2670489948217805,1739502687.8118045,48.06995415687561,1.4340930661409221 +1739502687.8306434,48.089954137802124,38.24421290988843,1739502687.830654,48.089954137802124,-0.008956469879717766,1739502687.8306642,48.089954137802124,75.00639260371382,1739502687.8306744,48.089954137802124,33.4524739496682,1739502687.8306801,48.089954137802124,-0.09435562116818198,1739502687.8306878,48.089954137802124,-3.1237723774943364,1739502687.830694,48.089954137802124,-0.5148503508349451,1739502687.8306994,48.089954137802124,-0.17196575655162394,1739502687.8307056,48.089954137802124,1.6560089345467268,1739502687.8307114,48.089954137802124,0.0,1739502687.830717,48.089954137802124,0.22191586840580468,1739502687.8307233,48.089954137802124,3.2670489948217805,1739502687.8307292,48.089954137802124,1.4340930661409221 +1739502687.8498783,48.10995411872864,38.24421290988843,1739502687.8498852,48.10995411872864,-0.008956469879717766,1739502687.8498917,48.10995411872864,75.00639260371382,1739502687.849898,48.10995411872864,33.4524739496682,1739502687.849901,48.10995411872864,-0.09435562116818198,1739502687.8499055,48.10995411872864,-3.1237723774943364,1739502687.8499088,48.10995411872864,-0.5148503508349451,1739502687.8499122,48.10995411872864,-0.17196575655162394,1739502687.8499155,48.10995411872864,1.6560089345467268,1739502687.8499198,48.10995411872864,0.0,1739502687.8499246,48.10995411872864,0.22191586840580468,1739502687.8499303,48.10995411872864,3.2670489948217805,1739502687.8499346,48.10995411872864,1.4340930661409221 +1739502687.8703375,48.12995409965515,38.24421290988843,1739502687.8703432,48.12995409965515,-0.008956469879717766,1739502687.8703477,48.12995409965515,75.00639260371382,1739502687.8703542,48.12995409965515,33.4524739496682,1739502687.8703573,48.12995409965515,-0.09435562116818198,1739502687.8703635,48.12995409965515,-3.1237723774943364,1739502687.8703682,48.12995409965515,-0.5148503508349451,1739502687.8703713,48.12995409965515,-0.17196575655162394,1739502687.8703752,48.12995409965515,1.6560089345467268,1739502687.870378,48.12995409965515,0.0,1739502687.8703804,48.12995409965515,0.22191586840580468,1739502687.8703823,48.12995409965515,3.2670489948217805,1739502687.8703845,48.12995409965515,1.4340930661409221 +1739502687.8890188,48.149954080581665,38.08638693465914,1739502687.8890224,48.149954080581665,-0.028158611640270337,1739502687.8890274,48.149954080581665,75.02120483440247,1739502687.889034,48.149954080581665,33.38864604427432,1739502687.8890371,48.149954080581665,-0.0937805949934623,1739502687.889041,48.149954080581665,-3.1276247236538133,1739502687.889043,48.149954080581665,-0.47842143119627384,1739502687.889045,48.149954080581665,-0.1662891412707426,1739502687.8890471,48.149954080581665,1.7049803520029334,1739502687.889051,48.149954080581665,0.0,1739502687.889055,48.149954080581665,0.2574973845020969,1739502687.8890579,48.149954080581665,3.2575682094300253,1739502687.8890612,48.149954080581665,1.4586021985712638 +1739502687.9111385,48.16995406150818,38.08638693465914,1739502687.9111423,48.16995406150818,-0.028158611640270337,1739502687.911147,48.16995406150818,75.02120483440247,1739502687.911152,48.16995406150818,33.38864604427432,1739502687.9111543,48.16995406150818,-0.0937805949934623,1739502687.9111571,48.16995406150818,-3.1276247236538133,1739502687.9111598,48.16995406150818,-0.47842143119627384,1739502687.9111621,48.16995406150818,-0.1662891412707426,1739502687.9111645,48.16995406150818,1.7049803520029334,1739502687.9111671,48.16995406150818,0.0,1739502687.9111698,48.16995406150818,0.24637815343166958,1739502687.9111726,48.16995406150818,3.2575682094300253,1739502687.9111753,48.16995406150818,1.4586021985712638 +1739502687.9294443,48.18995404243469,38.08638693465914,1739502687.9294481,48.18995404243469,-0.028158611640270337,1739502687.929453,48.18995404243469,75.02120483440247,1739502687.9294581,48.18995404243469,33.38864604427432,1739502687.929461,48.18995404243469,-0.0937805949934623,1739502687.9294648,48.18995404243469,-3.1276247236538133,1739502687.9294684,48.18995404243469,-0.47842143119627384,1739502687.929472,48.18995404243469,-0.1662891412707426,1739502687.9294758,48.18995404243469,1.7049803520029334,1739502687.9294794,48.18995404243469,0.0,1739502687.9294827,48.18995404243469,0.24637815343166958,1739502687.9294863,48.18995404243469,3.2575682094300253,1739502687.9294903,48.18995404243469,1.4586021985712638 +1739502687.950458,48.209954023361206,38.08638693465914,1739502687.9504633,48.209954023361206,-0.028158611640270337,1739502687.9504695,48.209954023361206,75.02120483440247,1739502687.950474,48.209954023361206,33.38864604427432,1739502687.950477,48.209954023361206,-0.0937805949934623,1739502687.9504802,48.209954023361206,-3.1276247236538133,1739502687.9504828,48.209954023361206,-0.47842143119627384,1739502687.9504855,48.209954023361206,-0.1662891412707426,1739502687.9504879,48.209954023361206,1.7049803520029334,1739502687.9504912,48.209954023361206,0.0,1739502687.9504938,48.209954023361206,0.24637815343166958,1739502687.950497,48.209954023361206,3.2575682094300253,1739502687.9504993,48.209954023361206,1.4586021985712638 +1739502687.9681993,48.22995400428772,38.08638693465914,1739502687.9682016,48.22995400428772,-0.028158611640270337,1739502687.9682045,48.22995400428772,75.02120483440247,1739502687.9682074,48.22995400428772,33.38864604427432,1739502687.9682086,48.22995400428772,-0.0937805949934623,1739502687.9682105,48.22995400428772,-3.1276247236538133,1739502687.9682117,48.22995400428772,-0.47842143119627384,1739502687.968213,48.22995400428772,-0.1662891412707426,1739502687.9682143,48.22995400428772,1.7049803520029334,1739502687.9682157,48.22995400428772,0.0,1739502687.9682174,48.22995400428772,0.24637815343166958,1739502687.9682186,48.22995400428772,3.2575682094300253,1739502687.9682205,48.22995400428772,1.4586021985712638 +1739502687.991099,48.24995398521423,37.92560764998388,1739502687.991103,48.24995398521423,-0.04621573950310687,1739502687.9911082,48.24995398521423,75.28315614709759,1739502687.9911132,48.24995398521423,33.07281127194979,1739502687.991116,48.24995398521423,-0.09014363928991766,1739502687.9911196,48.24995398521423,-3.132540821078317,1739502687.991123,48.24995398521423,-0.474429810860093,1739502687.9911263,48.24995398521423,-0.15457132243136731,1739502687.9911296,48.24995398521423,1.7104335616226463,1739502687.9911332,48.24995398521423,0.0,1739502687.9911366,48.24995398521423,0.21510522148505262,1739502687.9911401,48.24995398521423,3.2485610824954145,1739502687.9911435,48.24995398521423,1.4855555424967304 +1739502688.0084913,48.26995396614075,37.92560764998388,1739502688.0084934,48.26995396614075,-0.04621573950310687,1739502688.0084958,48.26995396614075,75.28315614709759,1739502688.0084984,48.26995396614075,33.07281127194979,1739502688.0084996,48.26995396614075,-0.09014363928991766,1739502688.0085013,48.26995396614075,-3.132540821078317,1739502688.0085025,48.26995396614075,-0.474429810860093,1739502688.008504,48.26995396614075,-0.15457132243136731,1739502688.008505,48.26995396614075,1.7104335616226463,1739502688.0085065,48.26995396614075,0.0,1739502688.008508,48.26995396614075,0.22487801912591587,1739502688.0085092,48.26995396614075,3.2485610824954145,1739502688.0085104,48.26995396614075,1.4855555424967304 +1739502688.028291,48.28995394706726,37.92560764998388,1739502688.0282938,48.28995394706726,-0.04621573950310687,1739502688.0282967,48.28995394706726,75.28315614709759,1739502688.0282996,48.28995394706726,33.07281127194979,1739502688.0283008,48.28995394706726,-0.09014363928991766,1739502688.0283027,48.28995394706726,-3.132540821078317,1739502688.028304,48.28995394706726,-0.474429810860093,1739502688.0283053,48.28995394706726,-0.15457132243136731,1739502688.0283067,48.28995394706726,1.7104335616226463,1739502688.0283082,48.28995394706726,0.0,1739502688.0283096,48.28995394706726,0.22487801912591587,1739502688.028311,48.28995394706726,3.2485610824954145,1739502688.0283127,48.28995394706726,1.4855555424967304 +1739502688.0483584,48.309953927993774,37.92560764998388,1739502688.0483615,48.309953927993774,-0.04621573950310687,1739502688.048365,48.309953927993774,75.28315614709759,1739502688.048368,48.309953927993774,33.07281127194979,1739502688.0483694,48.309953927993774,-0.09014363928991766,1739502688.0483713,48.309953927993774,-3.132540821078317,1739502688.0483727,48.309953927993774,-0.474429810860093,1739502688.0483742,48.309953927993774,-0.15457132243136731,1739502688.0483756,48.309953927993774,1.7104335616226463,1739502688.048377,48.309953927993774,0.0,1739502688.0483785,48.309953927993774,0.22487801912591587,1739502688.04838,48.309953927993774,3.2485610824954145,1739502688.0483813,48.309953927993774,1.4855555424967304 +1739502688.069147,48.32995390892029,37.92560764998388,1739502688.0691507,48.32995390892029,-0.04621573950310687,1739502688.0691547,48.32995390892029,75.28315614709759,1739502688.0691605,48.32995390892029,33.07281127194979,1739502688.069164,48.32995390892029,-0.09014363928991766,1739502688.069169,48.32995390892029,-3.132540821078317,1739502688.0691738,48.32995390892029,-0.474429810860093,1739502688.0691776,48.32995390892029,-0.15457132243136731,1739502688.069181,48.32995390892029,1.7104335616226463,1739502688.0691833,48.32995390892029,0.0,1739502688.0691872,48.32995390892029,0.22487801912591587,1739502688.0691905,48.32995390892029,3.2485610824954145,1739502688.0691924,48.32995390892029,1.4855555424967304 +1739502688.089134,48.339953899383545,37.92560764998388,1739502688.0891373,48.339953899383545,-0.04621573950310687,1739502688.0891433,48.339953899383545,75.28315614709759,1739502688.0891502,48.339953899383545,33.07281127194979,1739502688.089154,48.339953899383545,-0.09014363928991766,1739502688.0891588,48.339953899383545,-3.132540821078317,1739502688.0891628,48.339953899383545,-0.474429810860093,1739502688.089166,48.339953899383545,-0.15457132243136731,1739502688.089168,48.339953899383545,1.7104335616226463,1739502688.0891721,48.339953899383545,0.0,1739502688.089175,48.339953899383545,0.22487801912591587,1739502688.0891771,48.339953899383545,3.2485610824954145,1739502688.089179,48.339953899383545,1.4855555424967304 +1739502688.1095555,48.369953870773315,37.76185436125822,1739502688.1095579,48.369953870773315,-0.0631442036564609,1739502688.1095607,48.369953870773315,75.28628438804753,1739502688.1095634,48.369953870773315,33.020796622544346,1739502688.1095648,48.369953870773315,-0.08972192376052311,1739502688.1095665,48.369953870773315,-3.135986849322853,1739502688.109568,48.369953870773315,-0.43933817377114304,1739502688.1095695,48.369953870773315,-0.1499802233831895,1739502688.1095705,48.369953870773315,1.7591314498834736,1739502688.1095724,48.369953870773315,0.0,1739502688.1095736,48.369953870773315,0.260156326739563,1739502688.1095753,48.369953870773315,3.2399968336696063,1739502688.1095765,48.369953870773315,1.5099996015013866 +1739502688.1288996,48.38995385169983,37.76185436125822,1739502688.128902,48.38995385169983,-0.0631442036564609,1739502688.1289048,48.38995385169983,75.28628438804753,1739502688.1289074,48.38995385169983,33.020796622544346,1739502688.1289089,48.38995385169983,-0.08972192376052311,1739502688.1289105,48.38995385169983,-3.135986849322853,1739502688.128912,48.38995385169983,-0.43933817377114304,1739502688.1289132,48.38995385169983,-0.1499802233831895,1739502688.1289144,48.38995385169983,1.7591314498834736,1739502688.128916,48.38995385169983,0.0,1739502688.1289175,48.38995385169983,0.24913184838208702,1739502688.1289213,48.38995385169983,3.2399968336696063,1739502688.1289263,48.38995385169983,1.5099996015013866 +1739502688.1481845,48.40995383262634,37.76185436125822,1739502688.1481872,48.40995383262634,-0.0631442036564609,1739502688.1481898,48.40995383262634,75.28628438804753,1739502688.1481922,48.40995383262634,33.020796622544346,1739502688.1481938,48.40995383262634,-0.08972192376052311,1739502688.1481953,48.40995383262634,-3.135986849322853,1739502688.1481967,48.40995383262634,-0.43933817377114304,1739502688.1481984,48.40995383262634,-0.1499802233831895,1739502688.1481998,48.40995383262634,1.7591314498834736,1739502688.1482015,48.40995383262634,0.0,1739502688.1482027,48.40995383262634,0.24913184838208702,1739502688.148204,48.40995383262634,3.2399968336696063,1739502688.1482053,48.40995383262634,1.5099996015013866 +1739502688.1680374,48.429953813552856,37.76185436125822,1739502688.1680398,48.429953813552856,-0.0631442036564609,1739502688.1680422,48.429953813552856,75.28628438804753,1739502688.168045,48.429953813552856,33.020796622544346,1739502688.1680462,48.429953813552856,-0.08972192376052311,1739502688.1680481,48.429953813552856,-3.135986849322853,1739502688.1680493,48.429953813552856,-0.43933817377114304,1739502688.168051,48.429953813552856,-0.1499802233831895,1739502688.1680522,48.429953813552856,1.7591314498834736,1739502688.168054,48.429953813552856,0.0,1739502688.1680553,48.429953813552856,0.24913184838208702,1739502688.1680567,48.429953813552856,3.2399968336696063,1739502688.1680582,48.429953813552856,1.5099996015013866 +1739502688.1955667,48.44995379447937,37.76185436125822,1739502688.1955879,48.44995379447937,-0.0631442036564609,1739502688.1956122,48.44995379447937,75.28628438804753,1739502688.1956394,48.44995379447937,33.020796622544346,1739502688.1956458,48.44995379447937,-0.08972192376052311,1739502688.1956627,48.44995379447937,-3.135986849322853,1739502688.195677,48.44995379447937,-0.43933817377114304,1739502688.1956897,48.44995379447937,-0.1499802233831895,1739502688.1957061,48.44995379447937,1.7591314498834736,1739502688.1957204,48.44995379447937,0.0,1739502688.1957326,48.44995379447937,0.24913184838208702,1739502688.195738,48.44995379447937,3.2399968336696063,1739502688.1957436,48.44995379447937,1.5099996015013866 +1739502688.2201283,48.45995378494263,37.76185436125822,1739502688.2201378,48.45995378494263,-0.0631442036564609,1739502688.2201495,48.45995378494263,75.28628438804753,1739502688.2201595,48.45995378494263,33.020796622544346,1739502688.2201643,48.45995378494263,-0.08972192376052311,1739502688.2201712,48.45995378494263,-3.135986849322853,1739502688.2201765,48.45995378494263,-0.43933817377114304,1739502688.2201812,48.45995378494263,-0.1499802233831895,1739502688.220186,48.45995378494263,1.7591314498834736,1739502688.2201917,48.45995378494263,0.0,1739502688.2201967,48.45995378494263,0.24913184838208702,1739502688.220202,48.45995378494263,3.2399968336696063,1739502688.2202077,48.45995378494263,1.5099996015013866 +1739502688.2377694,48.4899537563324,37.595144512883685,1739502688.2377763,48.4899537563324,-0.07896628616849277,1739502688.2377844,48.4899537563324,75.28946769724915,1739502688.2377918,48.4899537563324,32.96310793582403,1739502688.237795,48.4899537563324,-0.08925291004734978,1739502688.2377994,48.4899537563324,-3.139371901055266,1739502688.237803,48.4899537563324,-0.40676778820639936,1739502688.2378066,48.4899537563324,-0.14548594108789853,1739502688.23781,48.4899537563324,1.8055703067690922,1739502688.237814,48.4899537563324,0.0,1739502688.2378175,48.4899537563324,0.2770376237708286,1739502688.2378213,48.4899537563324,3.231742637218304,1739502688.237825,48.4899537563324,1.5372532435248905 +1739502688.2573013,48.50995373725891,37.595144512883685,1739502688.2573073,48.50995373725891,-0.07896628616849277,1739502688.257315,48.50995373725891,75.28946769724915,1739502688.2573233,48.50995373725891,32.96310793582403,1739502688.257328,48.50995373725891,-0.08925291004734978,1739502688.257334,48.50995373725891,-3.139371901055266,1739502688.2573397,48.50995373725891,-0.40676778820639936,1739502688.257345,48.50995373725891,-0.14548594108789853,1739502688.2573504,48.50995373725891,1.8055703067690922,1739502688.257356,48.50995373725891,0.0,1739502688.2573617,48.50995373725891,0.2683170632442018,1739502688.2573674,48.50995373725891,3.231742637218304,1739502688.2573726,48.50995373725891,1.5372532435248905 +1739502688.272453,48.529953718185425,37.595144512883685,1739502688.2724574,48.529953718185425,-0.07896628616849277,1739502688.2724624,48.529953718185425,75.28946769724915,1739502688.2724683,48.529953718185425,32.96310793582403,1739502688.272471,48.529953718185425,-0.08925291004734978,1739502688.2724755,48.529953718185425,-3.139371901055266,1739502688.272479,48.529953718185425,-0.40676778820639936,1739502688.2724824,48.529953718185425,-0.14548594108789853,1739502688.272486,48.529953718185425,1.8055703067690922,1739502688.2724898,48.529953718185425,0.0,1739502688.2724934,48.529953718185425,0.2683170632442018,1739502688.272497,48.529953718185425,3.231742637218304,1739502688.2725005,48.529953718185425,1.5372532435248905 +1739502688.2896996,48.54995369911194,37.595144512883685,1739502688.2897017,48.54995369911194,-0.07896628616849277,1739502688.2897046,48.54995369911194,75.28946769724915,1739502688.2897072,48.54995369911194,32.96310793582403,1739502688.2897089,48.54995369911194,-0.08925291004734978,1739502688.2897103,48.54995369911194,-3.139371901055266,1739502688.2897117,48.54995369911194,-0.40676778820639936,1739502688.289713,48.54995369911194,-0.14548594108789853,1739502688.2897143,48.54995369911194,1.8055703067690922,1739502688.289716,48.54995369911194,0.0,1739502688.2897172,48.54995369911194,0.2683170632442018,1739502688.2897189,48.54995369911194,3.231742637218304,1739502688.2897203,48.54995369911194,1.5372532435248905 +1739502688.3100135,48.56995368003845,37.595144512883685,1739502688.310016,48.56995368003845,-0.07896628616849277,1739502688.3100197,48.56995368003845,75.28946769724915,1739502688.3100226,48.56995368003845,32.96310793582403,1739502688.3100245,48.56995368003845,-0.08925291004734978,1739502688.3100262,48.56995368003845,-3.139371901055266,1739502688.3100276,48.56995368003845,-0.40676778820639936,1739502688.3100288,48.56995368003845,-0.14548594108789853,1739502688.3100302,48.56995368003845,1.8055703067690922,1739502688.310032,48.56995368003845,0.0,1739502688.310033,48.56995368003845,0.2683170632442018,1739502688.3100348,48.56995368003845,3.231742637218304,1739502688.310036,48.56995368003845,1.5372532435248905 +1739502688.3304222,48.589953660964966,37.42523911895955,1739502688.3304255,48.589953660964966,-0.09368959638497731,1739502688.3304288,48.589953660964966,75.5202192393713,1739502688.3304317,48.589953660964966,32.674077001653494,1739502688.3304334,48.589953660964966,-0.08685723202645589,1739502688.3304353,48.589953660964966,3.1401546139102057,1739502688.330437,48.589953660964966,-0.3962426548034719,1739502688.3304381,48.589953660964966,-0.13471928812584288,1739502688.3304393,48.589953660964966,1.8208375873107578,1739502688.330441,48.589953660964966,0.0,1739502688.3304424,48.589953660964966,0.24813157851073056,1739502688.3304439,48.589953660964966,3.223650612556335,1739502688.3304453,48.589953660964966,1.5663980406849913 +1739502688.3515265,48.60995364189148,37.42523911895955,1739502688.3515294,48.60995364189148,-0.09368959638497731,1739502688.3515334,48.60995364189148,75.5202192393713,1739502688.351536,48.60995364189148,32.674077001653494,1739502688.3515377,48.60995364189148,-0.08685723202645589,1739502688.3515394,48.60995364189148,3.1401546139102057,1739502688.351541,48.60995364189148,-0.3962426548034719,1739502688.3515425,48.60995364189148,-0.13471928812584288,1739502688.351544,48.60995364189148,1.8208375873107578,1739502688.3515456,48.60995364189148,0.0,1739502688.3515472,48.60995364189148,0.2544395466257665,1739502688.3515484,48.60995364189148,3.223650612556335,1739502688.35155,48.60995364189148,1.5663980406849913 +1739502688.370145,48.62995362281799,37.42523911895955,1739502688.3701506,48.62995362281799,-0.09368959638497731,1739502688.3701558,48.62995362281799,75.5202192393713,1739502688.3701613,48.62995362281799,32.674077001653494,1739502688.3701642,48.62995362281799,-0.08685723202645589,1739502688.3701682,48.62995362281799,3.1401546139102057,1739502688.3701715,48.62995362281799,-0.3962426548034719,1739502688.370175,48.62995362281799,-0.13471928812584288,1739502688.3701782,48.62995362281799,1.8208375873107578,1739502688.370182,48.62995362281799,0.0,1739502688.3701854,48.62995362281799,0.2544395466257665,1739502688.3701887,48.62995362281799,3.223650612556335,1739502688.3701923,48.62995362281799,1.5663980406849913 +1739502688.3894053,48.64995360374451,37.42523911895955,1739502688.3894074,48.64995360374451,-0.09368959638497731,1739502688.3894103,48.64995360374451,75.5202192393713,1739502688.3894129,48.64995360374451,32.674077001653494,1739502688.389414,48.64995360374451,-0.08685723202645589,1739502688.389416,48.64995360374451,3.1401546139102057,1739502688.3894172,48.64995360374451,-0.3962426548034719,1739502688.3894188,48.64995360374451,-0.13471928812584288,1739502688.3894198,48.64995360374451,1.8208375873107578,1739502688.3894215,48.64995360374451,0.0,1739502688.389423,48.64995360374451,0.2544395466257665,1739502688.389424,48.64995360374451,3.223650612556335,1739502688.3894258,48.64995360374451,1.5663980406849913 +1739502688.4100733,48.66995358467102,37.42523911895955,1739502688.410076,48.66995358467102,-0.09368959638497731,1739502688.4100788,48.66995358467102,75.5202192393713,1739502688.4100814,48.66995358467102,32.674077001653494,1739502688.4100828,48.66995358467102,-0.08685723202645589,1739502688.4100847,48.66995358467102,3.1401546139102057,1739502688.410086,48.66995358467102,-0.3962426548034719,1739502688.410087,48.66995358467102,-0.13471928812584288,1739502688.4100888,48.66995358467102,1.8208375873107578,1739502688.4100902,48.66995358467102,0.0,1739502688.4100916,48.66995358467102,0.2544395466257665,1739502688.4100935,48.66995358467102,3.223650612556335,1739502688.4100955,48.66995358467102,1.5663980406849913 +1739502688.4297516,48.689953565597534,37.252073608038394,1739502688.429754,48.689953565597534,-0.10730740886600376,1739502688.4297569,48.689953565597534,75.43746212717296,1739502688.4297597,48.689953565597534,32.70110537794488,1739502688.4297612,48.689953565597534,-0.08714601111245866,1739502688.4297628,48.689953565597534,3.137162548864968,1739502688.4297643,48.689953565597534,-0.3580932185669648,1739502688.4297657,48.689953565597534,-0.13269599898564635,1739502688.429767,48.689953565597534,1.8772654254692898,1739502688.4297688,48.689953565597534,0.0,1739502688.42977,48.689953565597534,0.2959876835358784,1739502688.4297712,48.689953565597534,3.2159282579726245,1739502688.4297729,48.689953565597534,1.5942615432306648 +1739502688.4498973,48.70995354652405,37.252073608038394,1739502688.4499002,48.70995354652405,-0.10730740886600376,1739502688.4499032,48.70995354652405,75.43746212717296,1739502688.449906,48.70995354652405,32.70110537794488,1739502688.4499078,48.70995354652405,-0.08714601111245866,1739502688.4499094,48.70995354652405,3.137162548864968,1739502688.449911,48.70995354652405,-0.3580932185669648,1739502688.4499123,48.70995354652405,-0.13269599898564635,1739502688.4499135,48.70995354652405,1.8772654254692898,1739502688.4499156,48.70995354652405,0.0,1739502688.449917,48.70995354652405,0.28300388223862494,1739502688.4499187,48.70995354652405,3.2159282579726245,1739502688.44992,48.70995354652405,1.5942615432306648 +1739502688.4702072,48.72995352745056,37.252073608038394,1739502688.4702098,48.72995352745056,-0.10730740886600376,1739502688.4702132,48.72995352745056,75.43746212717296,1739502688.470216,48.72995352745056,32.70110537794488,1739502688.4702172,48.72995352745056,-0.08714601111245866,1739502688.470219,48.72995352745056,3.137162548864968,1739502688.4702203,48.72995352745056,-0.3580932185669648,1739502688.4702218,48.72995352745056,-0.13269599898564635,1739502688.4702232,48.72995352745056,1.8772654254692898,1739502688.4702249,48.72995352745056,0.0,1739502688.4702263,48.72995352745056,0.28300388223862494,1739502688.4702277,48.72995352745056,3.2159282579726245,1739502688.470229,48.72995352745056,1.5942615432306648 +1739502688.4897664,48.749953508377075,37.252073608038394,1739502688.4897687,48.749953508377075,-0.10730740886600376,1739502688.489772,48.749953508377075,75.43746212717296,1739502688.4897747,48.749953508377075,32.70110537794488,1739502688.4897761,48.749953508377075,-0.08714601111245866,1739502688.4897778,48.749953508377075,3.137162548864968,1739502688.4897795,48.749953508377075,-0.3580932185669648,1739502688.4897807,48.749953508377075,-0.13269599898564635,1739502688.489782,48.749953508377075,1.8772654254692898,1739502688.4897835,48.749953508377075,0.0,1739502688.4897852,48.749953508377075,0.28300388223862494,1739502688.4897866,48.749953508377075,3.2159282579726245,1739502688.4897878,48.749953508377075,1.5942615432306648 +1739502688.5096438,48.76995348930359,37.252073608038394,1739502688.5096464,48.76995348930359,-0.10730740886600376,1739502688.5096495,48.76995348930359,75.43746212717296,1739502688.5096521,48.76995348930359,32.70110537794488,1739502688.5096536,48.76995348930359,-0.08714601111245866,1739502688.5096552,48.76995348930359,3.137162548864968,1739502688.509657,48.76995348930359,-0.3580932185669648,1739502688.509658,48.76995348930359,-0.13269599898564635,1739502688.5096598,48.76995348930359,1.8772654254692898,1739502688.5096614,48.76995348930359,0.0,1739502688.5096633,48.76995348930359,0.28300388223862494,1739502688.509665,48.76995348930359,3.2159282579726245,1739502688.5096672,48.76995348930359,1.5942615432306648 +1739502688.52963,48.7899534702301,37.252073608038394,1739502688.5296323,48.7899534702301,-0.10730740886600376,1739502688.5296357,48.7899534702301,75.43746212717296,1739502688.5296383,48.7899534702301,32.70110537794488,1739502688.5296402,48.7899534702301,-0.08714601111245866,1739502688.5296416,48.7899534702301,3.137162548864968,1739502688.5296433,48.7899534702301,-0.3580932185669648,1739502688.529645,48.7899534702301,-0.13269599898564635,1739502688.5296464,48.7899534702301,1.8772654254692898,1739502688.5296478,48.7899534702301,0.0,1739502688.5296493,48.7899534702301,0.28300388223862494,1739502688.5296504,48.7899534702301,3.2159282579726245,1739502688.5296519,48.7899534702301,1.5942615432306648 +1739502688.549726,48.809953451156616,37.07557307036615,1739502688.5497282,48.809953451156616,-0.11985022904082054,1739502688.5497317,48.809953451156616,75.46884069336288,1739502688.5497344,48.809953451156616,32.607215835323174,1739502688.549736,48.809953451156616,-0.08578745336517075,1739502688.5497377,48.809953451156616,3.133969691930602,1739502688.5497396,48.809953451156616,-0.33273987313837694,1739502688.5497408,48.809953451156616,-0.1279033166930895,1739502688.549742,48.809953451156616,1.915730157712702,1739502688.549744,48.809953451156616,0.0,1739502688.549745,48.809953451156616,0.29348257594900684,1739502688.5497468,48.809953451156616,3.208502332635277,1739502688.5497484,48.809953451156616,1.6255221756951805 +1739502688.5695984,48.82995343208313,37.07557307036615,1739502688.5696013,48.82995343208313,-0.11985022904082054,1739502688.5696042,48.82995343208313,75.46884069336288,1739502688.569607,48.82995343208313,32.607215835323174,1739502688.5696082,48.82995343208313,-0.08578745336517075,1739502688.5696099,48.82995343208313,3.133969691930602,1739502688.5696113,48.82995343208313,-0.33273987313837694,1739502688.5696127,48.82995343208313,-0.1279033166930895,1739502688.5696142,48.82995343208313,1.915730157712702,1739502688.5696156,48.82995343208313,0.0,1739502688.5696168,48.82995343208313,0.2902079820175214,1739502688.5696185,48.82995343208313,3.208502332635277,1739502688.56962,48.82995343208313,1.6255221756951805 +1739502688.603576,48.849953413009644,37.07557307036615,1739502688.603589,48.849953413009644,-0.11985022904082054,1739502688.6036062,48.849953413009644,75.46884069336288,1739502688.6036263,48.849953413009644,32.607215835323174,1739502688.6036372,48.849953413009644,-0.08578745336517075,1739502688.6036515,48.849953413009644,3.133969691930602,1739502688.6036644,48.849953413009644,-0.33273987313837694,1739502688.6036773,48.849953413009644,-0.1279033166930895,1739502688.6036897,48.849953413009644,1.915730157712702,1739502688.6037028,48.849953413009644,0.0,1739502688.6037157,48.849953413009644,0.2902079820175214,1739502688.6037283,48.849953413009644,3.208502332635277,1739502688.6037412,48.849953413009644,1.6255221756951805 +1739502688.620063,48.86995339393616,37.07557307036615,1739502688.6200686,48.86995339393616,-0.11985022904082054,1739502688.6200757,48.86995339393616,75.46884069336288,1739502688.6200845,48.86995339393616,32.607215835323174,1739502688.620089,48.86995339393616,-0.08578745336517075,1739502688.6200955,48.86995339393616,3.133969691930602,1739502688.620101,48.86995339393616,-0.33273987313837694,1739502688.6201062,48.86995339393616,-0.1279033166930895,1739502688.6201117,48.86995339393616,1.915730157712702,1739502688.6201172,48.86995339393616,0.0,1739502688.6201227,48.86995339393616,0.2902079820175214,1739502688.6201282,48.86995339393616,3.208502332635277,1739502688.6201339,48.86995339393616,1.6255221756951805 +1739502688.6378188,48.88995337486267,37.07557307036615,1739502688.6378243,48.88995337486267,-0.11985022904082054,1739502688.6378295,48.88995337486267,75.46884069336288,1739502688.6378324,48.88995337486267,32.607215835323174,1739502688.637834,48.88995337486267,-0.08578745336517075,1739502688.6378355,48.88995337486267,3.133969691930602,1739502688.6378372,48.88995337486267,-0.33273987313837694,1739502688.6378386,48.88995337486267,-0.1279033166930895,1739502688.6378398,48.88995337486267,1.915730157712702,1739502688.6378417,48.88995337486267,0.0,1739502688.637843,48.88995337486267,0.2902079820175214,1739502688.6378443,48.88995337486267,3.208502332635277,1739502688.6378639,48.88995337486267,1.6255221756951805 +1739502688.657289,48.909953355789185,36.895542428509614,1739502688.6572926,48.909953355789185,-0.13131067814431674,1739502688.657297,48.909953355789185,75.57394433159732,1739502688.6573017,48.909953355789185,32.43860374684463,1739502688.6573045,48.909953355789185,-0.084044829974757,1739502688.657308,48.909953355789185,3.130988048112826,1739502688.6573114,48.909953355789185,-0.31277865551394146,1739502688.6573145,48.909953355789185,-0.12084847375126767,1739502688.6573179,48.909953355789185,1.9465679717884043,1739502688.6573212,48.909953355789185,0.0,1739502688.6573243,48.909953355789185,0.28886766021045895,1739502688.6573277,48.909953355789185,3.2012197371807116,1739502688.657331,48.909953355789185,1.6572814607386184 +1739502688.6777816,48.9299533367157,36.895542428509614,1739502688.6777852,48.9299533367157,-0.13131067814431674,1739502688.6777894,48.9299533367157,75.57394433159732,1739502688.6777945,48.9299533367157,32.43860374684463,1739502688.677797,48.9299533367157,-0.084044829974757,1739502688.677801,48.9299533367157,3.130988048112826,1739502688.6778042,48.9299533367157,-0.31277865551394146,1739502688.6778073,48.9299533367157,-0.12084847375126767,1739502688.677811,48.9299533367157,1.9465679717884043,1739502688.6778142,48.9299533367157,0.0,1739502688.6778176,48.9299533367157,0.289286511049786,1739502688.677821,48.9299533367157,3.2012197371807116,1739502688.6778243,48.9299533367157,1.6572814607386184 +1739502688.6973157,48.94995331764221,36.895542428509614,1739502688.6973186,48.94995331764221,-0.13131067814431674,1739502688.697323,48.94995331764221,75.57394433159732,1739502688.6973279,48.94995331764221,32.43860374684463,1739502688.6973307,48.94995331764221,-0.084044829974757,1739502688.6973345,48.94995331764221,3.130988048112826,1739502688.6973376,48.94995331764221,-0.31277865551394146,1739502688.697341,48.94995331764221,-0.12084847375126767,1739502688.6973443,48.94995331764221,1.9465679717884043,1739502688.6973474,48.94995331764221,0.0,1739502688.6973507,48.94995331764221,0.289286511049786,1739502688.697354,48.94995331764221,3.2012197371807116,1739502688.6973574,48.94995331764221,1.6572814607386184 +1739502688.7176511,48.969953298568726,36.895542428509614,1739502688.7176542,48.969953298568726,-0.13131067814431674,1739502688.7176585,48.969953298568726,75.57394433159732,1739502688.7176633,48.969953298568726,32.43860374684463,1739502688.717666,48.969953298568726,-0.084044829974757,1739502688.7176695,48.969953298568726,3.130988048112826,1739502688.7176726,48.969953298568726,-0.31277865551394146,1739502688.7176757,48.969953298568726,-0.12084847375126767,1739502688.7176788,48.969953298568726,1.9465679717884043,1739502688.717682,48.969953298568726,0.0,1739502688.717685,48.969953298568726,0.289286511049786,1739502688.7176883,48.969953298568726,3.2012197371807116,1739502688.7176917,48.969953298568726,1.6572814607386184 +1739502688.7376254,48.98995327949524,36.895542428509614,1739502688.7376287,48.98995327949524,-0.13131067814431674,1739502688.7376332,48.98995327949524,75.57394433159732,1739502688.7376385,48.98995327949524,32.43860374684463,1739502688.7376413,48.98995327949524,-0.084044829974757,1739502688.737645,48.98995327949524,3.130988048112826,1739502688.7376478,48.98995327949524,-0.31277865551394146,1739502688.737651,48.98995327949524,-0.12084847375126767,1739502688.7376542,48.98995327949524,1.9465679717884043,1739502688.7376575,48.98995327949524,0.0,1739502688.737661,48.98995327949524,0.289286511049786,1739502688.7376642,48.98995327949524,3.2012197371807116,1739502688.7376676,48.98995327949524,1.6572814607386184 +1739502688.7569275,49.00995326042175,36.895542428509614,1739502688.7569306,49.00995326042175,-0.13131067814431674,1739502688.756935,49.00995326042175,75.57394433159732,1739502688.7569401,49.00995326042175,32.43860374684463,1739502688.7569427,49.00995326042175,-0.084044829974757,1739502688.7569463,49.00995326042175,3.130988048112826,1739502688.7569494,49.00995326042175,-0.31277865551394146,1739502688.7569528,49.00995326042175,-0.12084847375126767,1739502688.7569559,49.00995326042175,1.9465679717884043,1739502688.7569592,49.00995326042175,0.0,1739502688.7569625,49.00995326042175,0.289286511049786,1739502688.7569659,49.00995326042175,3.2012197371807116,1739502688.7569692,49.00995326042175,1.6572814607386184 +1739502688.7778876,49.02995324134827,36.71194809470455,1739502688.7778912,49.02995324134827,-0.1416796159667877,1739502688.7778952,49.02995324134827,75.77619074463786,1739502688.7779,49.02995324134827,32.17300386362528,1739502688.7779026,49.02995324134827,-0.08203968161784392,1739502688.7779062,49.02995324134827,3.1284538046844927,1739502688.7779095,49.02995324134827,-0.2984371829406371,1739502688.7779126,49.02995324134827,-0.1111810037861213,1739502688.7779157,49.02995324134827,1.9690299011945467,1739502688.7779188,49.02995324134827,0.0,1739502688.7779222,49.02995324134827,0.2758770603113592,1739502688.777925,49.02995324134827,3.194245936410567,1739502688.7779284,49.02995324134827,1.688962384779952 +1739502688.797406,49.04995322227478,36.71194809470455,1739502688.797409,49.04995322227478,-0.1416796159667877,1739502688.7974133,49.04995322227478,75.77619074463786,1739502688.7974184,49.04995322227478,32.17300386362528,1739502688.797421,49.04995322227478,-0.08203968161784392,1739502688.7974246,49.04995322227478,3.1284538046844927,1739502688.797428,49.04995322227478,-0.2984371829406371,1739502688.797431,49.04995322227478,-0.1111810037861213,1739502688.7974343,49.04995322227478,1.9690299011945467,1739502688.7974377,49.04995322227478,0.0,1739502688.7974408,49.04995322227478,0.2800675164145947,1739502688.797444,49.04995322227478,3.194245936410567,1739502688.7974474,49.04995322227478,1.688962384779952 +1739502688.8157682,49.069953203201294,36.71194809470455,1739502688.8157706,49.069953203201294,-0.1416796159667877,1739502688.8157735,49.069953203201294,75.77619074463786,1739502688.815776,49.069953203201294,32.17300386362528,1739502688.8157773,49.069953203201294,-0.08203968161784392,1739502688.8157787,49.069953203201294,3.1284538046844927,1739502688.8157806,49.069953203201294,-0.2984371829406371,1739502688.8157818,49.069953203201294,-0.1111810037861213,1739502688.8157833,49.069953203201294,1.9690299011945467,1739502688.815785,49.069953203201294,0.0,1739502688.8157861,49.069953203201294,0.2800675164145947,1739502688.8157876,49.069953203201294,3.194245936410567,1739502688.8157887,49.069953203201294,1.688962384779952 +1739502688.835405,49.08995318412781,36.71194809470455,1739502688.835407,49.08995318412781,-0.1416796159667877,1739502688.8354099,49.08995318412781,75.77619074463786,1739502688.8354125,49.08995318412781,32.17300386362528,1739502688.8354137,49.08995318412781,-0.08203968161784392,1739502688.8354156,49.08995318412781,3.1284538046844927,1739502688.8354168,49.08995318412781,-0.2984371829406371,1739502688.8354182,49.08995318412781,-0.1111810037861213,1739502688.8354194,49.08995318412781,1.9690299011945467,1739502688.8354208,49.08995318412781,0.0,1739502688.8354223,49.08995318412781,0.2800675164145947,1739502688.8354235,49.08995318412781,3.194245936410567,1739502688.8354251,49.08995318412781,1.688962384779952 +1739502688.8559,49.10995316505432,36.71194809470455,1739502688.8559022,49.10995316505432,-0.1416796159667877,1739502688.8559053,49.10995316505432,75.77619074463786,1739502688.8559082,49.10995316505432,32.17300386362528,1739502688.8559093,49.10995316505432,-0.08203968161784392,1739502688.8559113,49.10995316505432,3.1284538046844927,1739502688.8559124,49.10995316505432,-0.2984371829406371,1739502688.8559136,49.10995316505432,-0.1111810037861213,1739502688.8559148,49.10995316505432,1.9690299011945467,1739502688.8559163,49.10995316505432,0.0,1739502688.8559175,49.10995316505432,0.2800675164145947,1739502688.855919,49.10995316505432,3.194245936410567,1739502688.85592,49.10995316505432,1.688962384779952 +1739502688.8755832,49.129953145980835,36.52484704605236,1739502688.8755856,49.129953145980835,-0.15096114662610471,1739502688.8755884,49.129953145980835,75.98308141227254,1739502688.8755908,49.129953145980835,31.904588408136608,1739502688.8755925,49.129953145980835,-0.07976820206075849,1739502688.8755941,49.129953145980835,3.1261850073030146,1739502688.8755956,49.129953145980835,-0.28354633765050663,1739502688.8755968,49.129953145980835,-0.10194885625009995,1739502688.8755982,49.129953145980835,1.992626587688517,1739502688.8755999,49.129953145980835,0.0,1739502688.875601,49.129953145980835,0.2696376374475629,1739502688.8756025,49.129953145980835,3.1875865283045615,1739502688.875604,49.129953145980835,1.7197296109267672 +1739502688.8959389,49.14995312690735,36.52484704605236,1739502688.895941,49.14995312690735,-0.15096114662610471,1739502688.8959439,49.14995312690735,75.98308141227254,1739502688.8959467,49.14995312690735,31.904588408136608,1739502688.8959482,49.14995312690735,-0.07976820206075849,1739502688.8959498,49.14995312690735,3.1261850073030146,1739502688.8959513,49.14995312690735,-0.28354633765050663,1739502688.8959527,49.14995312690735,-0.10194885625009995,1739502688.895954,49.14995312690735,1.992626587688517,1739502688.8959558,49.14995312690735,0.0,1739502688.895957,49.14995312690735,0.27289697676174973,1739502688.8959584,49.14995312690735,3.1875865283045615,1739502688.89596,49.14995312690735,1.7197296109267672 +1739502688.9155815,49.16995310783386,36.52484704605236,1739502688.9155843,49.16995310783386,-0.15096114662610471,1739502688.9155872,49.16995310783386,75.98308141227254,1739502688.91559,49.16995310783386,31.904588408136608,1739502688.9155915,49.16995310783386,-0.07976820206075849,1739502688.9155934,49.16995310783386,3.1261850073030146,1739502688.915595,49.16995310783386,-0.28354633765050663,1739502688.9155962,49.16995310783386,-0.10194885625009995,1739502688.9155977,49.16995310783386,1.992626587688517,1739502688.915599,49.16995310783386,0.0,1739502688.915601,49.16995310783386,0.27289697676174973,1739502688.9156024,49.16995310783386,3.1875865283045615,1739502688.9156036,49.16995310783386,1.7197296109267672 +1739502688.9361656,49.189953088760376,36.52484704605236,1739502688.9361684,49.189953088760376,-0.15096114662610471,1739502688.9361718,49.189953088760376,75.98308141227254,1739502688.9361746,49.189953088760376,31.904588408136608,1739502688.9361758,49.189953088760376,-0.07976820206075849,1739502688.936178,49.189953088760376,3.1261850073030146,1739502688.9361794,49.189953088760376,-0.28354633765050663,1739502688.9361806,49.189953088760376,-0.10194885625009995,1739502688.9361818,49.189953088760376,1.992626587688517,1739502688.9361832,49.189953088760376,0.0,1739502688.936185,49.189953088760376,0.27289697676174973,1739502688.936186,49.189953088760376,3.1875865283045615,1739502688.9361877,49.189953088760376,1.7197296109267672 +1739502688.9618328,49.21995306015015,36.52484704605236,1739502688.9618351,49.21995306015015,-0.15096114662610471,1739502688.961838,49.21995306015015,75.98308141227254,1739502688.9618406,49.21995306015015,31.904588408136608,1739502688.9618418,49.21995306015015,-0.07976820206075849,1739502688.9618435,49.21995306015015,3.1261850073030146,1739502688.9618447,49.21995306015015,-0.28354633765050663,1739502688.9618464,49.21995306015015,-0.10194885625009995,1739502688.9618473,49.21995306015015,1.992626587688517,1739502688.9618487,49.21995306015015,0.0,1739502688.9618502,49.21995306015015,0.27289697676174973,1739502688.9618514,49.21995306015015,3.1875865283045615,1739502688.9618528,49.21995306015015,1.7197296109267672 +1739502688.9980795,49.24995303153992,36.33436350801378,1739502688.9980834,49.24995303153992,-0.1591835338972345,1739502688.9980884,49.24995303153992,76.32437257633187,1739502688.998094,49.24995303153992,31.5036548496893,1739502688.9980974,49.24995303153992,-0.07665869960385277,1739502688.9981012,49.24995303153992,3.1245109346397677,1739502688.9981053,49.24995303153992,-0.27464647875224113,1739502688.9981086,49.24995303153992,-0.0903348960799647,1739502688.9981122,49.24995303153992,2.0068644900446606,1739502688.998116,49.24995303153992,0.0,1739502688.9981196,49.24995303153992,0.25022138318716275,1739502688.9981234,49.24995303153992,3.1813875841466803,1739502688.9981272,49.24995303153992,1.7495569792194121 +1739502689.0160728,49.26995301246643,36.33436350801378,1739502689.0160756,49.26995301246643,-0.1591835338972345,1739502689.0160792,49.26995301246643,76.32437257633187,1739502689.0160818,49.26995301246643,31.5036548496893,1739502689.0160835,49.26995301246643,-0.07665869960385277,1739502689.0160851,49.26995301246643,3.1245109346397677,1739502689.0160868,49.26995301246643,-0.27464647875224113,1739502689.0160882,49.26995301246643,-0.0903348960799647,1739502689.0160897,49.26995301246643,2.0068644900446606,1739502689.0160916,49.26995301246643,0.0,1739502689.016093,49.26995301246643,0.2573075108252485,1739502689.0160947,49.26995301246643,3.1813875841466803,1739502689.0160966,49.26995301246643,1.7495569792194121 +1739502689.037368,49.289952993392944,36.33436350801378,1739502689.037371,49.289952993392944,-0.1591835338972345,1739502689.0373738,49.289952993392944,76.32437257633187,1739502689.0373764,49.289952993392944,31.5036548496893,1739502689.037378,49.289952993392944,-0.07665869960385277,1739502689.0373797,49.289952993392944,3.1245109346397677,1739502689.0373814,49.289952993392944,-0.27464647875224113,1739502689.0373826,49.289952993392944,-0.0903348960799647,1739502689.037384,49.289952993392944,2.0068644900446606,1739502689.0373855,49.289952993392944,0.0,1739502689.037387,49.289952993392944,0.2573075108252485,1739502689.0373883,49.289952993392944,3.1813875841466803,1739502689.0373898,49.289952993392944,1.7495569792194121 +1739502689.0562284,49.30995297431946,36.33436350801378,1739502689.0562305,49.30995297431946,-0.1591835338972345,1739502689.0562334,49.30995297431946,76.32437257633187,1739502689.0562363,49.30995297431946,31.5036548496893,1739502689.056238,49.30995297431946,-0.07665869960385277,1739502689.0562394,49.30995297431946,3.1245109346397677,1739502689.0562406,49.30995297431946,-0.27464647875224113,1739502689.0562425,49.30995297431946,-0.0903348960799647,1739502689.0562437,49.30995297431946,2.0068644900446606,1739502689.0562456,49.30995297431946,0.0,1739502689.0562468,49.30995297431946,0.2573075108252485,1739502689.0562484,49.30995297431946,3.1813875841466803,1739502689.0562496,49.30995297431946,1.7495569792194121 +1739502689.0763023,49.32995295524597,36.33436350801378,1739502689.0763052,49.32995295524597,-0.1591835338972345,1739502689.0763083,49.32995295524597,76.32437257633187,1739502689.0763118,49.32995295524597,31.5036548496893,1739502689.0763133,49.32995295524597,-0.07665869960385277,1739502689.0763152,49.32995295524597,3.1245109346397677,1739502689.0763168,49.32995295524597,-0.27464647875224113,1739502689.0763187,49.32995295524597,-0.0903348960799647,1739502689.0763202,49.32995295524597,2.0068644900446606,1739502689.076322,49.32995295524597,0.0,1739502689.0763237,49.32995295524597,0.2573075108252485,1739502689.0763254,49.32995295524597,3.1813875841466803,1739502689.076327,49.32995295524597,1.7495569792194121 +1739502689.0955877,49.349952936172485,36.140615005445106,1739502689.0955904,49.349952936172485,-0.16636770405833445,1739502689.0955932,49.349952936172485,76.32844847905596,1739502689.095596,49.349952936172485,31.442836075329016,1739502689.0955975,49.349952936172485,-0.07617981161676389,1739502689.0955992,49.349952936172485,3.122397025981592,1739502689.0956006,49.349952936172485,-0.2494915763173864,1739502689.095602,49.349952936172485,-0.08676624499494895,1739502689.0956037,49.349952936172485,2.0476595762370193,1739502689.0956051,49.349952936172485,0.0,1739502689.0956066,49.349952936172485,0.27537690922269786,1739502689.095608,49.349952936172485,3.175520636570718,1739502689.0956097,49.349952936172485,1.7779293577157833 +1739502689.1153963,49.369952917099,36.140615005445106,1739502689.115399,49.369952917099,-0.16636770405833445,1739502689.115402,49.369952917099,76.32844847905596,1739502689.1154048,49.369952917099,31.442836075329016,1739502689.1154063,49.369952917099,-0.07617981161676389,1739502689.115408,49.369952917099,3.122397025981592,1739502689.1154094,49.369952917099,-0.2494915763173864,1739502689.1154108,49.369952917099,-0.08676624499494895,1739502689.115412,49.369952917099,2.0476595762370193,1739502689.1154137,49.369952917099,0.0,1739502689.1154153,49.369952917099,0.269730218521236,1739502689.1154165,49.369952917099,3.175520636570718,1739502689.1154182,49.369952917099,1.7779293577157833 +1739502689.1357164,49.38995289802551,36.140615005445106,1739502689.1357186,49.38995289802551,-0.16636770405833445,1739502689.1357214,49.38995289802551,76.32844847905596,1739502689.135724,49.38995289802551,31.442836075329016,1739502689.1357255,49.38995289802551,-0.07617981161676389,1739502689.1357276,49.38995289802551,3.122397025981592,1739502689.135729,49.38995289802551,-0.2494915763173864,1739502689.1357305,49.38995289802551,-0.08676624499494895,1739502689.1357317,49.38995289802551,2.0476595762370193,1739502689.1357334,49.38995289802551,0.0,1739502689.1357346,49.38995289802551,0.269730218521236,1739502689.1357358,49.38995289802551,3.175520636570718,1739502689.1357374,49.38995289802551,1.7779293577157833 +1739502689.1557727,49.409952878952026,36.140615005445106,1739502689.155775,49.409952878952026,-0.16636770405833445,1739502689.1557777,49.409952878952026,76.32844847905596,1739502689.1557806,49.409952878952026,31.442836075329016,1739502689.1557817,49.409952878952026,-0.07617981161676389,1739502689.1557834,49.409952878952026,3.122397025981592,1739502689.1557846,49.409952878952026,-0.2494915763173864,1739502689.155786,49.409952878952026,-0.08676624499494895,1739502689.1557872,49.409952878952026,2.0476595762370193,1739502689.155789,49.409952878952026,0.0,1739502689.15579,49.409952878952026,0.269730218521236,1739502689.1557913,49.409952878952026,3.175520636570718,1739502689.1557927,49.409952878952026,1.7779293577157833 +1739502689.1757872,49.42995285987854,36.140615005445106,1739502689.1757896,49.42995285987854,-0.16636770405833445,1739502689.1757925,49.42995285987854,76.32844847905596,1739502689.1757956,49.42995285987854,31.442836075329016,1739502689.1757967,49.42995285987854,-0.07617981161676389,1739502689.1757984,49.42995285987854,3.122397025981592,1739502689.1758,49.42995285987854,-0.2494915763173864,1739502689.1758013,49.42995285987854,-0.08676624499494895,1739502689.1758025,49.42995285987854,2.0476595762370193,1739502689.1758041,49.42995285987854,0.0,1739502689.1758053,49.42995285987854,0.269730218521236,1739502689.1758068,49.42995285987854,3.175520636570718,1739502689.1758084,49.42995285987854,1.7779293577157833 +1739502689.1972868,49.449952840805054,36.140615005445106,1739502689.1972892,49.449952840805054,-0.16636770405833445,1739502689.197292,49.449952840805054,76.32844847905596,1739502689.197295,49.449952840805054,31.442836075329016,1739502689.1972961,49.449952840805054,-0.07617981161676389,1739502689.1972978,49.449952840805054,3.122397025981592,1739502689.1972992,49.449952840805054,-0.2494915763173864,1739502689.1973007,49.449952840805054,-0.08676624499494895,1739502689.197302,49.449952840805054,2.0476595762370193,1739502689.1973035,49.449952840805054,0.0,1739502689.1973047,49.449952840805054,0.269730218521236,1739502689.1973064,49.449952840805054,3.175520636570718,1739502689.1973076,49.449952840805054,1.7779293577157833 +1739502689.2159011,49.46995282173157,35.94364991917917,1739502689.2159035,49.46995282173157,-0.17255950935909414,1739502689.2159064,49.46995282173157,76.62206788529501,1739502689.2159088,49.46995282173157,31.089917761395167,1739502689.2159104,49.46995282173157,-0.0732807549650016,1739502689.2159119,49.46995282173157,3.1211413988559467,1739502689.2159135,49.46995282173157,-0.2373613162039887,1739502689.2159147,49.46995282173157,-0.07732887468496509,1739502689.215916,49.46995282173157,2.0676272192466123,1739502689.2159176,49.46995282173157,0.0,1739502689.2159188,49.46995282173157,0.2556388446026318,1739502689.2159204,49.46995282173157,3.170053518827438,1739502689.2159219,49.46995282173157,1.8075848174072195 +1739502689.235765,49.48995280265808,35.94364991917917,1739502689.2357674,49.48995280265808,-0.17255950935909414,1739502689.2357702,49.48995280265808,76.62206788529501,1739502689.235773,49.48995280265808,31.089917761395167,1739502689.2357745,49.48995280265808,-0.0732807549650016,1739502689.2357762,49.48995280265808,3.1211413988559467,1739502689.2357779,49.48995280265808,-0.2373613162039887,1739502689.235779,49.48995280265808,-0.07732887468496509,1739502689.23578,49.48995280265808,2.0676272192466123,1739502689.235782,49.48995280265808,0.0,1739502689.235783,49.48995280265808,0.26004240183939276,1739502689.2357845,49.48995280265808,3.170053518827438,1739502689.235786,49.48995280265808,1.8075848174072195 +1739502689.2573142,49.509952783584595,35.94364991917917,1739502689.2573178,49.509952783584595,-0.17255950935909414,1739502689.2573225,49.509952783584595,76.62206788529501,1739502689.2573278,49.509952783584595,31.089917761395167,1739502689.2573307,49.509952783584595,-0.0732807549650016,1739502689.2573345,49.509952783584595,3.1211413988559467,1739502689.257338,49.509952783584595,-0.2373613162039887,1739502689.2573414,49.509952783584595,-0.07732887468496509,1739502689.2573447,49.509952783584595,2.0676272192466123,1739502689.2573483,49.509952783584595,0.0,1739502689.2573519,49.509952783584595,0.26004240183939276,1739502689.2573555,49.509952783584595,3.170053518827438,1739502689.2573588,49.509952783584595,1.8075848174072195 +1739502689.277705,49.52995276451111,35.94364991917917,1739502689.2777085,49.52995276451111,-0.17255950935909414,1739502689.277713,49.52995276451111,76.62206788529501,1739502689.2777185,49.52995276451111,31.089917761395167,1739502689.2777214,49.52995276451111,-0.0732807549650016,1739502689.2777252,49.52995276451111,3.1211413988559467,1739502689.2777288,49.52995276451111,-0.2373613162039887,1739502689.2777321,49.52995276451111,-0.07732887468496509,1739502689.2777355,49.52995276451111,2.0676272192466123,1739502689.277739,49.52995276451111,0.0,1739502689.2777424,49.52995276451111,0.26004240183939276,1739502689.277746,49.52995276451111,3.170053518827438,1739502689.2777493,49.52995276451111,1.8075848174072195 +1739502689.2973886,49.54995274543762,35.94364991917917,1739502689.2973917,49.54995274543762,-0.17255950935909414,1739502689.2973955,49.54995274543762,76.62206788529501,1739502689.2974002,49.54995274543762,31.089917761395167,1739502689.2974029,49.54995274543762,-0.0732807549650016,1739502689.2974064,49.54995274543762,3.1211413988559467,1739502689.2974095,49.54995274543762,-0.2373613162039887,1739502689.2974126,49.54995274543762,-0.07732887468496509,1739502689.2974157,49.54995274543762,2.0676272192466123,1739502689.2974188,49.54995274543762,0.0,1739502689.297422,49.54995274543762,0.26004240183939276,1739502689.2974253,49.54995274543762,3.170053518827438,1739502689.2974281,49.54995274543762,1.8075848174072195 +1739502689.317452,49.569952726364136,35.74345759630508,1739502689.3174553,49.569952726364136,-0.1777768494546148,1739502689.3174598,49.569952726364136,76.74296823313404,1739502689.317465,49.569952726364136,30.91209267918774,1739502689.317468,49.569952726364136,-0.072152317568725,1739502689.3174715,49.569952726364136,3.119733880658133,1739502689.3174748,49.569952726364136,-0.2180757509724265,1739502689.3174782,49.569952726364136,-0.07170322335346987,1739502689.3174813,49.569952726364136,2.0997748634394267,1739502689.3174846,49.569952726364136,0.0,1739502689.317488,49.569952726364136,0.26539914642420404,1739502689.317491,49.569952726364136,3.164875931346321,1739502689.3174946,49.569952726364136,1.8360497007955254 +1739502689.3375142,49.58995270729065,35.74345759630508,1739502689.3375177,49.58995270729065,-0.1777768494546148,1739502689.3375432,49.58995270729065,76.74296823313404,1739502689.3375485,49.58995270729065,30.91209267918774,1739502689.3375514,49.58995270729065,-0.072152317568725,1739502689.3375552,49.58995270729065,3.119733880658133,1739502689.3375585,49.58995270729065,-0.2180757509724265,1739502689.3375618,49.58995270729065,-0.07170322335346987,1739502689.3375652,49.58995270729065,2.0997748634394267,1739502689.3375685,49.58995270729065,0.0,1739502689.3375719,49.58995270729065,0.2637251626439012,1739502689.3375752,49.58995270729065,3.164875931346321,1739502689.3375788,49.58995270729065,1.8360497007955254 +1739502689.3571053,49.60995268821716,35.74345759630508,1739502689.357108,49.60995268821716,-0.1777768494546148,1739502689.3571126,49.60995268821716,76.74296823313404,1739502689.3571177,49.60995268821716,30.91209267918774,1739502689.3571203,49.60995268821716,-0.072152317568725,1739502689.357124,49.60995268821716,3.119733880658133,1739502689.3571272,49.60995268821716,-0.2180757509724265,1739502689.3571305,49.60995268821716,-0.07170322335346987,1739502689.3571336,49.60995268821716,2.0997748634394267,1739502689.3571372,49.60995268821716,0.0,1739502689.3571403,49.60995268821716,0.2637251626439012,1739502689.3571436,49.60995268821716,3.164875931346321,1739502689.3571472,49.60995268821716,1.8360497007955254 +1739502689.386181,49.62995266914368,35.74345759630508,1739502689.3861876,49.62995266914368,-0.1777768494546148,1739502689.3862345,49.62995266914368,76.74296823313404,1739502689.3862438,49.62995266914368,30.91209267918774,1739502689.3862474,49.62995266914368,-0.072152317568725,1739502689.386252,49.62995266914368,3.119733880658133,1739502689.3862555,49.62995266914368,-0.2180757509724265,1739502689.3862588,49.62995266914368,-0.07170322335346987,1739502689.3862622,49.62995266914368,2.0997748634394267,1739502689.3862665,49.62995266914368,0.0,1739502689.38627,49.62995266914368,0.2637251626439012,1739502689.3862736,49.62995266914368,3.164875931346321,1739502689.3862774,49.62995266914368,1.8360497007955254 +1739502689.3997617,49.64995265007019,35.74345759630508,1739502689.3997662,49.64995265007019,-0.1777768494546148,1739502689.3997724,49.64995265007019,76.74296823313404,1739502689.3997793,49.64995265007019,30.91209267918774,1739502689.3997834,49.64995265007019,-0.072152317568725,1739502689.3997886,49.64995265007019,3.119733880658133,1739502689.3997931,49.64995265007019,-0.2180757509724265,1739502689.3997977,49.64995265007019,-0.07170322335346987,1739502689.3998022,49.64995265007019,2.0997748634394267,1739502689.399807,49.64995265007019,0.0,1739502689.3998115,49.64995265007019,0.2637251626439012,1739502689.3998163,49.64995265007019,3.164875931346321,1739502689.399821,49.64995265007019,1.8360497007955254 +1739502689.4184744,49.669952630996704,35.74345759630508,1739502689.4184785,49.669952630996704,-0.1777768494546148,1739502689.4184828,49.669952630996704,76.74296823313404,1739502689.4184875,49.669952630996704,30.91209267918774,1739502689.4184902,49.669952630996704,-0.072152317568725,1739502689.418494,49.669952630996704,3.119733880658133,1739502689.418497,49.669952630996704,-0.2180757509724265,1739502689.4185002,49.669952630996704,-0.07170322335346987,1739502689.4185033,49.669952630996704,2.0997748634394267,1739502689.4185069,49.669952630996704,0.0,1739502689.4185097,49.669952630996704,0.2637251626439012,1739502689.4185128,49.669952630996704,3.164875931346321,1739502689.4185162,49.669952630996704,1.8360497007955254 +1739502689.4373972,49.68995261192322,35.54008758103605,1739502689.4374008,49.68995261192322,-0.18206205804852793,1739502689.4374049,49.68995261192322,76.88230901196006,1739502689.4374096,49.68995261192322,30.714930219173013,1739502689.4374123,49.68995261192322,-0.06999890967457831,1739502689.4374156,49.68995261192322,3.118372062442411,1739502689.4374187,49.68995261192322,-0.20112324721994854,1739502689.437422,49.68995261192322,-0.06629726792247938,1739502689.4374251,49.68995261192322,2.1284459959832134,1739502689.4374285,49.68995261192322,0.0,1739502689.4374316,49.68995261192322,0.26336718076538573,1739502689.437435,49.68995261192322,3.1600551101479155,1739502689.437438,49.68995261192322,1.8649669458074443 +1739502689.457021,49.70995259284973,35.54008758103605,1739502689.457024,49.70995259284973,-0.18206205804852793,1739502689.4570284,49.70995259284973,76.88230901196006,1739502689.4570332,49.70995259284973,30.714930219173013,1739502689.4570358,49.70995259284973,-0.06999890967457831,1739502689.457039,49.70995259284973,3.118372062442411,1739502689.4570422,49.70995259284973,-0.20112324721994854,1739502689.4570453,49.70995259284973,-0.06629726792247938,1739502689.4570484,49.70995259284973,2.1284459959832134,1739502689.457052,49.70995259284973,0.0,1739502689.457055,49.70995259284973,0.2634790501757691,1739502689.457058,49.70995259284973,3.1600551101479155,1739502689.457061,49.70995259284973,1.8649669458074443 +1739502689.475904,49.729952573776245,35.54008758103605,1739502689.4759068,49.729952573776245,-0.18206205804852793,1739502689.4759097,49.729952573776245,76.88230901196006,1739502689.475912,49.729952573776245,30.714930219173013,1739502689.4759138,49.729952573776245,-0.06999890967457831,1739502689.4759152,49.729952573776245,3.118372062442411,1739502689.4759169,49.729952573776245,-0.20112324721994854,1739502689.4759183,49.729952573776245,-0.06629726792247938,1739502689.47592,49.729952573776245,2.1284459959832134,1739502689.4759214,49.729952573776245,0.0,1739502689.4759226,49.729952573776245,0.2634790501757691,1739502689.4759243,49.729952573776245,3.1600551101479155,1739502689.4759257,49.729952573776245,1.8649669458074443 +1739502689.4955359,49.74995255470276,35.54008758103605,1739502689.4955387,49.74995255470276,-0.18206205804852793,1739502689.495542,49.74995255470276,76.88230901196006,1739502689.4955447,49.74995255470276,30.714930219173013,1739502689.4955459,49.74995255470276,-0.06999890967457831,1739502689.4955475,49.74995255470276,3.118372062442411,1739502689.4955492,49.74995255470276,-0.20112324721994854,1739502689.4955506,49.74995255470276,-0.06629726792247938,1739502689.4955518,49.74995255470276,2.1284459959832134,1739502689.4955535,49.74995255470276,0.0,1739502689.495555,49.74995255470276,0.2634790501757691,1739502689.495556,49.74995255470276,3.1600551101479155,1739502689.4955575,49.74995255470276,1.8649669458074443 +1739502689.516264,49.76995253562927,35.54008758103605,1739502689.5162666,49.76995253562927,-0.18206205804852793,1739502689.5162692,49.76995253562927,76.88230901196006,1739502689.516272,49.76995253562927,30.714930219173013,1739502689.5162735,49.76995253562927,-0.06999890967457831,1739502689.5162756,49.76995253562927,3.118372062442411,1739502689.516277,49.76995253562927,-0.20112324721994854,1739502689.5162783,49.76995253562927,-0.06629726792247938,1739502689.5162797,49.76995253562927,2.1284459959832134,1739502689.5162816,49.76995253562927,0.0,1739502689.5162828,49.76995253562927,0.2634790501757691,1739502689.5162845,49.76995253562927,3.1600551101479155,1739502689.516286,49.76995253562927,1.8649669458074443 +1739502689.547015,49.789952516555786,35.33352609979971,1739502689.5470233,49.789952516555786,-0.1854384572941319,1739502689.5470338,49.789952516555786,77.18944457704652,1739502689.5470436,49.789952516555786,30.350153287477333,1739502689.5470488,49.789952516555786,-0.06632020600740052,1739502689.5470545,49.789952516555786,3.1176940658106784,1739502689.5470595,49.789952516555786,-0.18821431138968928,1739502689.5470643,49.789952516555786,-0.058165386040273354,1739502689.547069,49.789952516555786,2.150540665308852,1739502689.5470748,49.789952516555786,0.0,1739502689.5470796,49.789952516555786,0.25367997714832574,1739502689.5470848,49.789952516555786,3.155460716914593,1739502689.5470896,49.789952516555786,1.8937984758317072 +1739502689.5628347,49.8099524974823,35.33352609979971,1739502689.5628433,49.8099524974823,-0.1854384572941319,1739502689.5628538,49.8099524974823,77.18944457704652,1739502689.5628638,49.8099524974823,30.350153287477333,1739502689.562869,49.8099524974823,-0.06632020600740052,1739502689.5628755,49.8099524974823,3.1176940658106784,1739502689.5628808,49.8099524974823,-0.18821431138968928,1739502689.562886,49.8099524974823,-0.058165386040273354,1739502689.5628905,49.8099524974823,2.150540665308852,1739502689.5628965,49.8099524974823,0.0,1739502689.5629013,49.8099524974823,0.25674218947714467,1739502689.5629067,49.8099524974823,3.155460716914593,1739502689.5629117,49.8099524974823,1.8937984758317072 +1739502689.586507,49.83995246887207,35.33352609979971,1739502689.5865126,49.83995246887207,-0.1854384572941319,1739502689.58652,49.83995246887207,77.18944457704652,1739502689.5865273,49.83995246887207,30.350153287477333,1739502689.5865304,49.83995246887207,-0.06632020600740052,1739502689.5865352,49.83995246887207,3.1176940658106784,1739502689.5865388,49.83995246887207,-0.18821431138968928,1739502689.5865426,49.83995246887207,-0.058165386040273354,1739502689.586546,49.83995246887207,2.150540665308852,1739502689.5865498,49.83995246887207,0.0,1739502689.5865533,49.83995246887207,0.25674218947714467,1739502689.586557,49.83995246887207,3.155460716914593,1739502689.5865605,49.83995246887207,1.8937984758317072 +1739502689.6064224,49.859952449798584,35.33352609979971,1739502689.6064272,49.859952449798584,-0.1854384572941319,1739502689.6064327,49.859952449798584,77.18944457704652,1739502689.6064382,49.859952449798584,30.350153287477333,1739502689.6064408,49.859952449798584,-0.06632020600740052,1739502689.6064441,49.859952449798584,3.1176940658106784,1739502689.6064467,49.859952449798584,-0.18821431138968928,1739502689.6064494,49.859952449798584,-0.058165386040273354,1739502689.606452,49.859952449798584,2.150540665308852,1739502689.606455,49.859952449798584,0.0,1739502689.6064577,49.859952449798584,0.25674218947714467,1739502689.6064603,49.859952449798584,3.155460716914593,1739502689.6064632,49.859952449798584,1.8937984758317072 +1739502689.6256824,49.8799524307251,35.33352609979971,1739502689.6256866,49.8799524307251,-0.1854384572941319,1739502689.6256912,49.8799524307251,77.18944457704652,1739502689.6256952,49.8799524307251,30.350153287477333,1739502689.6256974,49.8799524307251,-0.06632020600740052,1739502689.6256998,49.8799524307251,3.1176940658106784,1739502689.6257021,49.8799524307251,-0.18821431138968928,1739502689.6257043,49.8799524307251,-0.058165386040273354,1739502689.6257062,49.8799524307251,2.150540665308852,1739502689.625709,49.8799524307251,0.0,1739502689.6257117,49.8799524307251,0.25674218947714467,1739502689.6257136,49.8799524307251,3.155460716914593,1739502689.625716,49.8799524307251,1.8937984758317072 +1739502689.6459785,49.89995241165161,35.123813401798905,1739502689.645982,49.89995241165161,-0.18792858712060845,1739502689.6459866,49.89995241165161,77.41360411192062,1739502689.6459908,49.89995241165161,30.069751925798414,1739502689.6459932,49.89995241165161,-0.06347869709921253,1739502689.6459959,49.89995241165161,3.116973889601074,1739502689.645998,49.89995241165161,-0.17279249514032632,1739502689.6460001,49.89995241165161,-0.05191566893712006,1739502689.6460023,49.89995241165161,2.1772372047120543,1739502689.6460044,49.89995241165161,0.0,1739502689.6460066,49.89995241165161,0.2546586192180036,1739502689.6460087,49.89995241165161,3.1511590265545477,1739502689.646011,49.89995241165161,1.921927469361164 +1739502689.66635,49.919952392578125,35.123813401798905,1739502689.6663535,49.919952392578125,-0.18792858712060845,1739502689.6663582,49.919952392578125,77.41360411192062,1739502689.6663623,49.919952392578125,30.069751925798414,1739502689.6663647,49.919952392578125,-0.06347869709921253,1739502689.6663673,49.919952392578125,3.116973889601074,1739502689.6663694,49.919952392578125,-0.17279249514032632,1739502689.6663716,49.919952392578125,-0.05191566893712006,1739502689.666374,49.919952392578125,2.1772372047120543,1739502689.6663764,49.919952392578125,0.0,1739502689.6663785,49.919952392578125,0.2553097353508902,1739502689.666381,49.919952392578125,3.1511590265545477,1739502689.6663828,49.919952392578125,1.921927469361164 +1739502689.6844091,49.93995237350464,35.123813401798905,1739502689.6844118,49.93995237350464,-0.18792858712060845,1739502689.6844149,49.93995237350464,77.41360411192062,1739502689.684418,49.93995237350464,30.069751925798414,1739502689.6844196,49.93995237350464,-0.06347869709921253,1739502689.6844215,49.93995237350464,3.116973889601074,1739502689.6844234,49.93995237350464,-0.17279249514032632,1739502689.6844249,49.93995237350464,-0.05191566893712006,1739502689.6844265,49.93995237350464,2.1772372047120543,1739502689.6844285,49.93995237350464,0.0,1739502689.68443,49.93995237350464,0.2553097353508902,1739502689.6844316,49.93995237350464,3.1511590265545477,1739502689.6844332,49.93995237350464,1.921927469361164 +1739502689.7042494,49.95995235443115,35.123813401798905,1739502689.7042518,49.95995235443115,-0.18792858712060845,1739502689.7042544,49.95995235443115,77.41360411192062,1739502689.704257,49.95995235443115,30.069751925798414,1739502689.7042582,49.95995235443115,-0.06347869709921253,1739502689.70426,49.95995235443115,3.116973889601074,1739502689.7042615,49.95995235443115,-0.17279249514032632,1739502689.704263,49.95995235443115,-0.05191566893712006,1739502689.7042642,49.95995235443115,2.1772372047120543,1739502689.7042658,49.95995235443115,0.0,1739502689.704267,49.95995235443115,0.2553097353508902,1739502689.7042682,49.95995235443115,3.1511590265545477,1739502689.7042696,49.95995235443115,1.921927469361164 +1739502689.727383,49.979952335357666,35.123813401798905,1739502689.727388,49.979952335357666,-0.18792858712060845,1739502689.727394,49.979952335357666,77.41360411192062,1739502689.7273996,49.979952335357666,30.069751925798414,1739502689.7274024,49.979952335357666,-0.06347869709921253,1739502689.727406,49.979952335357666,3.116973889601074,1739502689.7274091,49.979952335357666,-0.17279249514032632,1739502689.727412,49.979952335357666,-0.05191566893712006,1739502689.7274146,49.979952335357666,2.1772372047120543,1739502689.727418,49.979952335357666,0.0,1739502689.727421,49.979952335357666,0.2553097353508902,1739502689.727424,49.979952335357666,3.1511590265545477,1739502689.7274272,49.979952335357666,1.921927469361164 +1739502689.7449443,49.99995231628418,35.123813401798905,1739502689.7449474,49.99995231628418,-0.18792858712060845,1739502689.7449512,49.99995231628418,77.41360411192062,1739502689.7449546,49.99995231628418,30.069751925798414,1739502689.7449567,49.99995231628418,-0.06347869709921253,1739502689.7449586,49.99995231628418,3.116973889601074,1739502689.7449605,49.99995231628418,-0.17279249514032632,1739502689.744962,49.99995231628418,-0.05191566893712006,1739502689.7449636,49.99995231628418,2.1772372047120543,1739502689.744966,49.99995231628418,0.0,1739502689.7449677,49.99995231628418,0.2553097353508902,1739502689.7449694,49.99995231628418,3.1511590265545477,1739502689.7449713,49.99995231628418,1.921927469361164 +1739502689.7681718,50.01995229721069,34.91100862753623,1739502689.7681768,50.01995229721069,-0.1895731496161419,1739502689.7681832,50.01995229721069,77.44878282789055,1739502689.7681892,50.01995229721069,29.978681869792425,1739502689.7681918,50.01995229721069,-0.06276914858104271,1739502689.7681956,50.01995229721069,3.115889556104488,1739502689.7681985,50.01995229721069,-0.15427954692210352,1739502689.768201,50.01995229721069,-0.04866770269781849,1739502689.768204,50.01995229721069,2.209722836544501,1739502689.7682073,50.01995229721069,0.0,1739502689.7682102,50.01995229721069,0.2619113077850946,1739502689.768213,50.01995229721069,3.147163585334509,1739502689.768216,50.01995229721069,1.9498745214976987 +1739502689.7847745,50.03995227813721,34.91100862753623,1739502689.7847788,50.03995227813721,-0.1895731496161419,1739502689.7847831,50.03995227813721,77.44878282789055,1739502689.7847872,50.03995227813721,29.978681869792425,1739502689.784789,50.03995227813721,-0.06276914858104271,1739502689.7847912,50.03995227813721,3.115889556104488,1739502689.784793,50.03995227813721,-0.15427954692210352,1739502689.7847946,50.03995227813721,-0.04866770269781849,1739502689.7847962,50.03995227813721,2.209722836544501,1739502689.784798,50.03995227813721,0.0,1739502689.7848,50.03995227813721,0.2598483150468023,1739502689.784802,50.03995227813721,3.147163585334509,1739502689.7848039,50.03995227813721,1.9498745214976987 +1739502689.804338,50.05995225906372,34.91100862753623,1739502689.8043401,50.05995225906372,-0.1895731496161419,1739502689.804343,50.05995225906372,77.44878282789055,1739502689.8043456,50.05995225906372,29.978681869792425,1739502689.8043468,50.05995225906372,-0.06276914858104271,1739502689.8043487,50.05995225906372,3.115889556104488,1739502689.80435,50.05995225906372,-0.15427954692210352,1739502689.8043513,50.05995225906372,-0.04866770269781849,1739502689.8043525,50.05995225906372,2.209722836544501,1739502689.804354,50.05995225906372,0.0,1739502689.8043554,50.05995225906372,0.2598483150468023,1739502689.8043566,50.05995225906372,3.147163585334509,1739502689.804358,50.05995225906372,1.9498745214976987 +1739502689.8248937,50.079952239990234,34.91100862753623,1739502689.8248963,50.079952239990234,-0.1895731496161419,1739502689.8248994,50.079952239990234,77.44878282789055,1739502689.8249018,50.079952239990234,29.978681869792425,1739502689.8249032,50.079952239990234,-0.06276914858104271,1739502689.8249047,50.079952239990234,3.115889556104488,1739502689.8249059,50.079952239990234,-0.15427954692210352,1739502689.8249073,50.079952239990234,-0.04866770269781849,1739502689.8249085,50.079952239990234,2.209722836544501,1739502689.8249102,50.079952239990234,0.0,1739502689.824911,50.079952239990234,0.2598483150468023,1739502689.8249125,50.079952239990234,3.147163585334509,1739502689.824914,50.079952239990234,1.9498745214976987 +1739502689.8443222,50.09995222091675,34.91100862753623,1739502689.8443244,50.09995222091675,-0.1895731496161419,1739502689.8443272,50.09995222091675,77.44878282789055,1739502689.8443298,50.09995222091675,29.978681869792425,1739502689.844331,50.09995222091675,-0.06276914858104271,1739502689.8443327,50.09995222091675,3.115889556104488,1739502689.8443341,50.09995222091675,-0.15427954692210352,1739502689.8443353,50.09995222091675,-0.04866770269781849,1739502689.8443367,50.09995222091675,2.209722836544501,1739502689.8443384,50.09995222091675,0.0,1739502689.8443396,50.09995222091675,0.2598483150468023,1739502689.8443413,50.09995222091675,3.147163585334509,1739502689.8443425,50.09995222091675,1.9498745214976987 +1739502689.8647738,50.11995220184326,34.69510227372672,1739502689.8647761,50.11995220184326,-0.19039658738715914,1739502689.8647792,50.11995220184326,77.72242867794583,1739502689.8647826,50.11995220184326,29.648200639415304,1739502689.8647838,50.11995220184326,-0.05943637009510408,1739502689.8647854,50.11995220184326,3.1156498384877604,1739502689.8647866,50.11995220184326,-0.13977516036765456,1739502689.8647883,50.11995220184326,-0.04211343673079831,1739502689.8647895,50.11995220184326,2.2355127130745704,1739502689.8647912,50.11995220184326,0.0,1739502689.8647923,50.11995220184326,0.256011631831452,1739502689.8647935,50.11995220184326,3.143339298949896,1739502689.8647952,50.11995220184326,1.9783021169522192 +1739502689.8841782,50.139952182769775,34.69510227372672,1739502689.8841808,50.139952182769775,-0.19039658738715914,1739502689.8841836,50.139952182769775,77.72242867794583,1739502689.8841863,50.139952182769775,29.648200639415304,1739502689.8841877,50.139952182769775,-0.05943637009510408,1739502689.8841894,50.139952182769775,3.1156498384877604,1739502689.8841908,50.139952182769775,-0.13977516036765456,1739502689.884192,50.139952182769775,-0.04211343673079831,1739502689.8841932,50.139952182769775,2.2355127130745704,1739502689.884195,50.139952182769775,0.0,1739502689.8841963,50.139952182769775,0.2572105961223512,1739502689.8841977,50.139952182769775,3.143339298949896,1739502689.884199,50.139952182769775,1.9783021169522192 +1739502689.9043543,50.15995216369629,34.69510227372672,1739502689.9043572,50.15995216369629,-0.19039658738715914,1739502689.9043603,50.15995216369629,77.72242867794583,1739502689.9043636,50.15995216369629,29.648200639415304,1739502689.9043648,50.15995216369629,-0.05943637009510408,1739502689.9043663,50.15995216369629,3.1156498384877604,1739502689.904368,50.15995216369629,-0.13977516036765456,1739502689.904369,50.15995216369629,-0.04211343673079831,1739502689.9043705,50.15995216369629,2.2355127130745704,1739502689.904372,50.15995216369629,0.0,1739502689.9043732,50.15995216369629,0.2572105961223512,1739502689.904375,50.15995216369629,3.143339298949896,1739502689.9043763,50.15995216369629,1.9783021169522192 +1739502689.9243836,50.1799521446228,34.69510227372672,1739502689.924386,50.1799521446228,-0.19039658738715914,1739502689.924389,50.1799521446228,77.72242867794583,1739502689.9243917,50.1799521446228,29.648200639415304,1739502689.924393,50.1799521446228,-0.05943637009510408,1739502689.9243948,50.1799521446228,3.1156498384877604,1739502689.9243963,50.1799521446228,-0.13977516036765456,1739502689.9243975,50.1799521446228,-0.04211343673079831,1739502689.9243991,50.1799521446228,2.2355127130745704,1739502689.9244006,50.1799521446228,0.0,1739502689.924402,50.1799521446228,0.2572105961223512,1739502689.9244032,50.1799521446228,3.143339298949896,1739502689.9244046,50.1799521446228,1.9783021169522192 +1739502689.9444005,50.199952125549316,34.69510227372672,1739502689.9444027,50.199952125549316,-0.19039658738715914,1739502689.9444056,50.199952125549316,77.72242867794583,1739502689.9444084,50.199952125549316,29.648200639415304,1739502689.9444096,50.199952125549316,-0.05943637009510408,1739502689.944411,50.199952125549316,3.1156498384877604,1739502689.9444125,50.199952125549316,-0.13977516036765456,1739502689.9444137,50.199952125549316,-0.04211343673079831,1739502689.944415,50.199952125549316,2.2355127130745704,1739502689.9444165,50.199952125549316,0.0,1739502689.9444177,50.199952125549316,0.2572105961223512,1739502689.9444191,50.199952125549316,3.143339298949896,1739502689.9444203,50.199952125549316,1.9783021169522192 +1739502689.964969,50.21995210647583,34.69510227372672,1739502689.9649715,50.21995210647583,-0.19039658738715914,1739502689.9649744,50.21995210647583,77.72242867794583,1739502689.9649768,50.21995210647583,29.648200639415304,1739502689.9649782,50.21995210647583,-0.05943637009510408,1739502689.96498,50.21995210647583,3.1156498384877604,1739502689.9649816,50.21995210647583,-0.13977516036765456,1739502689.9649827,50.21995210647583,-0.04211343673079831,1739502689.9649837,50.21995210647583,2.2355127130745704,1739502689.9649856,50.21995210647583,0.0,1739502689.9649866,50.21995210647583,0.2572105961223512,1739502689.9649882,50.21995210647583,3.143339298949896,1739502689.9649894,50.21995210647583,1.9783021169522192 +1739502689.9841726,50.239952087402344,34.476080565423295,1739502689.9841754,50.239952087402344,-0.1904203695067439,1739502689.984179,50.239952087402344,77.99514065593482,1739502689.9841814,50.239952087402344,29.31921236352199,1739502689.984183,50.239952087402344,-0.05732670037586979,1739502689.9841845,50.239952087402344,3.115789370614402,1739502689.9841864,50.239952087402344,-0.12386870104941357,1739502689.9841878,50.239952087402344,-0.035747114805832765,1739502689.9841893,50.239952087402344,2.2641417550481533,1739502689.9841907,50.239952087402344,0.0,1739502689.9841924,50.239952087402344,0.25791789803507964,1739502689.9841936,50.239952087402344,3.139803823684501,1739502689.984195,50.239952087402344,2.006444889005721 +1739502690.004252,50.25995206832886,34.476080565423295,1739502690.004254,50.25995206832886,-0.1904203695067439,1739502690.0042574,50.25995206832886,77.99514065593482,1739502690.00426,50.25995206832886,29.31921236352199,1739502690.0042615,50.25995206832886,-0.05732670037586979,1739502690.0042632,50.25995206832886,3.115789370614402,1739502690.0042644,50.25995206832886,-0.12386870104941357,1739502690.004266,50.25995206832886,-0.035747114805832765,1739502690.0042672,50.25995206832886,2.2641417550481533,1739502690.004269,50.25995206832886,0.0,1739502690.00427,50.25995206832886,0.25769686604243214,1739502690.0042713,50.25995206832886,3.139803823684501,1739502690.004273,50.25995206832886,2.006444889005721 +1739502690.0241,50.27995204925537,34.476080565423295,1739502690.024103,50.27995204925537,-0.1904203695067439,1739502690.0241063,50.27995204925537,77.99514065593482,1739502690.024109,50.27995204925537,29.31921236352199,1739502690.02411,50.27995204925537,-0.05732670037586979,1739502690.0241115,50.27995204925537,3.115789370614402,1739502690.0241132,50.27995204925537,-0.12386870104941357,1739502690.0241144,50.27995204925537,-0.035747114805832765,1739502690.0241156,50.27995204925537,2.2641417550481533,1739502690.0241172,50.27995204925537,0.0,1739502690.0241184,50.27995204925537,0.25769686604243214,1739502690.02412,50.27995204925537,3.139803823684501,1739502690.0241215,50.27995204925537,2.006444889005721 +1739502690.0441673,50.299952030181885,34.476080565423295,1739502690.0441709,50.299952030181885,-0.1904203695067439,1739502690.0441735,50.299952030181885,77.99514065593482,1739502690.044176,50.299952030181885,29.31921236352199,1739502690.0441778,50.299952030181885,-0.05732670037586979,1739502690.0441794,50.299952030181885,3.115789370614402,1739502690.0441806,50.299952030181885,-0.12386870104941357,1739502690.0441825,50.299952030181885,-0.035747114805832765,1739502690.0441837,50.299952030181885,2.2641417550481533,1739502690.0441856,50.299952030181885,0.0,1739502690.0441868,50.299952030181885,0.25769686604243214,1739502690.0441885,50.299952030181885,3.139803823684501,1739502690.0441897,50.299952030181885,2.006444889005721 +1739502690.0640304,50.3199520111084,34.476080565423295,1739502690.064033,50.3199520111084,-0.1904203695067439,1739502690.064036,50.3199520111084,77.99514065593482,1739502690.0640385,50.3199520111084,29.31921236352199,1739502690.0640397,50.3199520111084,-0.05732670037586979,1739502690.0640414,50.3199520111084,3.115789370614402,1739502690.0640428,50.3199520111084,-0.12386870104941357,1739502690.064044,50.3199520111084,-0.035747114805832765,1739502690.0640454,50.3199520111084,2.2641417550481533,1739502690.0640469,50.3199520111084,0.0,1739502690.064048,50.3199520111084,0.25769686604243214,1739502690.0640495,50.3199520111084,3.139803823684501,1739502690.0640507,50.3199520111084,2.006444889005721 +1739502690.0842729,50.33995199203491,34.25396206853528,1739502690.0842755,50.33995199203491,-0.18968535461211466,1739502690.084278,50.33995199203491,78.22520451277626,1739502690.0842807,50.33995199203491,29.032770539544124,1739502690.0842822,50.33995199203491,-0.055065298651631296,1739502690.0842838,50.33995199203491,3.1158149673971596,1739502690.0842853,50.33995199203491,-0.10812851297017546,1739502690.0842865,50.33995199203491,-0.030440983487960108,1739502690.0842876,50.33995199203491,2.292832428231159,1739502690.0842893,50.33995199203491,0.0,1739502690.0842905,50.33995199203491,0.2584200072232452,1739502690.0842922,50.33995199203491,3.1365191135984665,1739502690.0842934,50.33995199203491,2.0346384027750832 +1739502690.1040852,50.359951972961426,34.25396206853528,1739502690.1040878,50.359951972961426,-0.18968535461211466,1739502690.1040905,50.359951972961426,78.22520451277626,1739502690.104093,50.359951972961426,29.032770539544124,1739502690.1040945,50.359951972961426,-0.055065298651631296,1739502690.1040962,50.359951972961426,3.1158149673971596,1739502690.1040976,50.359951972961426,-0.10812851297017546,1739502690.1040988,50.359951972961426,-0.030440983487960108,1739502690.1041,50.359951972961426,2.292832428231159,1739502690.104102,50.359951972961426,0.0,1739502690.104103,50.359951972961426,0.25819402545607595,1739502690.1041045,50.359951972961426,3.1365191135984665,1739502690.104106,50.359951972961426,2.0346384027750832 +1739502690.123994,50.37995195388794,34.25396206853528,1739502690.1239963,50.37995195388794,-0.18968535461211466,1739502690.1239989,50.37995195388794,78.22520451277626,1739502690.1240015,50.37995195388794,29.032770539544124,1739502690.124003,50.37995195388794,-0.055065298651631296,1739502690.1240046,50.37995195388794,3.1158149673971596,1739502690.1240058,50.37995195388794,-0.10812851297017546,1739502690.1240072,50.37995195388794,-0.030440983487960108,1739502690.1240084,50.37995195388794,2.292832428231159,1739502690.1240103,50.37995195388794,0.0,1739502690.1240115,50.37995195388794,0.25819402545607595,1739502690.1240127,50.37995195388794,3.1365191135984665,1739502690.1240141,50.37995195388794,2.0346384027750832 +1739502690.144044,50.39995193481445,34.25396206853528,1739502690.1440465,50.39995193481445,-0.18968535461211466,1739502690.1440494,50.39995193481445,78.22520451277626,1739502690.1440523,50.39995193481445,29.032770539544124,1739502690.1440535,50.39995193481445,-0.055065298651631296,1739502690.1440556,50.39995193481445,3.1158149673971596,1739502690.1440568,50.39995193481445,-0.10812851297017546,1739502690.1440585,50.39995193481445,-0.030440983487960108,1739502690.1440597,50.39995193481445,2.292832428231159,1739502690.144061,50.39995193481445,0.0,1739502690.1440625,50.39995193481445,0.25819402545607595,1739502690.144064,50.39995193481445,3.1365191135984665,1739502690.1440654,50.39995193481445,2.0346384027750832 +1739502690.1641955,50.41995191574097,34.25396206853528,1739502690.1641982,50.41995191574097,-0.18968535461211466,1739502690.1642013,50.41995191574097,78.22520451277626,1739502690.1642041,50.41995191574097,29.032770539544124,1739502690.1642053,50.41995191574097,-0.055065298651631296,1739502690.1642072,50.41995191574097,3.1158149673971596,1739502690.1642087,50.41995191574097,-0.10812851297017546,1739502690.1642098,50.41995191574097,-0.030440983487960108,1739502690.1642113,50.41995191574097,2.292832428231159,1739502690.1642127,50.41995191574097,0.0,1739502690.1642141,50.41995191574097,0.25819402545607595,1739502690.1642158,50.41995191574097,3.1365191135984665,1739502690.164217,50.41995191574097,2.0346384027750832 +1739502690.1841202,50.43995189666748,34.25396206853528,1739502690.1841226,50.43995189666748,-0.18968535461211466,1739502690.1841257,50.43995189666748,78.22520451277626,1739502690.1841285,50.43995189666748,29.032770539544124,1739502690.18413,50.43995189666748,-0.055065298651631296,1739502690.1841319,50.43995189666748,3.1158149673971596,1739502690.184133,50.43995189666748,-0.10812851297017546,1739502690.1841345,50.43995189666748,-0.030440983487960108,1739502690.184136,50.43995189666748,2.292832428231159,1739502690.1841376,50.43995189666748,0.0,1739502690.1841388,50.43995189666748,0.25819402545607595,1739502690.18414,50.43995189666748,3.1365191135984665,1739502690.1841416,50.43995189666748,2.0346384027750832 +1739502690.2041242,50.459951877593994,34.02874000583172,1739502690.2041264,50.459951877593994,-0.18822877890861456,1739502690.2041292,50.459951877593994,78.45649230998134,1739502690.204132,50.459951877593994,28.74493891538172,1739502690.2041333,50.459951877593994,-0.0526148625246301,1739502690.2041352,50.459951877593994,3.1159323102845815,1739502690.2041364,50.459951877593994,-0.09284349709081698,1739502690.204138,50.459951877593994,-0.02552250621606478,1739502690.204139,50.459951877593994,2.321041330204237,1739502690.2041411,50.459951877593994,0.0,1739502690.2041423,50.459951877593994,0.25809478625174936,1739502690.2041435,50.459951877593994,3.1334987750664545,1739502690.204145,50.459951877593994,2.0629155316808023 +1739502690.2241273,50.47995185852051,34.02874000583172,1739502690.2241294,50.47995185852051,-0.18822877890861456,1739502690.224132,50.47995185852051,78.45649230998134,1739502690.224135,50.47995185852051,28.74493891538172,1739502690.224136,50.47995185852051,-0.0526148625246301,1739502690.2241378,50.47995185852051,3.1159323102845815,1739502690.224139,50.47995185852051,-0.09284349709081698,1739502690.2241404,50.47995185852051,-0.02552250621606478,1739502690.2241416,50.47995185852051,2.321041330204237,1739502690.224143,50.47995185852051,0.0,1739502690.2241445,50.47995185852051,0.25812579852343465,1739502690.2241457,50.47995185852051,3.1334987750664545,1739502690.224147,50.47995185852051,2.0629155316808023 +1739502690.244173,50.49995183944702,34.02874000583172,1739502690.244176,50.49995183944702,-0.18822877890861456,1739502690.244179,50.49995183944702,78.45649230998134,1739502690.2441814,50.49995183944702,28.74493891538172,1739502690.244183,50.49995183944702,-0.0526148625246301,1739502690.2441847,50.49995183944702,3.1159323102845815,1739502690.2441862,50.49995183944702,-0.09284349709081698,1739502690.2441874,50.49995183944702,-0.02552250621606478,1739502690.2441888,50.49995183944702,2.321041330204237,1739502690.2441905,50.49995183944702,0.0,1739502690.2441916,50.49995183944702,0.25812579852343465,1739502690.244193,50.49995183944702,3.1334987750664545,1739502690.2441943,50.49995183944702,2.0629155316808023 +1739502690.2642882,50.519951820373535,34.02874000583172,1739502690.2642908,50.519951820373535,-0.18822877890861456,1739502690.2642941,50.519951820373535,78.45649230998134,1739502690.2642968,50.519951820373535,28.74493891538172,1739502690.264298,50.519951820373535,-0.0526148625246301,1739502690.2642999,50.519951820373535,3.1159323102845815,1739502690.264301,50.519951820373535,-0.09284349709081698,1739502690.2643025,50.519951820373535,-0.02552250621606478,1739502690.264304,50.519951820373535,2.321041330204237,1739502690.2643054,50.519951820373535,0.0,1739502690.2643068,50.519951820373535,0.25812579852343465,1739502690.2643082,50.519951820373535,3.1334987750664545,1739502690.2643094,50.519951820373535,2.0629155316808023 +1739502690.2841313,50.53995180130005,34.02874000583172,1739502690.2841341,50.53995180130005,-0.18822877890861456,1739502690.2841368,50.53995180130005,78.45649230998134,1739502690.2841396,50.53995180130005,28.74493891538172,1739502690.284141,50.53995180130005,-0.0526148625246301,1739502690.2841425,50.53995180130005,3.1159323102845815,1739502690.2841442,50.53995180130005,-0.09284349709081698,1739502690.2841454,50.53995180130005,-0.02552250621606478,1739502690.2841468,50.53995180130005,2.321041330204237,1739502690.2841482,50.53995180130005,0.0,1739502690.2841494,50.53995180130005,0.25812579852343465,1739502690.284151,50.53995180130005,3.1334987750664545,1739502690.2841525,50.53995180130005,2.0629155316808023 +1739502690.3039985,50.55995178222656,33.800416217154975,1739502690.3040006,50.55995178222656,-0.18608077825336888,1739502690.3040032,50.55995178222656,78.60082885108949,1739502690.304006,50.55995178222656,28.54412759119331,1739502690.3040075,50.55995178222656,-0.0518880660103766,1739502690.304009,50.55995178222656,3.1160682620307636,1739502690.3040104,50.55995178222656,-0.0766509208079497,1739502690.3040118,50.55995178222656,-0.021292660198404534,1739502690.304013,50.55995178222656,2.3513038291806896,1739502690.3040147,50.55995178222656,0.0,1739502690.304016,50.55995178222656,0.2610691453225667,1739502690.3040173,50.55995178222656,3.130646736140144,1739502690.304019,50.55995178222656,2.091154480335917 +1739502690.3239787,50.579951763153076,33.800416217154975,1739502690.3239808,50.579951763153076,-0.18608077825336888,1739502690.3239837,50.579951763153076,78.60082885108949,1739502690.3239865,50.579951763153076,28.54412759119331,1739502690.3239877,50.579951763153076,-0.0518880660103766,1739502690.3239894,50.579951763153076,3.1160682620307636,1739502690.3239913,50.579951763153076,-0.0766509208079497,1739502690.3239925,50.579951763153076,-0.021292660198404534,1739502690.323994,50.579951763153076,2.3513038291806896,1739502690.3239954,50.579951763153076,0.0,1739502690.3239968,50.579951763153076,0.26014934884477237,1739502690.323998,50.579951763153076,3.130646736140144,1739502690.3239994,50.579951763153076,2.091154480335917 +1739502690.3439384,50.59995174407959,33.800416217154975,1739502690.3439405,50.59995174407959,-0.18608077825336888,1739502690.3439434,50.59995174407959,78.60082885108949,1739502690.3439462,50.59995174407959,28.54412759119331,1739502690.3439472,50.59995174407959,-0.0518880660103766,1739502690.343949,50.59995174407959,3.1160682620307636,1739502690.3439505,50.59995174407959,-0.0766509208079497,1739502690.343952,50.59995174407959,-0.021292660198404534,1739502690.3439531,50.59995174407959,2.3513038291806896,1739502690.3439548,50.59995174407959,0.0,1739502690.343956,50.59995174407959,0.26014934884477237,1739502690.3439572,50.59995174407959,3.130646736140144,1739502690.3439586,50.59995174407959,2.091154480335917 +1739502690.3641143,50.6199517250061,33.800416217154975,1739502690.3641164,50.6199517250061,-0.18608077825336888,1739502690.3641193,50.6199517250061,78.60082885108949,1739502690.3641224,50.6199517250061,28.54412759119331,1739502690.3641236,50.6199517250061,-0.0518880660103766,1739502690.3641257,50.6199517250061,3.1160682620307636,1739502690.364127,50.6199517250061,-0.0766509208079497,1739502690.3641286,50.6199517250061,-0.021292660198404534,1739502690.3641298,50.6199517250061,2.3513038291806896,1739502690.3641317,50.6199517250061,0.0,1739502690.364133,50.6199517250061,0.26014934884477237,1739502690.3641343,50.6199517250061,3.130646736140144,1739502690.364136,50.6199517250061,2.091154480335917 +1739502690.3840892,50.63995170593262,33.800416217154975,1739502690.3840916,50.63995170593262,-0.18608077825336888,1739502690.3840947,50.63995170593262,78.60082885108949,1739502690.3840976,50.63995170593262,28.54412759119331,1739502690.3840988,50.63995170593262,-0.0518880660103766,1739502690.3841007,50.63995170593262,3.1160682620307636,1739502690.384102,50.63995170593262,-0.0766509208079497,1739502690.384104,50.63995170593262,-0.021292660198404534,1739502690.3841054,50.63995170593262,2.3513038291806896,1739502690.3841074,50.63995170593262,0.0,1739502690.3841085,50.63995170593262,0.26014934884477237,1739502690.38411,50.63995170593262,3.130646736140144,1739502690.384112,50.63995170593262,2.091154480335917 +1739502690.404062,50.65995168685913,33.800416217154975,1739502690.4040642,50.65995168685913,-0.18608077825336888,1739502690.4040673,50.65995168685913,78.60082885108949,1739502690.4040704,50.65995168685913,28.54412759119331,1739502690.404072,50.65995168685913,-0.0518880660103766,1739502690.4040737,50.65995168685913,3.1160682620307636,1739502690.4040751,50.65995168685913,-0.0766509208079497,1739502690.4040766,50.65995168685913,-0.021292660198404534,1739502690.404078,50.65995168685913,2.3513038291806896,1739502690.40408,50.65995168685913,0.0,1739502690.404081,50.65995168685913,0.26014934884477237,1739502690.4040828,50.65995168685913,3.130646736140144,1739502690.4040842,50.65995168685913,2.091154480335917 +1739502690.4241607,50.679951667785645,33.56897776872049,1739502690.4241633,50.679951667785645,-0.18326718634979677,1739502690.4241662,50.679951667785645,79.03121630681837,1739502690.424169,50.679951667785645,28.056750784508694,1739502690.4241707,50.679951667785645,-0.048,1739502690.4241724,50.679951667785645,3.1170580971325292,1739502690.4241738,50.679951667785645,-0.06048583571571539,1739502690.4241753,50.679951667785645,-0.015279020640665362,1739502690.4241767,50.679951667785645,2.3819085147785826,1739502690.4241784,50.679951667785645,0.0,1739502690.42418,50.679951667785645,0.2632057879486749,1739502690.4241815,50.679951667785645,3.128028045401894,1739502690.4241831,50.679951667785645,2.1196578646761144 +1739502690.4440928,50.69995164871216,33.56897776872049,1739502690.444095,50.69995164871216,-0.18326718634979677,1739502690.4440978,50.69995164871216,79.03121630681837,1739502690.4441009,50.69995164871216,28.056750784508694,1739502690.444102,50.69995164871216,-0.048,1739502690.4441042,50.69995164871216,3.1170580971325292,1739502690.4441056,50.69995164871216,-0.06048583571571539,1739502690.444107,50.69995164871216,-0.015279020640665362,1739502690.4441087,50.69995164871216,2.3819085147785826,1739502690.4441104,50.69995164871216,0.0,1739502690.4441116,50.69995164871216,0.2622506501024682,1739502690.4441133,50.69995164871216,3.128028045401894,1739502690.4441147,50.69995164871216,2.1196578646761144 +1739502690.4641225,50.71995162963867,33.56897776872049,1739502690.4641252,50.71995162963867,-0.18326718634979677,1739502690.464128,50.71995162963867,79.03121630681837,1739502690.4641309,50.71995162963867,28.056750784508694,1739502690.4641323,50.71995162963867,-0.048,1739502690.4641342,50.71995162963867,3.1170580971325292,1739502690.464136,50.71995162963867,-0.06048583571571539,1739502690.4641376,50.71995162963867,-0.015279020640665362,1739502690.4641387,50.71995162963867,2.3819085147785826,1739502690.4641407,50.71995162963867,0.0,1739502690.4641418,50.71995162963867,0.2622506501024682,1739502690.4641433,50.71995162963867,3.128028045401894,1739502690.4641447,50.71995162963867,2.1196578646761144 +1739502690.4841497,50.739951610565186,33.56897776872049,1739502690.4841523,50.739951610565186,-0.18326718634979677,1739502690.4841554,50.739951610565186,79.03121630681837,1739502690.4841585,50.739951610565186,28.056750784508694,1739502690.4841597,50.739951610565186,-0.048,1739502690.4841619,50.739951610565186,3.1170580971325292,1739502690.4841633,50.739951610565186,-0.06048583571571539,1739502690.4841647,50.739951610565186,-0.015279020640665362,1739502690.4841661,50.739951610565186,2.3819085147785826,1739502690.4841676,50.739951610565186,0.0,1739502690.4841692,50.739951610565186,0.2622506501024682,1739502690.4841704,50.739951610565186,3.128028045401894,1739502690.484172,50.739951610565186,2.1196578646761144 +1739502690.504153,50.7599515914917,33.56897776872049,1739502690.5041556,50.7599515914917,-0.18326718634979677,1739502690.5041585,50.7599515914917,79.03121630681837,1739502690.5041614,50.7599515914917,28.056750784508694,1739502690.5041628,50.7599515914917,-0.048,1739502690.5041647,50.7599515914917,3.1170580971325292,1739502690.504166,50.7599515914917,-0.06048583571571539,1739502690.5041673,50.7599515914917,-0.015279020640665362,1739502690.5041687,50.7599515914917,2.3819085147785826,1739502690.5041704,50.7599515914917,0.0,1739502690.5041718,50.7599515914917,0.2622506501024682,1739502690.5041733,50.7599515914917,3.128028045401894,1739502690.504175,50.7599515914917,2.1196578646761144 +1739502690.5241694,50.77995157241821,33.33440544908093,1739502690.5241718,50.77995157241821,-0.179823037409526,1739502690.524175,50.77995157241821,79.11976146896228,1739502690.524178,50.77995157241821,27.910835537204246,1739502690.5241792,50.77995157241821,-0.04732597820534733,1739502690.524181,50.77995157241821,3.1171676508867816,1739502690.5241826,50.77995157241821,-0.04589458995530117,1739502690.5241842,50.77995157241821,-0.01197542139030188,1739502690.5241857,50.77995157241821,2.409875436120946,1739502690.5241873,50.77995157241821,0.0,1739502690.524189,50.77995157241821,0.2612039408343468,1739502690.5241904,50.77995157241821,3.125627290703294,1739502690.5241919,50.77995157241821,2.14834439842585 +1739502690.5440845,50.79995155334473,33.33440544908093,1739502690.5440865,50.79995155334473,-0.179823037409526,1739502690.5440896,50.79995155334473,79.11976146896228,1739502690.5440927,50.79995155334473,27.910835537204246,1739502690.5440943,50.79995155334473,-0.04732597820534733,1739502690.5440958,50.79995155334473,3.1171676508867816,1739502690.5440972,50.79995155334473,-0.04589458995530117,1739502690.5440986,50.79995155334473,-0.01197542139030188,1739502690.5441,50.79995155334473,2.409875436120946,1739502690.5441017,50.79995155334473,0.0,1739502690.5441031,50.79995155334473,0.2615310376950961,1739502690.5441048,50.79995155334473,3.125627290703294,1739502690.544106,50.79995155334473,2.14834439842585 +1739502690.5641193,50.81995153427124,33.33440544908093,1739502690.564122,50.81995153427124,-0.179823037409526,1739502690.5641248,50.81995153427124,79.11976146896228,1739502690.5641277,50.81995153427124,27.910835537204246,1739502690.5641294,50.81995153427124,-0.04732597820534733,1739502690.564131,50.81995153427124,3.1171676508867816,1739502690.5641327,50.81995153427124,-0.04589458995530117,1739502690.5641341,50.81995153427124,-0.01197542139030188,1739502690.5641353,50.81995153427124,2.409875436120946,1739502690.5641372,50.81995153427124,0.0,1739502690.5641384,50.81995153427124,0.2615310376950961,1739502690.56414,50.81995153427124,3.125627290703294,1739502690.5641418,50.81995153427124,2.14834439842585 +1739502690.5841174,50.839951515197754,33.33440544908093,1739502690.5841203,50.839951515197754,-0.179823037409526,1739502690.5841231,50.839951515197754,79.11976146896228,1739502690.5841265,50.839951515197754,27.910835537204246,1739502690.584128,50.839951515197754,-0.04732597820534733,1739502690.5841298,50.839951515197754,3.1171676508867816,1739502690.584131,50.839951515197754,-0.04589458995530117,1739502690.5841327,50.839951515197754,-0.01197542139030188,1739502690.584134,50.839951515197754,2.409875436120946,1739502690.5841358,50.839951515197754,0.0,1739502690.584137,50.839951515197754,0.2615310376950961,1739502690.5841384,50.839951515197754,3.125627290703294,1739502690.58414,50.839951515197754,2.14834439842585 +1739502690.6040754,50.85995149612427,33.33440544908093,1739502690.6040778,50.85995149612427,-0.179823037409526,1739502690.604081,50.85995149612427,79.11976146896228,1739502690.6040838,50.85995149612427,27.910835537204246,1739502690.6040852,50.85995149612427,-0.04732597820534733,1739502690.604087,50.85995149612427,3.1171676508867816,1739502690.6040885,50.85995149612427,-0.04589458995530117,1739502690.6040897,50.85995149612427,-0.01197542139030188,1739502690.6040912,50.85995149612427,2.409875436120946,1739502690.6040928,50.85995149612427,0.0,1739502690.6040943,50.85995149612427,0.2615310376950961,1739502690.6040957,50.85995149612427,3.125627290703294,1739502690.6040974,50.85995149612427,2.14834439842585 +1739502690.624129,50.87995147705078,33.33440544908093,1739502690.624132,50.87995147705078,-0.179823037409526,1739502690.624135,50.87995147705078,79.11976146896228,1739502690.6241376,50.87995147705078,27.910835537204246,1739502690.624139,50.87995147705078,-0.04732597820534733,1739502690.6241407,50.87995147705078,3.1171676508867816,1739502690.6241426,50.87995147705078,-0.04589458995530117,1739502690.624144,50.87995147705078,-0.01197542139030188,1739502690.6241455,50.87995147705078,2.409875436120946,1739502690.6241472,50.87995147705078,0.0,1739502690.6241488,50.87995147705078,0.2615310376950961,1739502690.62415,50.87995147705078,3.125627290703294,1739502690.6241515,50.87995147705078,2.14834439842585 +1739502690.6441057,50.899951457977295,33.096688077958035,1739502690.644108,50.899951457977295,-0.1757871597310352,1739502690.6441112,50.899951457977295,79.40551905049514,1739502690.6441143,50.899951457977295,27.56783274694699,1739502690.6441154,50.899951457977295,-0.045,1739502690.6441174,50.899951457977295,3.1179416869913603,1739502690.644119,50.899951457977295,-0.03034933497396325,1739502690.6441202,50.899951457977295,-0.007620720950573954,1739502690.644122,50.899951457977295,2.440032268212659,1739502690.6441233,50.899951457977295,0.0,1739502690.644125,50.899951457977295,0.26375433510648855,1739502690.6441262,50.899951457977295,3.1234294412578274,1739502690.6441278,50.899951457977295,2.1769727140027646 +1739502690.6641107,50.91995143890381,33.096688077958035,1739502690.664113,50.91995143890381,-0.1757871597310352,1739502690.664116,50.91995143890381,79.40551905049514,1739502690.664119,50.91995143890381,27.56783274694699,1739502690.6641204,50.91995143890381,-0.045,1739502690.664122,50.91995143890381,3.1179416869913603,1739502690.6641235,50.91995143890381,-0.03034933497396325,1739502690.6641254,50.91995143890381,-0.007620720950573954,1739502690.6641266,50.91995143890381,2.440032268212659,1739502690.6641285,50.91995143890381,0.0,1739502690.6641297,50.91995143890381,0.2630595542098946,1739502690.6641316,50.91995143890381,3.1234294412578274,1739502690.664133,50.91995143890381,2.1769727140027646 +1739502690.6840827,50.93995141983032,33.096688077958035,1739502690.6840851,50.93995141983032,-0.1757871597310352,1739502690.684088,50.93995141983032,79.40551905049514,1739502690.6840909,50.93995141983032,27.56783274694699,1739502690.6840925,50.93995141983032,-0.045,1739502690.684094,50.93995141983032,3.1179416869913603,1739502690.6840954,50.93995141983032,-0.03034933497396325,1739502690.684097,50.93995141983032,-0.007620720950573954,1739502690.6840982,50.93995141983032,2.440032268212659,1739502690.6841002,50.93995141983032,0.0,1739502690.6841013,50.93995141983032,0.2630595542098946,1739502690.684103,50.93995141983032,3.1234294412578274,1739502690.6841047,50.93995141983032,2.1769727140027646 +1739502690.7040408,50.959951400756836,33.096688077958035,1739502690.7040436,50.959951400756836,-0.1757871597310352,1739502690.7040465,50.959951400756836,79.40551905049514,1739502690.7040493,50.959951400756836,27.56783274694699,1739502690.704051,50.959951400756836,-0.045,1739502690.7040527,50.959951400756836,3.1179416869913603,1739502690.704054,50.959951400756836,-0.03034933497396325,1739502690.7040555,50.959951400756836,-0.007620720950573954,1739502690.704057,50.959951400756836,2.440032268212659,1739502690.7040586,50.959951400756836,0.0,1739502690.70406,50.959951400756836,0.2630595542098946,1739502690.7040617,50.959951400756836,3.1234294412578274,1739502690.7040632,50.959951400756836,2.1769727140027646 +1739502690.7241626,50.97995138168335,33.096688077958035,1739502690.724166,50.97995138168335,-0.1757871597310352,1739502690.7241695,50.97995138168335,79.40551905049514,1739502690.7241728,50.97995138168335,27.56783274694699,1739502690.7241743,50.97995138168335,-0.045,1739502690.7241764,50.97995138168335,3.1179416869913603,1739502690.7241778,50.97995138168335,-0.03034933497396325,1739502690.7241795,50.97995138168335,-0.007620720950573954,1739502690.7241807,50.97995138168335,2.440032268212659,1739502690.7241828,50.97995138168335,0.0,1739502690.724184,50.97995138168335,0.2630595542098946,1739502690.7241857,50.97995138168335,3.1234294412578274,1739502690.7241874,50.97995138168335,2.1769727140027646 +1739502690.7442873,50.99995136260986,32.85582535440744,1739502690.7442899,50.99995136260986,-0.17118309209302485,1739502690.7442932,50.99995136260986,79.64832285025864,1739502690.7442966,50.99995136260986,27.267493374646957,1739502690.744298,50.99995136260986,-0.04275133756663229,1739502690.7443001,50.99995136260986,3.118614571661446,1739502690.7443016,50.99995136260986,-0.01543617397742306,1739502690.744303,50.99995136260986,-0.003794083924986035,1739502690.7443047,50.99995136260986,2.469317490182107,1739502690.7443063,50.99995136260986,0.0,1739502690.7443082,50.99995136260986,0.26380383977379473,1739502690.7443097,50.99995136260986,3.1213760609101637,1739502690.744312,50.99995136260986,2.2057462397995287 +1739502690.7654958,51.01995134353638,32.85582535440744,1739502690.7654994,51.01995134353638,-0.17118309209302485,1739502690.7655034,51.01995134353638,79.64832285025864,1739502690.7655077,51.01995134353638,27.267493374646957,1739502690.7655094,51.01995134353638,-0.04275133756663229,1739502690.7655118,51.01995134353638,3.118614571661446,1739502690.7655137,51.01995134353638,-0.01543617397742306,1739502690.7655158,51.01995134353638,-0.003794083924986035,1739502690.7655175,51.01995134353638,2.469317490182107,1739502690.7655199,51.01995134353638,0.0,1739502690.7655218,51.01995134353638,0.26357125038257845,1739502690.7655237,51.01995134353638,3.1213760609101637,1739502690.7655258,51.01995134353638,2.2057462397995287 +1739502690.7849607,51.03995132446289,32.85582535440744,1739502690.7849648,51.03995132446289,-0.17118309209302485,1739502690.7849693,51.03995132446289,79.64832285025864,1739502690.7849734,51.03995132446289,27.267493374646957,1739502690.784975,51.03995132446289,-0.04275133756663229,1739502690.7849777,51.03995132446289,3.118614571661446,1739502690.7849798,51.03995132446289,-0.01543617397742306,1739502690.784982,51.03995132446289,-0.003794083924986035,1739502690.7849839,51.03995132446289,2.469317490182107,1739502690.7849863,51.03995132446289,0.0,1739502690.7849884,51.03995132446289,0.26357125038257845,1739502690.7849905,51.03995132446289,3.1213760609101637,1739502690.7849925,51.03995132446289,2.2057462397995287 +1739502690.8049102,51.059951305389404,32.85582535440744,1739502690.804914,51.059951305389404,-0.17118309209302485,1739502690.804918,51.059951305389404,79.64832285025864,1739502690.804922,51.059951305389404,27.267493374646957,1739502690.8049242,51.059951305389404,-0.04275133756663229,1739502690.8049266,51.059951305389404,3.118614571661446,1739502690.8049288,51.059951305389404,-0.01543617397742306,1739502690.8049312,51.059951305389404,-0.003794083924986035,1739502690.8049328,51.059951305389404,2.469317490182107,1739502690.8049352,51.059951305389404,0.0,1739502690.804937,51.059951305389404,0.26357125038257845,1739502690.8049393,51.059951305389404,3.1213760609101637,1739502690.8049414,51.059951305389404,2.2057462397995287 +1739502690.82465,51.07995128631592,32.85582535440744,1739502690.8246531,51.07995128631592,-0.17118309209302485,1739502690.8246572,51.07995128631592,79.64832285025864,1739502690.8246613,51.07995128631592,27.267493374646957,1739502690.8246634,51.07995128631592,-0.04275133756663229,1739502690.8246655,51.07995128631592,3.118614571661446,1739502690.8246677,51.07995128631592,-0.01543617397742306,1739502690.8246694,51.07995128631592,-0.003794083924986035,1739502690.8246984,51.07995128631592,2.469317490182107,1739502690.824701,51.07995128631592,0.0,1739502690.824703,51.07995128631592,0.26357125038257845,1739502690.8247051,51.07995128631592,3.1213760609101637,1739502690.824707,51.07995128631592,2.2057462397995287 +1739502690.8449268,51.09995126724243,32.85582535440744,1739502690.8449306,51.09995126724243,-0.17118309209302485,1739502690.844935,51.09995126724243,79.64832285025864,1739502690.8449388,51.09995126724243,27.267493374646957,1739502690.844941,51.09995126724243,-0.04275133756663229,1739502690.8449433,51.09995126724243,3.118614571661446,1739502690.8449454,51.09995126724243,-0.01543617397742306,1739502690.8449473,51.09995126724243,-0.003794083924986035,1739502690.8449492,51.09995126724243,2.469317490182107,1739502690.8449516,51.09995126724243,0.0,1739502690.8449538,51.09995126724243,0.26357125038257845,1739502690.844956,51.09995126724243,3.1213760609101637,1739502690.8449583,51.09995126724243,2.2057462397995287 +1739502690.8648453,51.119951248168945,32.61180155334639,1739502690.8648486,51.119951248168945,-0.16603769365779986,1739502690.8648527,51.119951248168945,79.8015185458351,1739502690.8648565,51.119951248168945,27.056585622946418,1739502690.8648586,51.119951248168945,-0.040687142026785604,1739502690.8648615,51.119951248168945,3.119032003314072,1739502690.8648632,51.119951248168945,-0.0025761554388720625,1739502690.8648658,51.119951248168945,-0.0006407820253406622,1739502690.8648672,51.119951248168945,2.494852994738282,1739502690.8648696,51.119951248168945,0.0,1739502690.8648715,51.119951248168945,0.25873396957061007,1739502690.8648734,51.119951248168945,3.1194956216471166,1739502690.8648756,51.119951248168945,2.234607373922816 +1739502690.8849585,51.13995122909546,32.61180155334639,1739502690.8849626,51.13995122909546,-0.16603769365779986,1739502690.884967,51.13995122909546,79.8015185458351,1739502690.8849714,51.13995122909546,27.056585622946418,1739502690.884973,51.13995122909546,-0.040687142026785604,1739502690.884976,51.13995122909546,3.119032003314072,1739502690.8849778,51.13995122909546,-0.0025761554388720625,1739502690.8849797,51.13995122909546,-0.0006407820253406622,1739502690.8849819,51.13995122909546,2.494852994738282,1739502690.884984,51.13995122909546,0.0,1739502690.884986,51.13995122909546,0.260245620815466,1739502690.8849878,51.13995122909546,3.1194956216471166,1739502690.88499,51.13995122909546,2.234607373922816 +1739502690.904788,51.15995121002197,32.61180155334639,1739502690.9047918,51.15995121002197,-0.16603769365779986,1739502690.904796,51.15995121002197,79.8015185458351,1739502690.9048,51.15995121002197,27.056585622946418,1739502690.9048018,51.15995121002197,-0.040687142026785604,1739502690.9048047,51.15995121002197,3.119032003314072,1739502690.9048069,51.15995121002197,-0.0025761554388720625,1739502690.9048088,51.15995121002197,-0.0006407820253406622,1739502690.9048107,51.15995121002197,2.494852994738282,1739502690.904813,51.15995121002197,0.0,1739502690.9048152,51.15995121002197,0.260245620815466,1739502690.904817,51.15995121002197,3.1194956216471166,1739502690.9048193,51.15995121002197,2.234607373922816 +1739502690.9253092,51.179951190948486,32.61180155334639,1739502690.9253135,51.179951190948486,-0.16603769365779986,1739502690.9253187,51.179951190948486,79.8015185458351,1739502690.925323,51.179951190948486,27.056585622946418,1739502690.9253254,51.179951190948486,-0.040687142026785604,1739502690.925328,51.179951190948486,3.119032003314072,1739502690.9253302,51.179951190948486,-0.0025761554388720625,1739502690.9253325,51.179951190948486,-0.0006407820253406622,1739502690.9253342,51.179951190948486,2.494852994738282,1739502690.9253368,51.179951190948486,0.0,1739502690.925339,51.179951190948486,0.260245620815466,1739502690.9253411,51.179951190948486,3.1194956216471166,1739502690.9253435,51.179951190948486,2.234607373922816 +1739502690.944809,51.199951171875,32.61180155334639,1739502690.944813,51.199951171875,-0.16603769365779986,1739502690.9448173,51.199951171875,79.8015185458351,1739502690.9448214,51.199951171875,27.056585622946418,1739502690.9448233,51.199951171875,-0.040687142026785604,1739502690.9448256,51.199951171875,3.119032003314072,1739502690.9448276,51.199951171875,-0.0025761554388720625,1739502690.9448295,51.199951171875,-0.0006407820253406622,1739502690.9448314,51.199951171875,2.494852994738282,1739502690.9448338,51.199951171875,0.0,1739502690.944836,51.199951171875,0.260245620815466,1739502690.9448378,51.199951171875,3.1194956216471166,1739502690.94484,51.199951171875,2.234607373922816 +1739502690.9650528,51.219951152801514,32.36463428162872,1739502690.9650567,51.219951152801514,-0.1603760952745512,1739502690.9650612,51.219951152801514,80.46593248689672,1739502690.965065,51.219951152801514,26.335266562392864,1739502690.965067,51.219951152801514,-0.034214748339759855,1739502690.9650695,51.219951152801514,3.120671232789941,1739502690.9650717,51.219951152801514,0.017562625554074618,1739502690.9650733,51.219951152801514,0.003708658041234065,1739502690.9650753,51.219951152801514,2.465120353940889,1739502690.9650779,51.219951152801514,0.0,1739502690.9650798,51.219951152801514,0.17559074328281718,1739502690.965082,51.219951152801514,3.1177590191550646,1739502690.965084,51.219951152801514,2.263074944084088 +1739502690.9850488,51.23995113372803,32.36463428162872,1739502690.9850526,51.23995113372803,-0.1603760952745512,1739502690.9850569,51.23995113372803,80.46593248689672,1739502690.9850607,51.23995113372803,26.335266562392864,1739502690.9850626,51.23995113372803,-0.034214748339759855,1739502690.9850657,51.23995113372803,3.120671232789941,1739502690.9850676,51.23995113372803,0.017562625554074618,1739502690.9850695,51.23995113372803,0.003708658041234065,1739502690.9850714,51.23995113372803,2.465120353940889,1739502690.9850736,51.23995113372803,0.0,1739502690.9850757,51.23995113372803,0.20204540985680097,1739502690.9850779,51.23995113372803,3.1177590191550646,1739502690.9850795,51.23995113372803,2.263074944084088 +1739502691.0049021,51.25995111465454,32.36463428162872,1739502691.0049057,51.25995111465454,-0.1603760952745512,1739502691.0049095,51.25995111465454,80.46593248689672,1739502691.0049136,51.25995111465454,26.335266562392864,1739502691.0049157,51.25995111465454,-0.034214748339759855,1739502691.0049183,51.25995111465454,3.120671232789941,1739502691.0049202,51.25995111465454,0.017562625554074618,1739502691.0049224,51.25995111465454,0.003708658041234065,1739502691.0049243,51.25995111465454,2.465120353940889,1739502691.0049267,51.25995111465454,0.0,1739502691.0049286,51.25995111465454,0.20204540985680097,1739502691.0049305,51.25995111465454,3.1177590191550646,1739502691.0049326,51.25995111465454,2.263074944084088 +1739502691.0250437,51.279951095581055,32.36463428162872,1739502691.0250473,51.279951095581055,-0.1603760952745512,1739502691.025052,51.279951095581055,80.46593248689672,1739502691.025056,51.279951095581055,26.335266562392864,1739502691.025058,51.279951095581055,-0.034214748339759855,1739502691.0250607,51.279951095581055,3.120671232789941,1739502691.0250626,51.279951095581055,0.017562625554074618,1739502691.0250645,51.279951095581055,0.003708658041234065,1739502691.0250661,51.279951095581055,2.465120353940889,1739502691.0250688,51.279951095581055,0.0,1739502691.025071,51.279951095581055,0.20204540985680097,1739502691.0250728,51.279951095581055,3.1177590191550646,1739502691.025075,51.279951095581055,2.263074944084088 +1739502691.0447888,51.29995107650757,32.36463428162872,1739502691.044793,51.29995107650757,-0.1603760952745512,1739502691.0447972,51.29995107650757,80.46593248689672,1739502691.044801,51.29995107650757,26.335266562392864,1739502691.0448031,51.29995107650757,-0.034214748339759855,1739502691.0448055,51.29995107650757,3.120671232789941,1739502691.0448077,51.29995107650757,0.017562625554074618,1739502691.0448098,51.29995107650757,0.003708658041234065,1739502691.0448117,51.29995107650757,2.465120353940889,1739502691.0448143,51.29995107650757,0.0,1739502691.044816,51.29995107650757,0.20204540985680097,1739502691.0448182,51.29995107650757,3.1177590191550646,1739502691.0448208,51.29995107650757,2.263074944084088 +1739502691.0651822,51.31995105743408,32.36463428162872,1739502691.0651865,51.31995105743408,-0.1603760952745512,1739502691.065191,51.31995105743408,80.46593248689672,1739502691.065195,51.31995105743408,26.335266562392864,1739502691.065197,51.31995105743408,-0.034214748339759855,1739502691.0651996,51.31995105743408,3.120671232789941,1739502691.0652018,51.31995105743408,0.017562625554074618,1739502691.065204,51.31995105743408,0.003708658041234065,1739502691.0652058,51.31995105743408,2.465120353940889,1739502691.0652084,51.31995105743408,0.0,1739502691.06521,51.31995105743408,0.20204540985680097,1739502691.0652125,51.31995105743408,3.1177590191550646,1739502691.0652142,51.31995105743408,2.263074944084088 +1739502691.085066,51.339951038360596,32.11471340858202,1739502691.0850697,51.339951038360596,-0.15423809585907744,1739502691.085074,51.339951038360596,81.02492231221314,1739502691.085078,51.339951038360596,25.733103284168166,1739502691.08508,51.339951038360596,-0.030009429779215092,1739502691.0850823,51.339951038360596,3.122128447060251,1739502691.0850844,51.339951038360596,0.03787023694945271,1739502691.085086,51.339951038360596,0.00713893358183572,1739502691.0850883,51.339951038360596,2.4253953506922294,1739502691.0850906,51.339951038360596,0.0,1739502691.0850925,51.339951038360596,0.11285269688119451,1739502691.0850947,51.339951038360596,3.116195260150512,1739502691.0850966,51.339951038360596,2.2846699127313648 +1739502691.1047904,51.35995101928711,32.11471340858202,1739502691.104794,51.35995101928711,-0.15423809585907744,1739502691.1047988,51.35995101928711,81.02492231221314,1739502691.1048026,51.35995101928711,25.733103284168166,1739502691.1048045,51.35995101928711,-0.030009429779215092,1739502691.1048071,51.35995101928711,3.122128447060251,1739502691.104809,51.35995101928711,0.03787023694945271,1739502691.1048112,51.35995101928711,0.00713893358183572,1739502691.104813,51.35995101928711,2.4253953506922294,1739502691.1048152,51.35995101928711,0.0,1739502691.1048172,51.35995101928711,0.14072543796086467,1739502691.1048195,51.35995101928711,3.116195260150512,1739502691.1048214,51.35995101928711,2.2846699127313648 +1739502691.1251829,51.37995100021362,32.11471340858202,1739502691.1251876,51.37995100021362,-0.15423809585907744,1739502691.1251917,51.37995100021362,81.02492231221314,1739502691.1251962,51.37995100021362,25.733103284168166,1739502691.1251984,51.37995100021362,-0.030009429779215092,1739502691.1252007,51.37995100021362,3.122128447060251,1739502691.1252031,51.37995100021362,0.03787023694945271,1739502691.1252053,51.37995100021362,0.00713893358183572,1739502691.1252072,51.37995100021362,2.4253953506922294,1739502691.1252096,51.37995100021362,0.0,1739502691.125212,51.37995100021362,0.14072543796086467,1739502691.1252139,51.37995100021362,3.116195260150512,1739502691.1252162,51.37995100021362,2.2846699127313648 +1739502691.1448176,51.39995098114014,32.11471340858202,1739502691.1448212,51.39995098114014,-0.15423809585907744,1739502691.1448257,51.39995098114014,81.02492231221314,1739502691.14483,51.39995098114014,25.733103284168166,1739502691.144832,51.39995098114014,-0.030009429779215092,1739502691.1448345,51.39995098114014,3.122128447060251,1739502691.144837,51.39995098114014,0.03787023694945271,1739502691.1448393,51.39995098114014,0.00713893358183572,1739502691.144841,51.39995098114014,2.4253953506922294,1739502691.1448433,51.39995098114014,0.0,1739502691.1448452,51.39995098114014,0.14072543796086467,1739502691.1448474,51.39995098114014,3.116195260150512,1739502691.1448493,51.39995098114014,2.2846699127313648 +1739502691.1650324,51.41995096206665,32.11471340858202,1739502691.1650362,51.41995096206665,-0.15423809585907744,1739502691.1650407,51.41995096206665,81.02492231221314,1739502691.1650448,51.41995096206665,25.733103284168166,1739502691.1650467,51.41995096206665,-0.030009429779215092,1739502691.1650493,51.41995096206665,3.122128447060251,1739502691.165052,51.41995096206665,0.03787023694945271,1739502691.1650538,51.41995096206665,0.00713893358183572,1739502691.1650558,51.41995096206665,2.4253953506922294,1739502691.1650581,51.41995096206665,0.0,1739502691.1650603,51.41995096206665,0.14072543796086467,1739502691.1650627,51.41995096206665,3.116195260150512,1739502691.1650648,51.41995096206665,2.2846699127313648 +1739502691.1848614,51.439950942993164,31.86270175715927,1739502691.184865,51.439950942993164,-0.14766990451492035,1739502691.184869,51.439950942993164,81.0312226034987,1739502691.1848736,51.439950942993164,25.695924617795587,1739502691.1848752,51.439950942993164,-0.02969166339996228,1739502691.1848776,51.439950942993164,3.12246372318468,1739502691.1848795,51.439950942993164,0.047417868990137176,1739502691.1848817,51.439950942993164,0.009572521401700139,1739502691.1848834,51.439950942993164,2.4069404945953856,1739502691.1848857,51.439950942993164,0.0,1739502691.184888,51.439950942993164,0.09142400855378817,1739502691.1848898,51.439950942993164,3.114775807808298,1739502691.184892,51.439950942993164,2.300109779250462 +1739502691.2047882,51.45995092391968,31.86270175715927,1739502691.2047918,51.45995092391968,-0.14766990451492035,1739502691.204796,51.45995092391968,81.0312226034987,1739502691.2048006,51.45995092391968,25.695924617795587,1739502691.2048025,51.45995092391968,-0.02969166339996228,1739502691.2048051,51.45995092391968,3.12246372318468,1739502691.2048075,51.45995092391968,0.047417868990137176,1739502691.2048092,51.45995092391968,0.009572521401700139,1739502691.2048113,51.45995092391968,2.4069404945953856,1739502691.2048135,51.45995092391968,0.0,1739502691.2048154,51.45995092391968,0.10683071534492372,1739502691.2048173,51.45995092391968,3.114775807808298,1739502691.2048194,51.45995092391968,2.300109779250462 +1739502691.2256114,51.47995090484619,31.86270175715927,1739502691.2256148,51.47995090484619,-0.14766990451492035,1739502691.2256188,51.47995090484619,81.0312226034987,1739502691.2256231,51.47995090484619,25.695924617795587,1739502691.2256248,51.47995090484619,-0.02969166339996228,1739502691.2256274,51.47995090484619,3.12246372318468,1739502691.2256293,51.47995090484619,0.047417868990137176,1739502691.2256312,51.47995090484619,0.009572521401700139,1739502691.2256334,51.47995090484619,2.4069404945953856,1739502691.2256355,51.47995090484619,0.0,1739502691.2256374,51.47995090484619,0.10683071534492372,1739502691.2256393,51.47995090484619,3.114775807808298,1739502691.2256415,51.47995090484619,2.300109779250462 +1739502691.2439537,51.499950885772705,31.86270175715927,1739502691.2439556,51.499950885772705,-0.14766990451492035,1739502691.2439582,51.499950885772705,81.0312226034987,1739502691.2439609,51.499950885772705,25.695924617795587,1739502691.243962,51.499950885772705,-0.02969166339996228,1739502691.243964,51.499950885772705,3.12246372318468,1739502691.2439651,51.499950885772705,0.047417868990137176,1739502691.2439666,51.499950885772705,0.009572521401700139,1739502691.2439678,51.499950885772705,2.4069404945953856,1739502691.2439692,51.499950885772705,0.0,1739502691.2439706,51.499950885772705,0.10683071534492372,1739502691.2439718,51.499950885772705,3.114775807808298,1739502691.243973,51.499950885772705,2.300109779250462 +1739502691.2734618,51.529950857162476,31.86270175715927,1739502691.273466,51.529950857162476,-0.14766990451492035,1739502691.2734716,51.529950857162476,81.0312226034987,1739502691.2734768,51.529950857162476,25.695924617795587,1739502691.2734797,51.529950857162476,-0.02969166339996228,1739502691.2734835,51.529950857162476,3.12246372318468,1739502691.2734873,51.529950857162476,0.047417868990137176,1739502691.2734914,51.529950857162476,0.009572521401700139,1739502691.2734947,51.529950857162476,2.4069404945953856,1739502691.273498,51.529950857162476,0.0,1739502691.2735014,51.529950857162476,0.10683071534492372,1739502691.2735047,51.529950857162476,3.114775807808298,1739502691.2735083,51.529950857162476,2.300109779250462 +1739502691.3046396,51.559950828552246,31.6092282677087,1739502691.3046417,51.559950828552246,-0.14071877473286687,1739502691.3046448,51.559950828552246,81.03755944073498,1739502691.3046474,51.559950828552246,25.66680932906398,1739502691.3046486,51.559950828552246,-0.029442814778324628,1739502691.3046503,51.559950828552246,3.1228691409151796,1739502691.3046517,51.559950828552246,0.05589409905918539,1739502691.3046534,51.559950828552246,0.012151951099277483,1739502691.3046546,51.559950828552246,2.3906742822718496,1739502691.304656,51.559950828552246,0.0,1739502691.3046575,51.559950828552246,0.06660383820827664,1739502691.3046587,51.559950828552246,3.1134647003493026,1739502691.30466,51.559950828552246,2.3114995367162416 +1739502691.3245888,51.57995080947876,31.6092282677087,1739502691.3245912,51.57995080947876,-0.14071877473286687,1739502691.3245938,51.57995080947876,81.03755944073498,1739502691.3245962,51.57995080947876,25.66680932906398,1739502691.3245976,51.57995080947876,-0.029442814778324628,1739502691.324599,51.57995080947876,3.1228691409151796,1739502691.3246002,51.57995080947876,0.05589409905918539,1739502691.3246017,51.57995080947876,0.012151951099277483,1739502691.3246026,51.57995080947876,2.3906742822718496,1739502691.3246043,51.57995080947876,0.0,1739502691.3246055,51.57995080947876,0.079174745555608,1739502691.3246067,51.57995080947876,3.1134647003493026,1739502691.3246078,51.57995080947876,2.3114995367162416 +1739502691.3440626,51.59995079040527,31.6092282677087,1739502691.344065,51.59995079040527,-0.14071877473286687,1739502691.3440678,51.59995079040527,81.03755944073498,1739502691.3440707,51.59995079040527,25.66680932906398,1739502691.3440719,51.59995079040527,-0.029442814778324628,1739502691.3440738,51.59995079040527,3.1228691409151796,1739502691.344075,51.59995079040527,0.05589409905918539,1739502691.3440766,51.59995079040527,0.012151951099277483,1739502691.3440778,51.59995079040527,2.3906742822718496,1739502691.3440793,51.59995079040527,0.0,1739502691.3440807,51.59995079040527,0.079174745555608,1739502691.3440819,51.59995079040527,3.1134647003493026,1739502691.3440833,51.59995079040527,2.3114995367162416 +1739502691.3650887,51.61995077133179,31.6092282677087,1739502691.3650916,51.61995077133179,-0.14071877473286687,1739502691.3650942,51.61995077133179,81.03755944073498,1739502691.3650973,51.61995077133179,25.66680932906398,1739502691.3650982,51.61995077133179,-0.029442814778324628,1739502691.3651001,51.61995077133179,3.1228691409151796,1739502691.3651013,51.61995077133179,0.05589409905918539,1739502691.3651025,51.61995077133179,0.012151951099277483,1739502691.365104,51.61995077133179,2.3906742822718496,1739502691.3651054,51.61995077133179,0.0,1739502691.3651066,51.61995077133179,0.079174745555608,1739502691.365108,51.61995077133179,3.1134647003493026,1739502691.3651094,51.61995077133179,2.3114995367162416 +1739502691.3850145,51.6399507522583,31.6092282677087,1739502691.3850172,51.6399507522583,-0.14071877473286687,1739502691.38502,51.6399507522583,81.03755944073498,1739502691.3850226,51.6399507522583,25.66680932906398,1739502691.385024,51.6399507522583,-0.029442814778324628,1739502691.3850255,51.6399507522583,3.1228691409151796,1739502691.3850272,51.6399507522583,0.05589409905918539,1739502691.3850284,51.6399507522583,0.012151951099277483,1739502691.3850293,51.6399507522583,2.3906742822718496,1739502691.385031,51.6399507522583,0.0,1739502691.3850322,51.6399507522583,0.079174745555608,1739502691.3850338,51.6399507522583,3.1134647003493026,1739502691.3850353,51.6399507522583,2.3114995367162416 +1739502691.4049757,51.659950733184814,31.354628711324153,1739502691.4049776,51.659950733184814,-0.13341514039872937,1739502691.4049804,51.659950733184814,81.04392442964459,1739502691.4049833,51.659950733184814,25.6430829818233,1739502691.404985,51.659950733184814,-0.02924002548566927,1739502691.4049864,51.659950733184814,3.123355284935787,1739502691.4049878,51.659950733184814,0.06324439101844655,1739502691.4049892,51.659950733184814,0.014884282352059654,1739502691.4049904,51.659950733184814,2.3766578095626008,1739502691.4049926,51.659950733184814,0.0,1739502691.4049938,51.659950733184814,0.046160066367623716,1739502691.404995,51.659950733184814,3.112283822223347,1739502691.4049964,51.659950733184814,2.320180649184318 +1739502691.4239647,51.67995071411133,31.354628711324153,1739502691.423967,51.67995071411133,-0.13341514039872937,1739502691.4239697,51.67995071411133,81.04392442964459,1739502691.4239724,51.67995071411133,25.6430829818233,1739502691.4239738,51.67995071411133,-0.02924002548566927,1739502691.4239755,51.67995071411133,3.123355284935787,1739502691.423977,51.67995071411133,0.06324439101844655,1739502691.4239783,51.67995071411133,0.014884282352059654,1739502691.4239795,51.67995071411133,2.3766578095626008,1739502691.4239807,51.67995071411133,0.0,1739502691.4239821,51.67995071411133,0.056477160378282765,1739502691.4239833,51.67995071411133,3.112283822223347,1739502691.4239845,51.67995071411133,2.320180649184318 +1739502691.4439907,51.69995069503784,31.354628711324153,1739502691.4439929,51.69995069503784,-0.13341514039872937,1739502691.443996,51.69995069503784,81.04392442964459,1739502691.4439986,51.69995069503784,25.6430829818233,1739502691.4439998,51.69995069503784,-0.02924002548566927,1739502691.4440014,51.69995069503784,3.123355284935787,1739502691.444003,51.69995069503784,0.06324439101844655,1739502691.4440043,51.69995069503784,0.014884282352059654,1739502691.4440057,51.69995069503784,2.3766578095626008,1739502691.4440072,51.69995069503784,0.0,1739502691.4440084,51.69995069503784,0.056477160378282765,1739502691.44401,51.69995069503784,3.112283822223347,1739502691.4440114,51.69995069503784,2.320180649184318 +1739502691.4643595,51.719950675964355,31.354628711324153,1739502691.4643624,51.719950675964355,-0.13341514039872937,1739502691.4643662,51.719950675964355,81.04392442964459,1739502691.4643693,51.719950675964355,25.6430829818233,1739502691.464371,51.719950675964355,-0.02924002548566927,1739502691.4643736,51.719950675964355,3.123355284935787,1739502691.464375,51.719950675964355,0.06324439101844655,1739502691.464377,51.719950675964355,0.014884282352059654,1739502691.464378,51.719950675964355,2.3766578095626008,1739502691.4643803,51.719950675964355,0.0,1739502691.4643822,51.719950675964355,0.056477160378282765,1739502691.464384,51.719950675964355,3.112283822223347,1739502691.4643855,51.719950675964355,2.320180649184318 +1739502691.4842012,51.73995065689087,31.354628711324153,1739502691.4842038,51.73995065689087,-0.13341514039872937,1739502691.4842072,51.73995065689087,81.04392442964459,1739502691.4842103,51.73995065689087,25.6430829818233,1739502691.484212,51.73995065689087,-0.02924002548566927,1739502691.484214,51.73995065689087,3.123355284935787,1739502691.4842155,51.73995065689087,0.06324439101844655,1739502691.4842176,51.73995065689087,0.014884282352059654,1739502691.484219,51.73995065689087,2.3766578095626008,1739502691.484221,51.73995065689087,0.0,1739502691.4842224,51.73995065689087,0.056477160378282765,1739502691.484224,51.73995065689087,3.112283822223347,1739502691.4842255,51.73995065689087,2.320180649184318 +1739502691.5044441,51.75995063781738,31.354628711324153,1739502691.5044472,51.75995063781738,-0.13341514039872937,1739502691.504451,51.75995063781738,81.04392442964459,1739502691.5044549,51.75995063781738,25.6430829818233,1739502691.5044568,51.75995063781738,-0.02924002548566927,1739502691.5044587,51.75995063781738,3.123355284935787,1739502691.5044608,51.75995063781738,0.06324439101844655,1739502691.5044625,51.75995063781738,0.014884282352059654,1739502691.5044641,51.75995063781738,2.3766578095626008,1739502691.5044665,51.75995063781738,0.0,1739502691.504468,51.75995063781738,0.056477160378282765,1739502691.5044699,51.75995063781738,3.112283822223347,1739502691.5044715,51.75995063781738,2.320180649184318 +1739502691.52528,51.7799506187439,31.099232087745094,1739502691.5252843,51.7799506187439,-0.12580213426914444,1739502691.5252895,51.7799506187439,81.61070676567847,1739502691.5252936,51.7799506187439,25.064379767636336,1739502691.5252957,51.7799506187439,-0.024704850334833345,1739502691.525298,51.7799506187439,3.124841982167336,1739502691.5253005,51.7799506187439,0.08226646620638202,1739502691.5253024,51.7799506187439,0.01734299378248196,1739502691.5253046,51.7799506187439,2.340764437959501,1739502691.5253074,51.7799506187439,0.0,1739502691.525309,51.7799506187439,-0.0044269007330044186,1739502691.5253115,51.7799506187439,3.111211578671895,1739502691.5253134,51.7799506187439,2.3261588071165282 +1739502691.5447698,51.79995059967041,31.099232087745094,1739502691.5447733,51.79995059967041,-0.12580213426914444,1739502691.5447776,51.79995059967041,81.61070676567847,1739502691.544782,51.79995059967041,25.064379767636336,1739502691.5447838,51.79995059967041,-0.024704850334833345,1739502691.5447862,51.79995059967041,3.124841982167336,1739502691.5447888,51.79995059967041,0.08226646620638202,1739502691.5447907,51.79995059967041,0.01734299378248196,1739502691.5447927,51.79995059967041,2.340764437959501,1739502691.5447948,51.79995059967041,0.0,1739502691.544797,51.79995059967041,0.01460563084297295,1739502691.544799,51.79995059967041,3.111211578671895,1739502691.544801,51.79995059967041,2.3261588071165282 +1739502691.5652695,51.819950580596924,31.099232087745094,1739502691.5652733,51.819950580596924,-0.12580213426914444,1739502691.5652773,51.819950580596924,81.61070676567847,1739502691.5652819,51.819950580596924,25.064379767636336,1739502691.5652835,51.819950580596924,-0.024704850334833345,1739502691.5652862,51.819950580596924,3.124841982167336,1739502691.5652883,51.819950580596924,0.08226646620638202,1739502691.5652902,51.819950580596924,0.01734299378248196,1739502691.5652921,51.819950580596924,2.340764437959501,1739502691.5652945,51.819950580596924,0.0,1739502691.5652964,51.819950580596924,0.01460563084297295,1739502691.565299,51.819950580596924,3.111211578671895,1739502691.565301,51.819950580596924,2.3261588071165282 +1739502691.5848246,51.83995056152344,31.099232087745094,1739502691.5848284,51.83995056152344,-0.12580213426914444,1739502691.5848327,51.83995056152344,81.61070676567847,1739502691.5848367,51.83995056152344,25.064379767636336,1739502691.5848386,51.83995056152344,-0.024704850334833345,1739502691.5848415,51.83995056152344,3.124841982167336,1739502691.5848432,51.83995056152344,0.08226646620638202,1739502691.5848453,51.83995056152344,0.01734299378248196,1739502691.5848472,51.83995056152344,2.340764437959501,1739502691.5848494,51.83995056152344,0.0,1739502691.5848513,51.83995056152344,0.01460563084297295,1739502691.5848534,51.83995056152344,3.111211578671895,1739502691.5848553,51.83995056152344,2.3261588071165282 +1739502691.6049662,51.85995054244995,31.099232087745094,1739502691.60497,51.85995054244995,-0.12580213426914444,1739502691.604974,51.85995054244995,81.61070676567847,1739502691.604978,51.85995054244995,25.064379767636336,1739502691.6049802,51.85995054244995,-0.024704850334833345,1739502691.6049829,51.85995054244995,3.124841982167336,1739502691.6049845,51.85995054244995,0.08226646620638202,1739502691.6049867,51.85995054244995,0.01734299378248196,1739502691.6049886,51.85995054244995,2.340764437959501,1739502691.6049912,51.85995054244995,0.0,1739502691.604993,51.85995054244995,0.01460563084297295,1739502691.6049953,51.85995054244995,3.111211578671895,1739502691.6049972,51.85995054244995,2.3261588071165282 +1739502691.6253374,51.879950523376465,30.84338723321948,1739502691.6253407,51.879950523376465,-0.1179137300189046,1739502691.6253448,51.879950523376465,82.27725489546648,1739502691.6253486,51.879950523376465,24.394610221270323,1739502691.6253507,51.879950523376465,-0.01821463837518475,1739502691.6253529,51.879950523376465,3.126133730237513,1739502691.625355,51.879950523376465,0.10231012668022721,1739502691.625357,51.879950523376465,0.018889288166775917,1739502691.6253586,51.879950523376465,2.3035297732435067,1739502691.625361,51.879950523376465,0.0,1739502691.6253626,51.879950523376465,-0.04192528463453253,1739502691.6253648,51.879950523376465,3.1102699172022543,1739502691.6253667,51.879950523376465,2.3277891352086373 +1739502691.6447325,51.89995050430298,30.84338723321948,1739502691.6447358,51.89995050430298,-0.1179137300189046,1739502691.64474,51.89995050430298,82.27725489546648,1739502691.6447444,51.89995050430298,24.394610221270323,1739502691.6447463,51.89995050430298,-0.01821463837518475,1739502691.6447487,51.89995050430298,3.126133730237513,1739502691.6447508,51.89995050430298,0.10231012668022721,1739502691.644753,51.89995050430298,0.018889288166775917,1739502691.6447546,51.89995050430298,2.3035297732435067,1739502691.644757,51.89995050430298,0.0,1739502691.644759,51.89995050430298,-0.024259361965130566,1739502691.6447613,51.89995050430298,3.1102699172022543,1739502691.6447635,51.89995050430298,2.3277891352086373 +1739502691.66544,51.91995048522949,30.84338723321948,1739502691.6654444,51.91995048522949,-0.1179137300189046,1739502691.665449,51.91995048522949,82.27725489546648,1739502691.665453,51.91995048522949,24.394610221270323,1739502691.6654549,51.91995048522949,-0.01821463837518475,1739502691.6654572,51.91995048522949,3.126133730237513,1739502691.6654592,51.91995048522949,0.10231012668022721,1739502691.6654613,51.91995048522949,0.018889288166775917,1739502691.665463,51.91995048522949,2.3035297732435067,1739502691.6654654,51.91995048522949,0.0,1739502691.6654675,51.91995048522949,-0.024259361965130566,1739502691.6654758,51.91995048522949,3.1102699172022543,1739502691.6654782,51.91995048522949,2.3277891352086373 +1739502691.6848054,51.939950466156006,30.84338723321948,1739502691.6848094,51.939950466156006,-0.1179137300189046,1739502691.6848137,51.939950466156006,82.27725489546648,1739502691.684818,51.939950466156006,24.394610221270323,1739502691.68482,51.939950466156006,-0.01821463837518475,1739502691.6848223,51.939950466156006,3.126133730237513,1739502691.6848242,51.939950466156006,0.10231012668022721,1739502691.6848264,51.939950466156006,0.018889288166775917,1739502691.684828,51.939950466156006,2.3035297732435067,1739502691.6848304,51.939950466156006,0.0,1739502691.6848323,51.939950466156006,-0.024259361965130566,1739502691.6848342,51.939950466156006,3.1102699172022543,1739502691.6848364,51.939950466156006,2.3277891352086373 +1739502691.7047858,51.95995044708252,30.84338723321948,1739502691.7047899,51.95995044708252,-0.1179137300189046,1739502691.704794,51.95995044708252,82.27725489546648,1739502691.7047977,51.95995044708252,24.394610221270323,1739502691.7047994,51.95995044708252,-0.01821463837518475,1739502691.704802,51.95995044708252,3.126133730237513,1739502691.7048042,51.95995044708252,0.10231012668022721,1739502691.704806,51.95995044708252,0.018889288166775917,1739502691.704808,51.95995044708252,2.3035297732435067,1739502691.7048101,51.95995044708252,0.0,1739502691.704812,51.95995044708252,-0.024259361965130566,1739502691.7048147,51.95995044708252,3.1102699172022543,1739502691.7048166,51.95995044708252,2.3277891352086373 +1739502691.7255275,51.97995042800903,30.84338723321948,1739502691.7255316,51.97995042800903,-0.1179137300189046,1739502691.7255363,51.97995042800903,82.27725489546648,1739502691.7255406,51.97995042800903,24.394610221270323,1739502691.7255425,51.97995042800903,-0.01821463837518475,1739502691.7255452,51.97995042800903,3.126133730237513,1739502691.7255478,51.97995042800903,0.10231012668022721,1739502691.7255502,51.97995042800903,0.018889288166775917,1739502691.7255518,51.97995042800903,2.3035297732435067,1739502691.7255542,51.97995042800903,0.0,1739502691.7255561,51.97995042800903,-0.024259361965130566,1739502691.7255585,51.97995042800903,3.1102699172022543,1739502691.725561,51.97995042800903,2.3277891352086373 +1739502691.7449954,51.99995040893555,30.58762574269163,1739502691.7449994,51.99995040893555,-0.10979462257567363,1739502691.7450035,51.99995040893555,82.2902987314834,1739502691.7450082,51.99995040893555,24.387578232004714,1739502691.74501,51.99995040893555,-0.01815071120004286,1739502691.7450125,51.99995040893555,3.126812567165104,1739502691.7450147,51.99995040893555,0.10818498246559313,1739502691.7450166,51.99995040893555,0.0216090551346765,1739502691.7450185,51.99995040893555,2.29272885049853,1739502691.7450209,51.99995040893555,0.0,1739502691.745023,51.99995040893555,-0.03559775757020571,1739502691.7450247,51.99995040893555,3.109364530721727,1739502691.7450268,51.99995040893555,2.3247833571190135 +1739502691.7656314,52.01995038986206,30.58762574269163,1739502691.7656357,52.01995038986206,-0.10979462257567363,1739502691.7656403,52.01995038986206,82.2902987314834,1739502691.7656443,52.01995038986206,24.387578232004714,1739502691.7656462,52.01995038986206,-0.01815071120004286,1739502691.7656488,52.01995038986206,3.126812567165104,1739502691.7656507,52.01995038986206,0.10818498246559313,1739502691.7656527,52.01995038986206,0.0216090551346765,1739502691.7656546,52.01995038986206,2.29272885049853,1739502691.7656572,52.01995038986206,0.0,1739502691.7656589,52.01995038986206,-0.03205450662048337,1739502691.7656612,52.01995038986206,3.109364530721727,1739502691.7656631,52.01995038986206,2.3247833571190135 +1739502691.7850745,52.039950370788574,30.58762574269163,1739502691.7850785,52.039950370788574,-0.10979462257567363,1739502691.7850833,52.039950370788574,82.2902987314834,1739502691.7850876,52.039950370788574,24.387578232004714,1739502691.7850895,52.039950370788574,-0.01815071120004286,1739502691.7850926,52.039950370788574,3.126812567165104,1739502691.785095,52.039950370788574,0.10818498246559313,1739502691.785097,52.039950370788574,0.0216090551346765,1739502691.785099,52.039950370788574,2.29272885049853,1739502691.7851017,52.039950370788574,0.0,1739502691.7851033,52.039950370788574,-0.03205450662048337,1739502691.7851057,52.039950370788574,3.109364530721727,1739502691.7851074,52.039950370788574,2.3247833571190135 +1739502691.8050952,52.05995035171509,30.58762574269163,1739502691.805099,52.05995035171509,-0.10979462257567363,1739502691.8051026,52.05995035171509,82.2902987314834,1739502691.8051062,52.05995035171509,24.387578232004714,1739502691.805108,52.05995035171509,-0.01815071120004286,1739502691.8051102,52.05995035171509,3.126812567165104,1739502691.8051124,52.05995035171509,0.10818498246559313,1739502691.805114,52.05995035171509,0.0216090551346765,1739502691.805116,52.05995035171509,2.29272885049853,1739502691.8051178,52.05995035171509,0.0,1739502691.8051198,52.05995035171509,-0.03205450662048337,1739502691.8051212,52.05995035171509,3.109364530721727,1739502691.8051233,52.05995035171509,2.3247833571190135 +1739502691.8244767,52.0799503326416,30.58762574269163,1739502691.8244793,52.0799503326416,-0.10979462257567363,1739502691.8244822,52.0799503326416,82.2902987314834,1739502691.8244853,52.0799503326416,24.387578232004714,1739502691.824487,52.0799503326416,-0.01815071120004286,1739502691.8244886,52.0799503326416,3.126812567165104,1739502691.8244903,52.0799503326416,0.10818498246559313,1739502691.8244917,52.0799503326416,0.0216090551346765,1739502691.8244932,52.0799503326416,2.29272885049853,1739502691.8244948,52.0799503326416,0.0,1739502691.8244963,52.0799503326416,-0.03205450662048337,1739502691.824498,52.0799503326416,3.109364530721727,1739502691.8244994,52.0799503326416,2.3247833571190135 +1739502691.8443189,52.099950313568115,30.332209082228815,1739502691.8443217,52.099950313568115,-0.10146579018884516,1739502691.844325,52.099950313568115,82.30332498116701,1739502691.8443282,52.099950313568115,24.381550724379448,1739502691.8443294,52.099950313568115,-0.018095915676176792,1739502691.8443315,52.099950313568115,3.127583376737484,1739502691.8443334,52.099950313568115,0.11307043909493004,1739502691.844335,52.099950313568115,0.02451801790770877,1739502691.8443367,52.099950313568115,2.2837855169006973,1739502691.8443382,52.099950313568115,0.0,1739502691.8443396,52.099950313568115,-0.039973181127893866,1739502691.8443413,52.099950313568115,3.1085827653744764,1739502691.8443427,52.099950313568115,2.3212841106225595 +1739502691.8642163,52.11995029449463,30.332209082228815,1739502691.8642194,52.11995029449463,-0.10146579018884516,1739502691.8642225,52.11995029449463,82.30332498116701,1739502691.8642254,52.11995029449463,24.381550724379448,1739502691.8642268,52.11995029449463,-0.018095915676176792,1739502691.8642287,52.11995029449463,3.127583376737484,1739502691.8642302,52.11995029449463,0.11307043909493004,1739502691.8642316,52.11995029449463,0.02451801790770877,1739502691.864233,52.11995029449463,2.2837855169006973,1739502691.864235,52.11995029449463,0.0,1739502691.8642364,52.11995029449463,-0.03749859372186215,1739502691.8642378,52.11995029449463,3.1085827653744764,1739502691.8642395,52.11995029449463,2.3212841106225595 +1739502691.8843513,52.13995027542114,30.332209082228815,1739502691.8843544,52.13995027542114,-0.10146579018884516,1739502691.8843577,52.13995027542114,82.30332498116701,1739502691.8843608,52.13995027542114,24.381550724379448,1739502691.8843622,52.13995027542114,-0.018095915676176792,1739502691.8843641,52.13995027542114,3.127583376737484,1739502691.8843656,52.13995027542114,0.11307043909493004,1739502691.884367,52.13995027542114,0.02451801790770877,1739502691.8843687,52.13995027542114,2.2837855169006973,1739502691.8843708,52.13995027542114,0.0,1739502691.884372,52.13995027542114,-0.03749859372186215,1739502691.8843734,52.13995027542114,3.1085827653744764,1739502691.884375,52.13995027542114,2.3212841106225595 +1739502691.904298,52.159950256347656,30.332209082228815,1739502691.9043012,52.159950256347656,-0.10146579018884516,1739502691.9043043,52.159950256347656,82.30332498116701,1739502691.9043071,52.159950256347656,24.381550724379448,1739502691.904309,52.159950256347656,-0.018095915676176792,1739502691.9043107,52.159950256347656,3.127583376737484,1739502691.9043124,52.159950256347656,0.11307043909493004,1739502691.9043138,52.159950256347656,0.02451801790770877,1739502691.9043155,52.159950256347656,2.2837855169006973,1739502691.9043171,52.159950256347656,0.0,1739502691.9043188,52.159950256347656,-0.03749859372186215,1739502691.9043202,52.159950256347656,3.1085827653744764,1739502691.904322,52.159950256347656,2.3212841106225595 +1739502691.9253027,52.17995023727417,30.332209082228815,1739502691.9253063,52.17995023727417,-0.10146579018884516,1739502691.9253106,52.17995023727417,82.30332498116701,1739502691.9253156,52.17995023727417,24.381550724379448,1739502691.925318,52.17995023727417,-0.018095915676176792,1739502691.925321,52.17995023727417,3.127583376737484,1739502691.9253237,52.17995023727417,0.11307043909493004,1739502691.925326,52.17995023727417,0.02451801790770877,1739502691.9253287,52.17995023727417,2.2837855169006973,1739502691.9253325,52.17995023727417,0.0,1739502691.9253361,52.17995023727417,-0.03749859372186215,1739502691.9253404,52.17995023727417,3.1085827653744764,1739502691.9253445,52.17995023727417,2.3212841106225595 +1739502691.9455607,52.199950218200684,30.332209082228815,1739502691.945566,52.199950218200684,-0.10146579018884516,1739502691.9455717,52.199950218200684,82.30332498116701,1739502691.9455762,52.199950218200684,24.381550724379448,1739502691.9455786,52.199950218200684,-0.018095915676176792,1739502691.9455817,52.199950218200684,3.127583376737484,1739502691.9455838,52.199950218200684,0.11307043909493004,1739502691.9455864,52.199950218200684,0.02451801790770877,1739502691.9455888,52.199950218200684,2.2837855169006973,1739502691.945592,52.199950218200684,0.0,1739502691.9455945,52.199950218200684,-0.03749859372186215,1739502691.9455974,52.199950218200684,3.1085827653744764,1739502691.9456005,52.199950218200684,2.3212841106225595 +1739502691.9653194,52.2199501991272,30.07721976699525,1739502691.9653223,52.2199501991272,-0.09296670302014043,1739502691.9653254,52.2199501991272,82.31632943624392,1739502691.9653282,52.2199501991272,24.37685458632667,1739502691.9653294,52.2199501991272,-0.018053223512060627,1739502691.9653308,52.2199501991272,3.1284515363384315,1739502691.9653325,52.2199501991272,0.11709503883700534,1739502691.9653337,52.2199501991272,0.0276698651418782,1739502691.9653351,52.2199501991272,2.2764442833713137,1739502691.9653368,52.2199501991272,0.0,1739502691.9653382,52.2199501991272,-0.04213448171140318,1739502691.9653397,52.2199501991272,3.1079101922136614,1739502691.9653409,52.2199501991272,2.317130049136133 +1739502691.9851694,52.23995018005371,30.07721976699525,1739502691.9851735,52.23995018005371,-0.09296670302014043,1739502691.9851778,52.23995018005371,82.31632943624392,1739502691.9851825,52.23995018005371,24.37685458632667,1739502691.9851847,52.23995018005371,-0.018053223512060627,1739502691.9851878,52.23995018005371,3.1284515363384315,1739502691.985191,52.23995018005371,0.11709503883700534,1739502691.9851935,52.23995018005371,0.0276698651418782,1739502691.985196,52.23995018005371,2.2764442833713137,1739502691.9851992,52.23995018005371,0.0,1739502691.9852014,52.23995018005371,-0.040685765764819415,1739502691.9852037,52.23995018005371,3.1079101922136614,1739502691.9852066,52.23995018005371,2.317130049136133 +1739502692.0055094,52.259950160980225,30.07721976699525,1739502692.005513,52.259950160980225,-0.09296670302014043,1739502692.0055172,52.259950160980225,82.31632943624392,1739502692.0055213,52.259950160980225,24.37685458632667,1739502692.0055242,52.259950160980225,-0.018053223512060627,1739502692.005527,52.259950160980225,3.1284515363384315,1739502692.0055296,52.259950160980225,0.11709503883700534,1739502692.0055315,52.259950160980225,0.0276698651418782,1739502692.005534,52.259950160980225,2.2764442833713137,1739502692.0055366,52.259950160980225,0.0,1739502692.0055387,52.259950160980225,-0.040685765764819415,1739502692.005541,52.259950160980225,3.1079101922136614,1739502692.0055437,52.259950160980225,2.317130049136133 +1739502692.0252905,52.27995014190674,30.07721976699525,1739502692.0252926,52.27995014190674,-0.09296670302014043,1739502692.0252957,52.27995014190674,82.31632943624392,1739502692.025298,52.27995014190674,24.37685458632667,1739502692.0252995,52.27995014190674,-0.018053223512060627,1739502692.0253012,52.27995014190674,3.1284515363384315,1739502692.0253024,52.27995014190674,0.11709503883700534,1739502692.0253038,52.27995014190674,0.0276698651418782,1739502692.025305,52.27995014190674,2.2764442833713137,1739502692.0253067,52.27995014190674,0.0,1739502692.0253081,52.27995014190674,-0.040685765764819415,1739502692.0253093,52.27995014190674,3.1079101922136614,1739502692.0253115,52.27995014190674,2.317130049136133 +1739502692.0455182,52.29995012283325,30.07721976699525,1739502692.045523,52.29995012283325,-0.09296670302014043,1739502692.0455291,52.29995012283325,82.31632943624392,1739502692.0455363,52.29995012283325,24.37685458632667,1739502692.04554,52.29995012283325,-0.018053223512060627,1739502692.045545,52.29995012283325,3.1284515363384315,1739502692.0455496,52.29995012283325,0.11709503883700534,1739502692.0455542,52.29995012283325,0.0276698651418782,1739502692.0455585,52.29995012283325,2.2764442833713137,1739502692.0455632,52.29995012283325,0.0,1739502692.0455678,52.29995012283325,-0.040685765764819415,1739502692.0455723,52.29995012283325,3.1079101922136614,1739502692.045577,52.29995012283325,2.317130049136133 +1739502692.0670981,52.319950103759766,29.82270415460252,1739502692.0671031,52.319950103759766,-0.08432453083002311,1739502692.067109,52.319950103759766,82.69688832238847,1739502692.0671153,52.319950103759766,24.00520396243384,1739502692.0671184,52.319950103759766,-0.015,1739502692.0671222,52.319950103759766,3.129676667794785,1739502692.0671253,52.319950103759766,0.12977368744661533,1739502692.0671296,52.319950103759766,0.02944417836303114,1739502692.0671332,52.319950103759766,2.253471197678422,1739502692.067137,52.319950103759766,0.0,1739502692.0671399,52.319950103759766,-0.06763258872916834,1739502692.0671432,52.319950103759766,3.1073689354149177,1739502692.067147,52.319950103759766,2.312682898710067 +1739502692.0851903,52.33995008468628,29.82270415460252,1739502692.0851927,52.33995008468628,-0.08432453083002311,1739502692.0851958,52.33995008468628,82.69688832238847,1739502692.0851984,52.33995008468628,24.00520396243384,1739502692.0851996,52.33995008468628,-0.015,1739502692.0852015,52.33995008468628,3.129676667794785,1739502692.0852027,52.33995008468628,0.12977368744661533,1739502692.085204,52.33995008468628,0.02944417836303114,1739502692.0852053,52.33995008468628,2.253471197678422,1739502692.0852067,52.33995008468628,0.0,1739502692.0852082,52.33995008468628,-0.05921170103164508,1739502692.0852094,52.33995008468628,3.1073689354149177,1739502692.0852106,52.33995008468628,2.312682898710067 +1739502692.105233,52.35995006561279,29.82270415460252,1739502692.1052353,52.35995006561279,-0.08432453083002311,1739502692.1052384,52.35995006561279,82.69688832238847,1739502692.1052413,52.35995006561279,24.00520396243384,1739502692.1052427,52.35995006561279,-0.015,1739502692.1052442,52.35995006561279,3.129676667794785,1739502692.1052454,52.35995006561279,0.12977368744661533,1739502692.105247,52.35995006561279,0.02944417836303114,1739502692.1052482,52.35995006561279,2.253471197678422,1739502692.10525,52.35995006561279,0.0,1739502692.105251,52.35995006561279,-0.05921170103164508,1739502692.1052525,52.35995006561279,3.1073689354149177,1739502692.1052542,52.35995006561279,2.312682898710067 +1739502692.1246095,52.37995004653931,29.82270415460252,1739502692.124612,52.37995004653931,-0.08432453083002311,1739502692.124615,52.37995004653931,82.69688832238847,1739502692.1246178,52.37995004653931,24.00520396243384,1739502692.124619,52.37995004653931,-0.015,1739502692.124621,52.37995004653931,3.129676667794785,1739502692.1246223,52.37995004653931,0.12977368744661533,1739502692.1246238,52.37995004653931,0.02944417836303114,1739502692.1246252,52.37995004653931,2.253471197678422,1739502692.1246266,52.37995004653931,0.0,1739502692.124628,52.37995004653931,-0.05921170103164508,1739502692.1246293,52.37995004653931,3.1073689354149177,1739502692.1246307,52.37995004653931,2.312682898710067 +1739502692.144194,52.39995002746582,29.82270415460252,1739502692.1441965,52.39995002746582,-0.08432453083002311,1739502692.1441998,52.39995002746582,82.69688832238847,1739502692.1442027,52.39995002746582,24.00520396243384,1739502692.1442041,52.39995002746582,-0.015,1739502692.1442056,52.39995002746582,3.129676667794785,1739502692.144207,52.39995002746582,0.12977368744661533,1739502692.1442084,52.39995002746582,0.02944417836303114,1739502692.1442099,52.39995002746582,2.253471197678422,1739502692.1442115,52.39995002746582,0.0,1739502692.1442127,52.39995002746582,-0.05921170103164508,1739502692.1442146,52.39995002746582,3.1073689354149177,1739502692.1442158,52.39995002746582,2.312682898710067 +1739502692.1642075,52.419950008392334,29.82270415460252,1739502692.1642103,52.419950008392334,-0.08432453083002311,1739502692.1642134,52.419950008392334,82.69688832238847,1739502692.1642163,52.419950008392334,24.00520396243384,1739502692.164218,52.419950008392334,-0.015,1739502692.1642196,52.419950008392334,3.129676667794785,1739502692.1642213,52.419950008392334,0.12977368744661533,1739502692.1642225,52.419950008392334,0.02944417836303114,1739502692.1642237,52.419950008392334,2.253471197678422,1739502692.1642256,52.419950008392334,0.0,1739502692.164227,52.419950008392334,-0.05921170103164508,1739502692.1642284,52.419950008392334,3.1073689354149177,1739502692.16423,52.419950008392334,2.312682898710067 +1739502692.1842544,52.43994998931885,29.568800204722336,1739502692.184257,52.43994998931885,-0.07558089435422488,1739502692.18426,52.43994998931885,83.2634951486143,1739502692.1842628,52.43994998931885,23.451908574302525,1739502692.184264,52.43994998931885,-0.017436031719421034,1739502692.1842656,52.43994998931885,3.132087317386319,1739502692.184267,52.43994998931885,0.15383133978535107,1739502692.1842685,52.43994998931885,0.031571062442002,1739502692.1842697,52.43994998931885,2.210515309449282,1739502692.1842713,52.43994998931885,0.0,1739502692.1842725,52.43994998931885,-0.11202183843812863,1739502692.1842742,52.43994998931885,3.1069371893006466,1739502692.1842754,52.43994998931885,2.3060339691275575 +1739502692.2041883,52.45994997024536,29.568800204722336,1739502692.2041914,52.45994997024536,-0.07558089435422488,1739502692.2041945,52.45994997024536,83.2634951486143,1739502692.2041972,52.45994997024536,23.451908574302525,1739502692.2041986,52.45994997024536,-0.017436031719421034,1739502692.2042003,52.45994997024536,3.132087317386319,1739502692.2042017,52.45994997024536,0.15383133978535107,1739502692.204203,52.45994997024536,0.031571062442002,1739502692.2042043,52.45994997024536,2.210515309449282,1739502692.2042062,52.45994997024536,0.0,1739502692.2042077,52.45994997024536,-0.09551865967827533,1739502692.2042089,52.45994997024536,3.1069371893006466,1739502692.2042105,52.45994997024536,2.3060339691275575 +1739502692.2242937,52.479949951171875,29.568800204722336,1739502692.2242963,52.479949951171875,-0.07558089435422488,1739502692.2242992,52.479949951171875,83.2634951486143,1739502692.224302,52.479949951171875,23.451908574302525,1739502692.2243032,52.479949951171875,-0.017436031719421034,1739502692.2243056,52.479949951171875,3.132087317386319,1739502692.224307,52.479949951171875,0.15383133978535107,1739502692.2243085,52.479949951171875,0.031571062442002,1739502692.2243097,52.479949951171875,2.210515309449282,1739502692.2243118,52.479949951171875,0.0,1739502692.2243133,52.479949951171875,-0.09551865967827533,1739502692.2243147,52.479949951171875,3.1069371893006466,1739502692.2243161,52.479949951171875,2.3060339691275575 +1739502692.2441344,52.49994993209839,29.568800204722336,1739502692.2441375,52.49994993209839,-0.07558089435422488,1739502692.2441404,52.49994993209839,83.2634951486143,1739502692.2441432,52.49994993209839,23.451908574302525,1739502692.244145,52.49994993209839,-0.017436031719421034,1739502692.2441466,52.49994993209839,3.132087317386319,1739502692.2441483,52.49994993209839,0.15383133978535107,1739502692.2441497,52.49994993209839,0.031571062442002,1739502692.2441514,52.49994993209839,2.210515309449282,1739502692.2441528,52.49994993209839,0.0,1739502692.2441545,52.49994993209839,-0.09551865967827533,1739502692.244156,52.49994993209839,3.1069371893006466,1739502692.2441576,52.49994993209839,2.3060339691275575 +1739502692.2642949,52.5199499130249,29.568800204722336,1739502692.264298,52.5199499130249,-0.07558089435422488,1739502692.264301,52.5199499130249,83.2634951486143,1739502692.264304,52.5199499130249,23.451908574302525,1739502692.264305,52.5199499130249,-0.017436031719421034,1739502692.2643073,52.5199499130249,3.132087317386319,1739502692.2643087,52.5199499130249,0.15383133978535107,1739502692.2643101,52.5199499130249,0.031571062442002,1739502692.2643113,52.5199499130249,2.210515309449282,1739502692.2643135,52.5199499130249,0.0,1739502692.2643147,52.5199499130249,-0.09551865967827533,1739502692.2643158,52.5199499130249,3.1069371893006466,1739502692.2643175,52.5199499130249,2.3060339691275575 +1739502692.2842534,52.539949893951416,29.315804963273557,1739502692.284256,52.539949893951416,-0.06676694175262021,1739502692.284259,52.539949893951416,83.83512504315598,1739502692.284262,52.539949893951416,22.90113613145612,1739502692.2842634,52.539949893951416,-0.022,1739502692.2842653,52.539949893951416,3.1346139277711633,1739502692.2842665,52.539949893951416,0.17981846833599657,1739502692.2842681,52.539949893951416,0.033558903867037415,1739502692.2842693,52.539949893951416,2.1650337650640035,1739502692.2842708,52.539949893951416,0.0,1739502692.2842724,52.539949893951416,-0.14651992843000156,1739502692.2842739,52.539949893951416,3.106578552675704,1739502692.2842755,52.539949893951416,2.2956157865593845 +1739502692.3041754,52.55994987487793,29.315804963273557,1739502692.3041782,52.55994987487793,-0.06676694175262021,1739502692.304181,52.55994987487793,83.83512504315598,1739502692.3041835,52.55994987487793,22.90113613145612,1739502692.304185,52.55994987487793,-0.022,1739502692.3041868,52.55994987487793,3.1346139277711633,1739502692.3041883,52.55994987487793,0.17981846833599657,1739502692.3041897,52.55994987487793,0.033558903867037415,1739502692.3041909,52.55994987487793,2.1650337650640035,1739502692.3041928,52.55994987487793,0.0,1739502692.304194,52.55994987487793,-0.130582021495381,1739502692.3041956,52.55994987487793,3.106578552675704,1739502692.304197,52.55994987487793,2.2956157865593845 +1739502692.3241906,52.57994985580444,29.315804963273557,1739502692.3241932,52.57994985580444,-0.06676694175262021,1739502692.324196,52.57994985580444,83.83512504315598,1739502692.324199,52.57994985580444,22.90113613145612,1739502692.3242004,52.57994985580444,-0.022,1739502692.324202,52.57994985580444,3.1346139277711633,1739502692.3242033,52.57994985580444,0.17981846833599657,1739502692.3242047,52.57994985580444,0.033558903867037415,1739502692.324206,52.57994985580444,2.1650337650640035,1739502692.3242075,52.57994985580444,0.0,1739502692.3242092,52.57994985580444,-0.130582021495381,1739502692.3242104,52.57994985580444,3.106578552675704,1739502692.324212,52.57994985580444,2.2956157865593845 +1739502692.3442132,52.59994983673096,29.315804963273557,1739502692.3442163,52.59994983673096,-0.06676694175262021,1739502692.3442194,52.59994983673096,83.83512504315598,1739502692.3442223,52.59994983673096,22.90113613145612,1739502692.3442235,52.59994983673096,-0.022,1739502692.3442252,52.59994983673096,3.1346139277711633,1739502692.3442268,52.59994983673096,0.17981846833599657,1739502692.344228,52.59994983673096,0.033558903867037415,1739502692.3442297,52.59994983673096,2.1650337650640035,1739502692.3442311,52.59994983673096,0.0,1739502692.3442326,52.59994983673096,-0.130582021495381,1739502692.344234,52.59994983673096,3.106578552675704,1739502692.3442354,52.59994983673096,2.2956157865593845 +1739502692.3641553,52.61994981765747,29.315804963273557,1739502692.3641586,52.61994981765747,-0.06676694175262021,1739502692.364162,52.61994981765747,83.83512504315598,1739502692.3641648,52.61994981765747,22.90113613145612,1739502692.3641663,52.61994981765747,-0.022,1739502692.3641677,52.61994981765747,3.1346139277711633,1739502692.3641691,52.61994981765747,0.17981846833599657,1739502692.3641706,52.61994981765747,0.033558903867037415,1739502692.3641717,52.61994981765747,2.1650337650640035,1739502692.3641737,52.61994981765747,0.0,1739502692.3641753,52.61994981765747,-0.130582021495381,1739502692.364177,52.61994981765747,3.106578552675704,1739502692.3641784,52.61994981765747,2.2956157865593845 +1739502692.3842728,52.639949798583984,29.315804963273557,1739502692.3842754,52.639949798583984,-0.06676694175262021,1739502692.3842785,52.639949798583984,83.83512504315598,1739502692.3842814,52.639949798583984,22.90113613145612,1739502692.3842826,52.639949798583984,-0.022,1739502692.3842845,52.639949798583984,3.1346139277711633,1739502692.3842857,52.639949798583984,0.17981846833599657,1739502692.384287,52.639949798583984,0.033558903867037415,1739502692.3842885,52.639949798583984,2.1650337650640035,1739502692.38429,52.639949798583984,0.0,1739502692.3842914,52.639949798583984,-0.130582021495381,1739502692.384293,52.639949798583984,3.106578552675704,1739502692.3842945,52.639949798583984,2.2956157865593845 +1739502692.404256,52.6599497795105,29.064188959637875,1739502692.4042587,52.6599497795105,-0.05792141736458767,1739502692.4042618,52.6599497795105,83.85349301142139,1739502692.4042647,52.6599497795105,22.911990705370705,1739502692.4042664,52.6599497795105,-0.022,1739502692.404268,52.6599497795105,3.135753926084083,1739502692.4042695,52.6599497795105,0.18113568111842318,1739502692.404271,52.6599497795105,0.03675090626822165,1739502692.404272,52.6599497795105,2.162753518583151,1739502692.4042737,52.6599497795105,0.0,1739502692.4042752,52.6599497795105,-0.11264598035489612,1739502692.4042764,52.6599497795105,3.106307740383685,1739502692.404278,52.6599497795105,2.281004515469384 +1739502692.4246511,52.67994976043701,29.064188959637875,1739502692.424654,52.67994976043701,-0.05792141736458767,1739502692.424657,52.67994976043701,83.85349301142139,1739502692.42466,52.67994976043701,22.911990705370705,1739502692.4246614,52.67994976043701,-0.022,1739502692.4246633,52.67994976043701,3.135753926084083,1739502692.4246647,52.67994976043701,0.18113568111842318,1739502692.4246662,52.67994976043701,0.03675090626822165,1739502692.4246674,52.67994976043701,2.162753518583151,1739502692.424669,52.67994976043701,0.0,1739502692.4246848,52.67994976043701,-0.11825099688623286,1739502692.4246905,52.67994976043701,3.106307740383685,1739502692.4246948,52.67994976043701,2.281004515469384 +1739502692.4442568,52.699949741363525,29.064188959637875,1739502692.4442596,52.699949741363525,-0.05792141736458767,1739502692.4442627,52.699949741363525,83.85349301142139,1739502692.4442654,52.699949741363525,22.911990705370705,1739502692.444267,52.699949741363525,-0.022,1739502692.4442687,52.699949741363525,3.135753926084083,1739502692.4442704,52.699949741363525,0.18113568111842318,1739502692.4442718,52.699949741363525,0.03675090626822165,1739502692.4442737,52.699949741363525,2.162753518583151,1739502692.444277,52.699949741363525,0.0,1739502692.4442782,52.699949741363525,-0.11825099688623286,1739502692.44428,52.699949741363525,3.106307740383685,1739502692.4442813,52.699949741363525,2.281004515469384 +1739502692.4641562,52.71994972229004,29.064188959637875,1739502692.4641588,52.71994972229004,-0.05792141736458767,1739502692.4641619,52.71994972229004,83.85349301142139,1739502692.4641645,52.71994972229004,22.911990705370705,1739502692.4641662,52.71994972229004,-0.022,1739502692.4641676,52.71994972229004,3.135753926084083,1739502692.4641695,52.71994972229004,0.18113568111842318,1739502692.4641707,52.71994972229004,0.03675090626822165,1739502692.4641721,52.71994972229004,2.162753518583151,1739502692.4641738,52.71994972229004,0.0,1739502692.464175,52.71994972229004,-0.11825099688623286,1739502692.4641767,52.71994972229004,3.106307740383685,1739502692.4641778,52.71994972229004,2.281004515469384 +1739502692.4842541,52.73994970321655,29.064188959637875,1739502692.484257,52.73994970321655,-0.05792141736458767,1739502692.48426,52.73994970321655,83.85349301142139,1739502692.4842632,52.73994970321655,22.911990705370705,1739502692.4842644,52.73994970321655,-0.022,1739502692.4842665,52.73994970321655,3.135753926084083,1739502692.484268,52.73994970321655,0.18113568111842318,1739502692.4842699,52.73994970321655,0.03675090626822165,1739502692.484271,52.73994970321655,2.162753518583151,1739502692.4842727,52.73994970321655,0.0,1739502692.4842741,52.73994970321655,-0.11825099688623286,1739502692.4842753,52.73994970321655,3.106307740383685,1739502692.484277,52.73994970321655,2.281004515469384 +1739502692.5043707,52.759949684143066,28.814084828268065,1739502692.5043733,52.759949684143066,-0.04907355844973704,1739502692.5043764,52.759949684143066,83.79945576160853,1739502692.504379,52.759949684143066,22.991911973424646,1739502692.5043805,52.759949684143066,-0.021686000246068083,1739502692.5043821,52.759949684143066,3.136888678479264,1739502692.5043836,52.759949684143066,0.17882960882942614,1739502692.5043848,52.759949684143066,0.04051300383618153,1739502692.5043862,52.759949684143066,2.1667471740794673,1739502692.5043879,52.759949684143066,0.0,1739502692.504389,52.759949684143066,-0.0936162383407872,1739502692.5043907,52.759949684143066,3.106168917216454,1739502692.5043921,52.759949684143066,2.268061779513149 +1739502692.5242133,52.77994966506958,28.814084828268065,1739502692.5242171,52.77994966506958,-0.04907355844973704,1739502692.5242221,52.77994966506958,83.79945576160853,1739502692.5242274,52.77994966506958,22.991911973424646,1739502692.5242305,52.77994966506958,-0.021686000246068083,1739502692.5242343,52.77994966506958,3.136888678479264,1739502692.5242379,52.77994966506958,0.17882960882942614,1739502692.5242414,52.77994966506958,0.04051300383618153,1739502692.5242448,52.77994966506958,2.1667471740794673,1739502692.5242484,52.77994966506958,0.0,1739502692.5242517,52.77994966506958,-0.10131460543368176,1739502692.5242553,52.77994966506958,3.106168917216454,1739502692.5242589,52.77994966506958,2.268061779513149 +1739502692.5442126,52.799949645996094,28.814084828268065,1739502692.5442152,52.799949645996094,-0.04907355844973704,1739502692.5442183,52.799949645996094,83.79945576160853,1739502692.544221,52.799949645996094,22.991911973424646,1739502692.5442224,52.799949645996094,-0.021686000246068083,1739502692.544224,52.799949645996094,3.136888678479264,1739502692.5442255,52.799949645996094,0.17882960882942614,1739502692.544227,52.799949645996094,0.04051300383618153,1739502692.5442283,52.799949645996094,2.1667471740794673,1739502692.54423,52.799949645996094,0.0,1739502692.5442314,52.799949645996094,-0.10131460543368176,1739502692.5442328,52.799949645996094,3.106168917216454,1739502692.5442345,52.799949645996094,2.268061779513149 +1739502692.5642092,52.81994962692261,28.814084828268065,1739502692.5642128,52.81994962692261,-0.04907355844973704,1739502692.5642176,52.81994962692261,83.79945576160853,1739502692.5642228,52.81994962692261,22.991911973424646,1739502692.5642257,52.81994962692261,-0.021686000246068083,1739502692.5642297,52.81994962692261,3.136888678479264,1739502692.564233,52.81994962692261,0.17882960882942614,1739502692.5642364,52.81994962692261,0.04051300383618153,1739502692.56424,52.81994962692261,2.1667471740794673,1739502692.5642433,52.81994962692261,0.0,1739502692.564247,52.81994962692261,-0.10131460543368176,1739502692.5642505,52.81994962692261,3.106168917216454,1739502692.5642538,52.81994962692261,2.268061779513149 +1739502692.584234,52.83994960784912,28.814084828268065,1739502692.5842369,52.83994960784912,-0.04907355844973704,1739502692.5842402,52.83994960784912,83.79945576160853,1739502692.5842433,52.83994960784912,22.991911973424646,1739502692.5842447,52.83994960784912,-0.021686000246068083,1739502692.5842469,52.83994960784912,3.136888678479264,1739502692.5842483,52.83994960784912,0.17882960882942614,1739502692.58425,52.83994960784912,0.04051300383618153,1739502692.5842512,52.83994960784912,2.1667471740794673,1739502692.5842526,52.83994960784912,0.0,1739502692.584254,52.83994960784912,-0.10131460543368176,1739502692.5842555,52.83994960784912,3.106168917216454,1739502692.5842571,52.83994960784912,2.268061779513149 +1739502692.604043,52.859949588775635,28.814084828268065,1739502692.6040454,52.859949588775635,-0.04907355844973704,1739502692.604048,52.859949588775635,83.79945576160853,1739502692.6040506,52.859949588775635,22.991911973424646,1739502692.604052,52.859949588775635,-0.021686000246068083,1739502692.6040537,52.859949588775635,3.136888678479264,1739502692.6040554,52.859949588775635,0.17882960882942614,1739502692.6040566,52.859949588775635,0.04051300383618153,1739502692.6040578,52.859949588775635,2.1667471740794673,1739502692.6040595,52.859949588775635,0.0,1739502692.6040606,52.859949588775635,-0.10131460543368176,1739502692.6040623,52.859949588775635,3.106168917216454,1739502692.6040637,52.859949588775635,2.268061779513149 +1739502692.6242244,52.87994956970215,28.56529521473258,1739502692.6242273,52.87994956970215,-0.04025872219436444,1739502692.6242304,52.87994956970215,84.35605233338389,1739502692.6242332,52.87994956970215,22.45720568172001,1739502692.6242347,52.87994956970215,-0.02,1739502692.6242366,52.87994956970215,3.138275962208658,1739502692.6242378,52.87994956970215,0.1958512523162258,1739502692.6242394,52.87994956970215,0.04031306931008312,1739502692.6242406,52.87994956970215,2.1374418783014675,1739502692.624242,52.87994956970215,0.0,1739502692.6242435,52.87994956970215,-0.1280291097755638,1739502692.624245,52.87994956970215,3.1062064012380866,1739502692.6242466,52.87994956970215,2.257122699996629 +1739502692.6439893,52.89994955062866,28.56529521473258,1739502692.6439915,52.89994955062866,-0.04025872219436444,1739502692.6439946,52.89994955062866,84.35605233338389,1739502692.6439974,52.89994955062866,22.45720568172001,1739502692.6439986,52.89994955062866,-0.02,1739502692.6440003,52.89994955062866,3.138275962208658,1739502692.6440017,52.89994955062866,0.1958512523162258,1739502692.6440032,52.89994955062866,0.04031306931008312,1739502692.6440043,52.89994955062866,2.1374418783014675,1739502692.6440058,52.89994955062866,0.0,1739502692.6440072,52.89994955062866,-0.11968082169516148,1739502692.6440086,52.89994955062866,3.1062064012380866,1739502692.6440103,52.89994955062866,2.257122699996629 +1739502692.6641407,52.919949531555176,28.56529521473258,1739502692.6641436,52.919949531555176,-0.04025872219436444,1739502692.6641467,52.919949531555176,84.35605233338389,1739502692.6641493,52.919949531555176,22.45720568172001,1739502692.6641505,52.919949531555176,-0.02,1739502692.6641524,52.919949531555176,3.138275962208658,1739502692.6641538,52.919949531555176,0.1958512523162258,1739502692.6641552,52.919949531555176,0.04031306931008312,1739502692.6641564,52.919949531555176,2.1374418783014675,1739502692.6641579,52.919949531555176,0.0,1739502692.6641593,52.919949531555176,-0.11968082169516148,1739502692.6641607,52.919949531555176,3.1062064012380866,1739502692.6641622,52.919949531555176,2.257122699996629 +1739502692.683962,52.93994951248169,28.56529521473258,1739502692.6839643,52.93994951248169,-0.04025872219436444,1739502692.6839669,52.93994951248169,84.35605233338389,1739502692.6839695,52.93994951248169,22.45720568172001,1739502692.6839712,52.93994951248169,-0.02,1739502692.6839728,52.93994951248169,3.138275962208658,1739502692.683974,52.93994951248169,0.1958512523162258,1739502692.6839757,52.93994951248169,0.04031306931008312,1739502692.6839767,52.93994951248169,2.1374418783014675,1739502692.6839783,52.93994951248169,0.0,1739502692.6839797,52.93994951248169,-0.11968082169516148,1739502692.683981,52.93994951248169,3.1062064012380866,1739502692.6839826,52.93994951248169,2.257122699996629 +1739502692.704017,52.9599494934082,28.56529521473258,1739502692.7040193,52.9599494934082,-0.04025872219436444,1739502692.704022,52.9599494934082,84.35605233338389,1739502692.7040248,52.9599494934082,22.45720568172001,1739502692.7040265,52.9599494934082,-0.02,1739502692.7040281,52.9599494934082,3.138275962208658,1739502692.7040293,52.9599494934082,0.1958512523162258,1739502692.7040308,52.9599494934082,0.04031306931008312,1739502692.704032,52.9599494934082,2.1374418783014675,1739502692.7040336,52.9599494934082,0.0,1739502692.7040348,52.9599494934082,-0.11968082169516148,1739502692.7040362,52.9599494934082,3.1062064012380866,1739502692.7040377,52.9599494934082,2.257122699996629 +1739502692.724365,52.97994947433472,28.31781769232265,1739502692.7243676,52.97994947433472,-0.03150446107716576,1739502692.724371,52.97994947433472,84.38501595776695,1739502692.7243743,52.97994947433472,22.454393803718755,1739502692.7243757,52.97994947433472,-0.02,1739502692.7243776,52.97994947433472,3.1396305838959155,1739502692.724379,52.97994947433472,0.1955951696792149,1739502692.7243807,52.97994947433472,0.04369023536468364,1739502692.724382,52.97994947433472,2.1378798125610023,1739502692.724384,52.97994947433472,0.0,1739502692.7243853,52.97994947433472,-0.1000243686364298,1739502692.7243872,52.97994947433472,3.106265933656267,1739502692.7243886,52.97994947433472,2.244046826805718 +1739502692.7441013,52.99994945526123,28.31781769232265,1739502692.7441041,52.99994945526123,-0.03150446107716576,1739502692.7441072,52.99994945526123,84.38501595776695,1739502692.7441103,52.99994945526123,22.454393803718755,1739502692.7441118,52.99994945526123,-0.02,1739502692.7441137,52.99994945526123,3.1396305838959155,1739502692.744115,52.99994945526123,0.1955951696792149,1739502692.7441168,52.99994945526123,0.04369023536468364,1739502692.7441182,52.99994945526123,2.1378798125610023,1739502692.74412,52.99994945526123,0.0,1739502692.7441213,52.99994945526123,-0.10616701424471575,1739502692.744123,52.99994945526123,3.106265933656267,1739502692.7441244,52.99994945526123,2.244046826805718 +1739502692.764389,53.019949436187744,28.31781769232265,1739502692.764392,53.019949436187744,-0.03150446107716576,1739502692.7643952,53.019949436187744,84.38501595776695,1739502692.7643983,53.019949436187744,22.454393803718755,1739502692.7643995,53.019949436187744,-0.02,1739502692.7644017,53.019949436187744,3.1396305838959155,1739502692.764403,53.019949436187744,0.1955951696792149,1739502692.7644048,53.019949436187744,0.04369023536468364,1739502692.764406,53.019949436187744,2.1378798125610023,1739502692.7644083,53.019949436187744,0.0,1739502692.7644095,53.019949436187744,-0.10616701424471575,1739502692.7644114,53.019949436187744,3.106265933656267,1739502692.764413,53.019949436187744,2.244046826805718 +1739502692.784107,53.03994941711426,28.31781769232265,1739502692.7841094,53.03994941711426,-0.03150446107716576,1739502692.7841127,53.03994941711426,84.38501595776695,1739502692.7841158,53.03994941711426,22.454393803718755,1739502692.7841172,53.03994941711426,-0.02,1739502692.7841191,53.03994941711426,3.1396305838959155,1739502692.7841206,53.03994941711426,0.1955951696792149,1739502692.7841222,53.03994941711426,0.04369023536468364,1739502692.7841237,53.03994941711426,2.1378798125610023,1739502692.7841253,53.03994941711426,0.0,1739502692.7841268,53.03994941711426,-0.10616701424471575,1739502692.7841282,53.03994941711426,3.106265933656267,1739502692.7841303,53.03994941711426,2.244046826805718 +1739502692.8041131,53.05994939804077,28.31781769232265,1739502692.8041155,53.05994939804077,-0.03150446107716576,1739502692.8041186,53.05994939804077,84.38501595776695,1739502692.8041215,53.05994939804077,22.454393803718755,1739502692.8041232,53.05994939804077,-0.02,1739502692.8041246,53.05994939804077,3.1396305838959155,1739502692.8041263,53.05994939804077,0.1955951696792149,1739502692.8041277,53.05994939804077,0.04369023536468364,1739502692.8041296,53.05994939804077,2.1378798125610023,1739502692.8041313,53.05994939804077,0.0,1739502692.804133,53.05994939804077,-0.10616701424471575,1739502692.8041344,53.05994939804077,3.106265933656267,1739502692.8041363,53.05994939804077,2.244046826805718 +1739502692.824305,53.079949378967285,28.31781769232265,1739502692.824308,53.079949378967285,-0.03150446107716576,1739502692.824311,53.079949378967285,84.38501595776695,1739502692.824314,53.079949378967285,22.454393803718755,1739502692.8243158,53.079949378967285,-0.02,1739502692.8243177,53.079949378967285,3.1396305838959155,1739502692.8243196,53.079949378967285,0.1955951696792149,1739502692.824321,53.079949378967285,0.04369023536468364,1739502692.8243222,53.079949378967285,2.1378798125610023,1739502692.8243241,53.079949378967285,0.0,1739502692.8243253,53.079949378967285,-0.10616701424471575,1739502692.824327,53.079949378967285,3.106265933656267,1739502692.8243284,53.079949378967285,2.244046826805718 +1739502692.8441527,53.0999493598938,28.07169612949886,1739502692.8441548,53.0999493598938,-0.022826182776424453,1739502692.8441582,53.0999493598938,84.41382085889565,1739502692.8441613,53.0999493598938,22.448591738265076,1739502692.8441625,53.0999493598938,-0.02,1739502692.8441646,53.0999493598938,3.1410900517631477,1739502692.844166,53.0999493598938,0.19465933962906945,1739502692.8441677,53.0999493598938,0.047276804051635285,1739502692.844169,53.0999493598938,2.139480965586817,1739502692.8441708,53.0999493598938,0.0,1739502692.844172,53.0999493598938,-0.0871087236727949,1739502692.844174,53.0999493598938,3.1064653672295077,1739502692.8441753,53.0999493598938,2.2325454089682113 +1739502692.8642972,53.11994934082031,28.07169612949886,1739502692.8643,53.11994934082031,-0.022826182776424453,1739502692.8643034,53.11994934082031,84.41382085889565,1739502692.8643064,53.11994934082031,22.448591738265076,1739502692.8643079,53.11994934082031,-0.02,1739502692.8643098,53.11994934082031,3.1410900517631477,1739502692.8643115,53.11994934082031,0.19465933962906945,1739502692.8643131,53.11994934082031,0.047276804051635285,1739502692.8643146,53.11994934082031,2.139480965586817,1739502692.8643167,53.11994934082031,0.0,1739502692.8643181,53.11994934082031,-0.0930644433813943,1739502692.8643198,53.11994934082031,3.1064653672295077,1739502692.8643212,53.11994934082031,2.2325454089682113 +1739502692.8841848,53.139949321746826,28.07169612949886,1739502692.8841875,53.139949321746826,-0.022826182776424453,1739502692.8841906,53.139949321746826,84.41382085889565,1739502692.8841934,53.139949321746826,22.448591738265076,1739502692.884195,53.139949321746826,-0.02,1739502692.8841968,53.139949321746826,3.1410900517631477,1739502692.8841984,53.139949321746826,0.19465933962906945,1739502692.8841999,53.139949321746826,0.047276804051635285,1739502692.8842015,53.139949321746826,2.139480965586817,1739502692.8842032,53.139949321746826,0.0,1739502692.8842049,53.139949321746826,-0.0930644433813943,1739502692.8842063,53.139949321746826,3.1064653672295077,1739502692.884208,53.139949321746826,2.2325454089682113 +1739502692.9040585,53.15994930267334,28.07169612949886,1739502692.9040604,53.15994930267334,-0.022826182776424453,1739502692.9040635,53.15994930267334,84.41382085889565,1739502692.9040668,53.15994930267334,22.448591738265076,1739502692.9040685,53.15994930267334,-0.02,1739502692.9040701,53.15994930267334,3.1410900517631477,1739502692.9040716,53.15994930267334,0.19465933962906945,1739502692.9040732,53.15994930267334,0.047276804051635285,1739502692.9040747,53.15994930267334,2.139480965586817,1739502692.9040766,53.15994930267334,0.0,1739502692.9040778,53.15994930267334,-0.0930644433813943,1739502692.9040797,53.15994930267334,3.1064653672295077,1739502692.904081,53.15994930267334,2.2325454089682113 +1739502692.9242923,53.17994928359985,28.07169612949886,1739502692.9242952,53.17994928359985,-0.022826182776424453,1739502692.9242988,53.17994928359985,84.41382085889565,1739502692.9243019,53.17994928359985,22.448591738265076,1739502692.924303,53.17994928359985,-0.02,1739502692.924305,53.17994928359985,3.1410900517631477,1739502692.9243064,53.17994928359985,0.19465933962906945,1739502692.924308,53.17994928359985,0.047276804051635285,1739502692.9243095,53.17994928359985,2.139480965586817,1739502692.924311,53.17994928359985,0.0,1739502692.9243126,53.17994928359985,-0.0930644433813943,1739502692.9243143,53.17994928359985,3.1064653672295077,1739502692.924316,53.17994928359985,2.2325454089682113 +1739502692.9441729,53.19994926452637,27.826778362855208,1739502692.9441752,53.19994926452637,-0.014254532761818872,1739502692.9441783,53.19994926452637,85.04492056436618,1739502692.9441812,53.19994926452637,21.837889103231497,1739502692.944183,53.19994926452637,-0.016,1739502692.9441848,53.19994926452637,-3.1413012026857787,1739502692.9441864,53.19994926452637,0.20999790446738956,1739502692.9441879,53.19994926452637,0.04496256299177024,1739502692.944189,53.19994926452637,2.1133881296476726,1739502692.944191,53.19994926452637,0.0,1739502692.9441924,53.19994926452637,-0.11619636243460056,1739502692.9441943,53.19994926452637,3.1068123335510975,1739502692.9441957,53.19994926452637,2.222355762638622 +1739502692.9642997,53.21994924545288,27.826778362855208,1739502692.9643073,53.21994924545288,-0.014254532761818872,1739502692.9643202,53.21994924545288,85.04492056436618,1739502692.9643235,53.21994924545288,21.837889103231497,1739502692.9643373,53.21994924545288,-0.016,1739502692.96434,53.21994924545288,-3.1413012026857787,1739502692.964344,53.21994924545288,0.20999790446738956,1739502692.9643474,53.21994924545288,0.04496256299177024,1739502692.9643507,53.21994924545288,2.1133881296476726,1739502692.9643548,53.21994924545288,0.0,1739502692.9643674,53.21994924545288,-0.10896763299094925,1739502692.964369,53.21994924545288,3.1068123335510975,1739502692.9643712,53.21994924545288,2.222355762638622 +1739502692.9841425,53.239949226379395,27.826778362855208,1739502692.984145,53.239949226379395,-0.014254532761818872,1739502692.984148,53.239949226379395,85.04492056436618,1739502692.984151,53.239949226379395,21.837889103231497,1739502692.9841523,53.239949226379395,-0.016,1739502692.9841542,53.239949226379395,-3.1413012026857787,1739502692.9841557,53.239949226379395,0.20999790446738956,1739502692.984157,53.239949226379395,0.04496256299177024,1739502692.9841585,53.239949226379395,2.1133881296476726,1739502692.9841602,53.239949226379395,0.0,1739502692.9841616,53.239949226379395,-0.10896763299094925,1739502692.984163,53.239949226379395,3.1068123335510975,1739502692.9841647,53.239949226379395,2.222355762638622 +1739502693.0042088,53.25994920730591,27.826778362855208,1739502693.0042114,53.25994920730591,-0.014254532761818872,1739502693.0042145,53.25994920730591,85.04492056436618,1739502693.0042176,53.25994920730591,21.837889103231497,1739502693.004219,53.25994920730591,-0.016,1739502693.004221,53.25994920730591,-3.1413012026857787,1739502693.0042224,53.25994920730591,0.20999790446738956,1739502693.004224,53.25994920730591,0.04496256299177024,1739502693.0042255,53.25994920730591,2.1133881296476726,1739502693.0042274,53.25994920730591,0.0,1739502693.0042286,53.25994920730591,-0.10896763299094925,1739502693.0042303,53.25994920730591,3.1068123335510975,1739502693.0042315,53.25994920730591,2.222355762638622 +1739502693.0243578,53.27994918823242,27.826778362855208,1739502693.024363,53.27994918823242,-0.014254532761818872,1739502693.0243695,53.27994918823242,85.04492056436618,1739502693.0243769,53.27994918823242,21.837889103231497,1739502693.0243807,53.27994918823242,-0.016,1739502693.0243857,53.27994918823242,-3.1413012026857787,1739502693.0243907,53.27994918823242,0.20999790446738956,1739502693.0243948,53.27994918823242,0.04496256299177024,1739502693.0243983,53.27994918823242,2.1133881296476726,1739502693.0244024,53.27994918823242,0.0,1739502693.024406,53.27994918823242,-0.10896763299094925,1739502693.0244098,53.27994918823242,3.1068123335510975,1739502693.0244136,53.27994918823242,2.222355762638622 +1739502693.0440335,53.299949169158936,27.826778362855208,1739502693.0440361,53.299949169158936,-0.014254532761818872,1739502693.0440392,53.299949169158936,85.04492056436618,1739502693.0440423,53.299949169158936,21.837889103231497,1739502693.0440435,53.299949169158936,-0.016,1739502693.0440457,53.299949169158936,-3.1413012026857787,1739502693.044047,53.299949169158936,0.20999790446738956,1739502693.0440483,53.299949169158936,0.04496256299177024,1739502693.04405,53.299949169158936,2.1133881296476726,1739502693.0440514,53.299949169158936,0.0,1739502693.044053,53.299949169158936,-0.10896763299094925,1739502693.0440547,53.299949169158936,3.1068123335510975,1739502693.0440567,53.299949169158936,2.222355762638622 +1739502693.0644453,53.31994915008545,27.58307653651783,1739502693.0644493,53.31994915008545,-0.0058176167547916435,1739502693.0644546,53.31994915008545,85.06710586747889,1739502693.0644605,53.31994915008545,21.839850450379863,1739502693.0644636,53.31994915008545,-0.016,1739502693.064468,53.31994915008545,-3.1398197175389186,1739502693.0644715,53.31994915008545,0.2076840474058266,1739502693.064475,53.31994915008545,0.04835190178068724,1739502693.0644789,53.31994915008545,2.117303815102238,1739502693.064483,53.31994915008545,0.0,1739502693.0644867,53.31994915008545,-0.08571088339065015,1739502693.0644906,53.31994915008545,3.10719619501144,1739502693.0644941,53.31994915008545,2.2102824375080825 +1739502693.0841088,53.33994913101196,27.58307653651783,1739502693.0841115,53.33994913101196,-0.0058176167547916435,1739502693.0841143,53.33994913101196,85.06710586747889,1739502693.0841172,53.33994913101196,21.839850450379863,1739502693.0841188,53.33994913101196,-0.016,1739502693.0841205,53.33994913101196,-3.1398197175389186,1739502693.0841222,53.33994913101196,0.2076840474058266,1739502693.0841238,53.33994913101196,0.04835190178068724,1739502693.0841253,53.33994913101196,2.117303815102238,1739502693.084127,53.33994913101196,0.0,1739502693.0841281,53.33994913101196,-0.09297862240584465,1739502693.0841298,53.33994913101196,3.10719619501144,1739502693.0841312,53.33994913101196,2.2102824375080825 +1739502693.1041632,53.35994911193848,27.58307653651783,1739502693.1041653,53.35994911193848,-0.0058176167547916435,1739502693.1041687,53.35994911193848,85.06710586747889,1739502693.1041718,53.35994911193848,21.839850450379863,1739502693.1041734,53.35994911193848,-0.016,1739502693.104175,53.35994911193848,-3.1398197175389186,1739502693.1041765,53.35994911193848,0.2076840474058266,1739502693.1041782,53.35994911193848,0.04835190178068724,1739502693.1041796,53.35994911193848,2.117303815102238,1739502693.1041813,53.35994911193848,0.0,1739502693.1041827,53.35994911193848,-0.09297862240584465,1739502693.1041846,53.35994911193848,3.10719619501144,1739502693.1041858,53.35994911193848,2.2102824375080825 +1739502693.1250803,53.37994909286499,27.58307653651783,1739502693.1250844,53.37994909286499,-0.0058176167547916435,1739502693.1250885,53.37994909286499,85.06710586747889,1739502693.1250925,53.37994909286499,21.839850450379863,1739502693.1250944,53.37994909286499,-0.016,1739502693.125097,53.37994909286499,-3.1398197175389186,1739502693.1250987,53.37994909286499,0.2076840474058266,1739502693.1251009,53.37994909286499,0.04835190178068724,1739502693.1251023,53.37994909286499,2.117303815102238,1739502693.125105,53.37994909286499,0.0,1739502693.1251066,53.37994909286499,-0.09297862240584465,1739502693.1251087,53.37994909286499,3.10719619501144,1739502693.1251109,53.37994909286499,2.2102824375080825 +1739502693.1447904,53.399949073791504,27.58307653651783,1739502693.1447942,53.399949073791504,-0.0058176167547916435,1739502693.1447983,53.399949073791504,85.06710586747889,1739502693.1448023,53.399949073791504,21.839850450379863,1739502693.144804,53.399949073791504,-0.016,1739502693.1448066,53.399949073791504,-3.1398197175389186,1739502693.1448085,53.399949073791504,0.2076840474058266,1739502693.1448104,53.399949073791504,0.04835190178068724,1739502693.1448123,53.399949073791504,2.117303815102238,1739502693.1448143,53.399949073791504,0.0,1739502693.1448162,53.399949073791504,-0.09297862240584465,1739502693.144818,53.399949073791504,3.10719619501144,1739502693.1448202,53.399949073791504,2.2102824375080825 +1739502693.164574,53.41994905471802,27.340599944413864,1739502693.164577,53.41994905471802,0.0024836875830622773,1739502693.1645808,53.41994905471802,85.08917953866468,1739502693.1645846,53.41994905471802,21.838141891356408,1739502693.1645865,53.41994905471802,-0.016,1739502693.1645885,53.41994905471802,-3.138233497030691,1739502693.1645906,53.41994905471802,0.20558980328129692,1739502693.1645923,53.41994905471802,0.05214355924277005,1739502693.1645942,53.41994905471802,2.1208541092045032,1739502693.1645968,53.41994905471802,0.0,1739502693.1645985,53.41994905471802,-0.07300356164054181,1739502693.1646004,53.41994905471802,3.1075800564717824,1739502693.1646023,53.41994905471802,2.2000998814269144 +1739502693.184808,53.43994903564453,27.340599944413864,1739502693.1848116,53.43994903564453,0.0024836875830622773,1739502693.1848154,53.43994903564453,85.08917953866468,1739502693.184819,53.43994903564453,21.838141891356408,1739502693.1848207,53.43994903564453,-0.016,1739502693.184823,53.43994903564453,-3.138233497030691,1739502693.1848252,53.43994903564453,0.20558980328129692,1739502693.1848269,53.43994903564453,0.05214355924277005,1739502693.1848285,53.43994903564453,2.1208541092045032,1739502693.1848307,53.43994903564453,0.0,1739502693.1848326,53.43994903564453,-0.07924577222241114,1739502693.1848345,53.43994903564453,3.1075800564717824,1739502693.1848364,53.43994903564453,2.2000998814269144 +1739502693.2047808,53.459949016571045,27.340599944413864,1739502693.2047842,53.459949016571045,0.0024836875830622773,1739502693.2047884,53.459949016571045,85.08917953866468,1739502693.2047925,53.459949016571045,21.838141891356408,1739502693.2047944,53.459949016571045,-0.016,1739502693.204797,53.459949016571045,-3.138233497030691,1739502693.204799,53.459949016571045,0.20558980328129692,1739502693.2048008,53.459949016571045,0.05214355924277005,1739502693.2048025,53.459949016571045,2.1208541092045032,1739502693.2048047,53.459949016571045,0.0,1739502693.2048063,53.459949016571045,-0.07924577222241114,1739502693.2048085,53.459949016571045,3.1075800564717824,1739502693.2048104,53.459949016571045,2.2000998814269144 +1739502693.2246327,53.47994899749756,27.340599944413864,1739502693.2246358,53.47994899749756,0.0024836875830622773,1739502693.2246397,53.47994899749756,85.08917953866468,1739502693.2246432,53.47994899749756,21.838141891356408,1739502693.2246451,53.47994899749756,-0.016,1739502693.2246473,53.47994899749756,-3.138233497030691,1739502693.224649,53.47994899749756,0.20558980328129692,1739502693.2246509,53.47994899749756,0.05214355924277005,1739502693.2246525,53.47994899749756,2.1208541092045032,1739502693.2246547,53.47994899749756,0.0,1739502693.2246563,53.47994899749756,-0.07924577222241114,1739502693.2246583,53.47994899749756,3.1075800564717824,1739502693.22466,53.47994899749756,2.2000998814269144 +1739502693.2445765,53.49994897842407,27.340599944413864,1739502693.2445798,53.49994897842407,0.0024836875830622773,1739502693.2445838,53.49994897842407,85.08917953866468,1739502693.2445877,53.49994897842407,21.838141891356408,1739502693.2445896,53.49994897842407,-0.016,1739502693.244592,53.49994897842407,-3.138233497030691,1739502693.2445936,53.49994897842407,0.20558980328129692,1739502693.2445958,53.49994897842407,0.05214355924277005,1739502693.2445972,53.49994897842407,2.1208541092045032,1739502693.2445996,53.49994897842407,0.0,1739502693.244601,53.49994897842407,-0.07924577222241114,1739502693.2446032,53.49994897842407,3.1075800564717824,1739502693.2446053,53.49994897842407,2.2000998814269144 +1739502693.2651188,53.519948959350586,27.340599944413864,1739502693.2651227,53.519948959350586,0.0024836875830622773,1739502693.265127,53.519948959350586,85.08917953866468,1739502693.2651308,53.519948959350586,21.838141891356408,1739502693.265133,53.519948959350586,-0.016,1739502693.2651353,53.519948959350586,-3.138233497030691,1739502693.2651377,53.519948959350586,0.20558980328129692,1739502693.2651393,53.519948959350586,0.05214355924277005,1739502693.2651412,53.519948959350586,2.1208541092045032,1739502693.2651436,53.519948959350586,0.0,1739502693.2651453,53.519948959350586,-0.07924577222241114,1739502693.2651474,53.519948959350586,3.1075800564717824,1739502693.2651494,53.519948959350586,2.2000998814269144 +1739502693.2847912,53.5399489402771,27.099149627479964,1739502693.2847948,53.5399489402771,0.010643899496992404,1739502693.2847986,53.5399489402771,85.62591484748987,1739502693.2848027,53.5399489402771,21.31851151946758,1739502693.2848046,53.5399489402771,-0.016,1739502693.284807,53.5399489402771,-3.136983523884064,1739502693.2848089,53.5399489402771,0.22017550363661234,1739502693.2848108,53.5399489402771,0.050597405416012285,1739502693.2848125,53.5399489402771,2.0962506179946807,1739502693.2848146,53.5399489402771,0.0,1739502693.2848163,53.5399489402771,-0.10259272135001363,1739502693.2848184,53.5399489402771,3.1081045300602463,1739502693.2848203,53.5399489402771,2.1915474129587365 +1739502693.304666,53.55994892120361,27.099149627479964,1739502693.3046696,53.55994892120361,0.010643899496992404,1739502693.304695,53.55994892120361,85.62591484748987,1739502693.3047054,53.55994892120361,21.31851151946758,1739502693.3047082,53.55994892120361,-0.016,1739502693.304711,53.55994892120361,-3.136983523884064,1739502693.3047132,53.55994892120361,0.22017550363661234,1739502693.3047152,53.55994892120361,0.050597405416012285,1739502693.304717,53.55994892120361,2.0962506179946807,1739502693.3047192,53.55994892120361,0.0,1739502693.3047209,53.55994892120361,-0.09529679496405574,1739502693.3047228,53.55994892120361,3.1081045300602463,1739502693.3047247,53.55994892120361,2.1915474129587365 +1739502693.3251333,53.57994890213013,27.099149627479964,1739502693.3251374,53.57994890213013,0.010643899496992404,1739502693.3251429,53.57994890213013,85.62591484748987,1739502693.325147,53.57994890213013,21.31851151946758,1739502693.3251488,53.57994890213013,-0.016,1739502693.3251512,53.57994890213013,-3.136983523884064,1739502693.3251534,53.57994890213013,0.22017550363661234,1739502693.325155,53.57994890213013,0.050597405416012285,1739502693.3251572,53.57994890213013,2.0962506179946807,1739502693.325159,53.57994890213013,0.0,1739502693.3251612,53.57994890213013,-0.09529679496405574,1739502693.3251634,53.57994890213013,3.1081045300602463,1739502693.3251653,53.57994890213013,2.1915474129587365 +1739502693.344808,53.59994888305664,27.099149627479964,1739502693.3448114,53.59994888305664,0.010643899496992404,1739502693.3448153,53.59994888305664,85.62591484748987,1739502693.3448193,53.59994888305664,21.31851151946758,1739502693.344821,53.59994888305664,-0.016,1739502693.3448234,53.59994888305664,-3.136983523884064,1739502693.344825,53.59994888305664,0.22017550363661234,1739502693.3448267,53.59994888305664,0.050597405416012285,1739502693.3448284,53.59994888305664,2.0962506179946807,1739502693.3448305,53.59994888305664,0.0,1739502693.3448322,53.59994888305664,-0.09529679496405574,1739502693.344834,53.59994888305664,3.1081045300602463,1739502693.3448362,53.59994888305664,2.1915474129587365 +1739502693.3650017,53.619948863983154,27.099149627479964,1739502693.365005,53.619948863983154,0.010643899496992404,1739502693.365009,53.619948863983154,85.62591484748987,1739502693.3650126,53.619948863983154,21.31851151946758,1739502693.3650146,53.619948863983154,-0.016,1739502693.3650172,53.619948863983154,-3.136983523884064,1739502693.3650188,53.619948863983154,0.22017550363661234,1739502693.365021,53.619948863983154,0.050597405416012285,1739502693.3650224,53.619948863983154,2.0962506179946807,1739502693.3650248,53.619948863983154,0.0,1739502693.3650265,53.619948863983154,-0.09529679496405574,1739502693.3650286,53.619948863983154,3.1081045300602463,1739502693.3650308,53.619948863983154,2.1915474129587365 +1739502693.3847902,53.63994884490967,26.85873053082815,1739502693.3847938,53.63994884490967,0.018638339146165528,1739502693.3847978,53.63994884490967,85.64756056062818,1739502693.3848016,53.63994884490967,21.31768866912046,1739502693.3848033,53.63994884490967,-0.016,1739502693.384806,53.63994884490967,-3.1353415028453417,1739502693.3848076,53.63994884490967,0.21711647872860387,1739502693.3848095,53.63994884490967,0.05430086426042247,1739502693.3848112,53.63994884490967,2.1013868865037244,1739502693.3848133,53.63994884490967,0.0,1739502693.3848152,53.63994884490967,-0.07268195199936457,1739502693.3848171,53.63994884490967,3.1086512057394478,1739502693.384819,53.63994884490967,2.181135981563135 +1739502693.4047172,53.65994882583618,26.85873053082815,1739502693.4047208,53.65994882583618,0.018638339146165528,1739502693.4047248,53.65994882583618,85.64756056062818,1739502693.4047284,53.65994882583618,21.31768866912046,1739502693.40473,53.65994882583618,-0.016,1739502693.4047325,53.65994882583618,-3.1353415028453417,1739502693.4047344,53.65994882583618,0.21711647872860387,1739502693.4047363,53.65994882583618,0.05430086426042247,1739502693.404738,53.65994882583618,2.1013868865037244,1739502693.40474,53.65994882583618,0.0,1739502693.4047415,53.65994882583618,-0.07974909505941064,1739502693.4047437,53.65994882583618,3.1086512057394478,1739502693.4047456,53.65994882583618,2.181135981563135 +1739502693.4252315,53.679948806762695,26.85873053082815,1739502693.4252348,53.679948806762695,0.018638339146165528,1739502693.4252393,53.679948806762695,85.64756056062818,1739502693.4252431,53.679948806762695,21.31768866912046,1739502693.4252446,53.679948806762695,-0.016,1739502693.4252472,53.679948806762695,-3.1353415028453417,1739502693.425249,53.679948806762695,0.21711647872860387,1739502693.4252508,53.679948806762695,0.05430086426042247,1739502693.4252527,53.679948806762695,2.1013868865037244,1739502693.4252548,53.679948806762695,0.0,1739502693.4252567,53.679948806762695,-0.07974909505941064,1739502693.4252586,53.679948806762695,3.1086512057394478,1739502693.4252605,53.679948806762695,2.181135981563135 +1739502693.444713,53.69994878768921,26.85873053082815,1739502693.4447165,53.69994878768921,0.018638339146165528,1739502693.444721,53.69994878768921,85.64756056062818,1739502693.4447248,53.69994878768921,21.31768866912046,1739502693.4447267,53.69994878768921,-0.016,1739502693.444729,53.69994878768921,-3.1353415028453417,1739502693.4447312,53.69994878768921,0.21711647872860387,1739502693.444733,53.69994878768921,0.05430086426042247,1739502693.4447348,53.69994878768921,2.1013868865037244,1739502693.4447367,53.69994878768921,0.0,1739502693.4447386,53.69994878768921,-0.07974909505941064,1739502693.4447403,53.69994878768921,3.1086512057394478,1739502693.4447424,53.69994878768921,2.181135981563135 +1739502693.4652364,53.71994876861572,26.85873053082815,1739502693.4652402,53.71994876861572,0.018638339146165528,1739502693.4652448,53.71994876861572,85.64756056062818,1739502693.4652486,53.71994876861572,21.31768866912046,1739502693.4652503,53.71994876861572,-0.016,1739502693.4652526,53.71994876861572,-3.1353415028453417,1739502693.4652543,53.71994876861572,0.21711647872860387,1739502693.4652562,53.71994876861572,0.05430086426042247,1739502693.465258,53.71994876861572,2.1013868865037244,1739502693.46526,53.71994876861572,0.0,1739502693.465262,53.71994876861572,-0.07974909505941064,1739502693.465264,53.71994876861572,3.1086512057394478,1739502693.4652662,53.71994876861572,2.181135981563135 +1739502693.4851527,53.739948749542236,26.85873053082815,1739502693.4851563,53.739948749542236,0.018638339146165528,1739502693.4851604,53.739948749542236,85.64756056062818,1739502693.485164,53.739948749542236,21.31768866912046,1739502693.4851658,53.739948749542236,-0.016,1739502693.4851682,53.739948749542236,-3.1353415028453417,1739502693.4851701,53.739948749542236,0.21711647872860387,1739502693.485172,53.739948749542236,0.05430086426042247,1739502693.4851735,53.739948749542236,2.1013868865037244,1739502693.4851756,53.739948749542236,0.0,1739502693.4851773,53.739948749542236,-0.07974909505941064,1739502693.4851797,53.739948749542236,3.1086512057394478,1739502693.4851813,53.739948749542236,2.181135981563135 +1739502693.5049045,53.75994873046875,26.619357339301683,1739502693.504908,53.75994873046875,0.0264597308979706,1739502693.504912,53.75994873046875,86.08372232054519,1739502693.5049157,53.75994873046875,20.898714220806816,1739502693.5049176,53.75994873046875,-0.017,1739502693.5049198,53.75994873046875,-3.133995798840719,1739502693.5049217,53.75994873046875,0.22829984249812163,1739502693.5049233,53.75994873046875,0.05356805739193359,1739502693.504925,53.75994873046875,2.0826702780270905,1739502693.504927,53.75994873046875,0.0,1739502693.5049286,53.75994873046875,-0.09447669996534196,1739502693.5049307,53.75994873046875,3.1092719870687766,1739502693.5049326,53.75994873046875,2.1725445984417737 +1739502693.5249982,53.779948711395264,26.619357339301683,1739502693.525002,53.779948711395264,0.0264597308979706,1739502693.525006,53.779948711395264,86.08372232054519,1739502693.5250099,53.779948711395264,20.898714220806816,1739502693.5250118,53.779948711395264,-0.017,1739502693.5250142,53.779948711395264,-3.133995798840719,1739502693.525016,53.779948711395264,0.22829984249812163,1739502693.5250185,53.779948711395264,0.05356805739193359,1739502693.5250201,53.779948711395264,2.0826702780270905,1739502693.5250223,53.779948711395264,0.0,1739502693.525024,53.779948711395264,-0.08987432041468324,1739502693.525026,53.779948711395264,3.1092719870687766,1739502693.5250285,53.779948711395264,2.1725445984417737 +1739502693.5447743,53.79994869232178,26.619357339301683,1739502693.5447779,53.79994869232178,0.0264597308979706,1739502693.544782,53.79994869232178,86.08372232054519,1739502693.5447857,53.79994869232178,20.898714220806816,1739502693.5447874,53.79994869232178,-0.017,1739502693.5447898,53.79994869232178,-3.133995798840719,1739502693.5447917,53.79994869232178,0.22829984249812163,1739502693.5447934,53.79994869232178,0.05356805739193359,1739502693.544795,53.79994869232178,2.0826702780270905,1739502693.5447974,53.79994869232178,0.0,1739502693.5447993,53.79994869232178,-0.08987432041468324,1739502693.544801,53.79994869232178,3.1092719870687766,1739502693.5448031,53.79994869232178,2.1725445984417737 +1739502693.5647416,53.81994867324829,26.619357339301683,1739502693.5647447,53.81994867324829,0.0264597308979706,1739502693.5647485,53.81994867324829,86.08372232054519,1739502693.564752,53.81994867324829,20.898714220806816,1739502693.564754,53.81994867324829,-0.017,1739502693.564756,53.81994867324829,-3.133995798840719,1739502693.5647578,53.81994867324829,0.22829984249812163,1739502693.5647595,53.81994867324829,0.05356805739193359,1739502693.5647614,53.81994867324829,2.0826702780270905,1739502693.5647633,53.81994867324829,0.0,1739502693.564765,53.81994867324829,-0.08987432041468324,1739502693.564767,53.81994867324829,3.1092719870687766,1739502693.5647688,53.81994867324829,2.1725445984417737 +1739502693.584669,53.839948654174805,26.619357339301683,1739502693.5846913,53.839948654174805,0.0264597308979706,1739502693.5846956,53.839948654174805,86.08372232054519,1739502693.5846996,53.839948654174805,20.898714220806816,1739502693.5847015,53.839948654174805,-0.017,1739502693.5847037,53.839948654174805,-3.133995798840719,1739502693.5847058,53.839948654174805,0.22829984249812163,1739502693.5847075,53.839948654174805,0.05356805739193359,1739502693.5847094,53.839948654174805,2.0826702780270905,1739502693.5847113,53.839948654174805,0.0,1739502693.5847132,53.839948654174805,-0.08987432041468324,1739502693.5847154,53.839948654174805,3.1092719870687766,1739502693.584717,53.839948654174805,2.1725445984417737 +1739502693.6047533,53.85994863510132,26.38098964360499,1739502693.604756,53.85994863510132,0.034098539524910265,1739502693.6047602,53.85994863510132,86.12592868030077,1739502693.604764,53.85994863510132,20.876154239478986,1739502693.604766,53.85994863510132,-0.017,1739502693.6047685,53.85994863510132,-3.1323104374610375,1739502693.6047704,53.85994863510132,0.22550553220012773,1739502693.604772,53.85994863510132,0.057139943164241425,1739502693.604774,53.85994863510132,2.087331187301008,1739502693.604776,53.85994863510132,0.0,1739502693.6047778,53.85994863510132,-0.06880653451738815,1739502693.6047795,53.85994863510132,3.109900178963118,1739502693.6047816,53.85994863510132,2.1627214092279026 +1739502693.6251264,53.87994861602783,26.38098964360499,1739502693.62513,53.87994861602783,0.034098539524910265,1739502693.625134,53.87994861602783,86.12592868030077,1739502693.6251378,53.87994861602783,20.876154239478986,1739502693.6251397,53.87994861602783,-0.017,1739502693.6251423,53.87994861602783,-3.1323104374610375,1739502693.625144,53.87994861602783,0.22550553220012773,1739502693.6251462,53.87994861602783,0.057139943164241425,1739502693.6251476,53.87994861602783,2.087331187301008,1739502693.6251502,53.87994861602783,0.0,1739502693.625152,53.87994861602783,-0.07539022192689471,1739502693.625154,53.87994861602783,3.109900178963118,1739502693.6251562,53.87994861602783,2.1627214092279026 +1739502693.6447017,53.899948596954346,26.38098964360499,1739502693.644705,53.899948596954346,0.034098539524910265,1739502693.644709,53.899948596954346,86.12592868030077,1739502693.6447127,53.899948596954346,20.876154239478986,1739502693.6447148,53.899948596954346,-0.017,1739502693.6447172,53.899948596954346,-3.1323104374610375,1739502693.6447194,53.899948596954346,0.22550553220012773,1739502693.6447215,53.899948596954346,0.057139943164241425,1739502693.6447232,53.899948596954346,2.087331187301008,1739502693.6447256,53.899948596954346,0.0,1739502693.6447272,53.899948596954346,-0.07539022192689471,1739502693.6447291,53.899948596954346,3.109900178963118,1739502693.6447308,53.899948596954346,2.1627214092279026 +1739502693.6650648,53.91994857788086,26.38098964360499,1739502693.6650689,53.91994857788086,0.034098539524910265,1739502693.6650736,53.91994857788086,86.12592868030077,1739502693.6650772,53.91994857788086,20.876154239478986,1739502693.6650794,53.91994857788086,-0.017,1739502693.6650817,53.91994857788086,-3.1323104374610375,1739502693.665084,53.91994857788086,0.22550553220012773,1739502693.6650858,53.91994857788086,0.057139943164241425,1739502693.6650877,53.91994857788086,2.087331187301008,1739502693.6650898,53.91994857788086,0.0,1739502693.6650915,53.91994857788086,-0.07539022192689471,1739502693.6650941,53.91994857788086,3.109900178963118,1739502693.6650963,53.91994857788086,2.1627214092279026 +1739502693.6847746,53.93994855880737,26.38098964360499,1739502693.6847782,53.93994855880737,0.034098539524910265,1739502693.6847823,53.93994855880737,86.12592868030077,1739502693.6847858,53.93994855880737,20.876154239478986,1739502693.6847878,53.93994855880737,-0.017,1739502693.6847901,53.93994855880737,-3.1323104374610375,1739502693.6847918,53.93994855880737,0.22550553220012773,1739502693.6847937,53.93994855880737,0.057139943164241425,1739502693.6847951,53.93994855880737,2.087331187301008,1739502693.6847975,53.93994855880737,0.0,1739502693.684799,53.93994855880737,-0.07539022192689471,1739502693.684801,53.93994855880737,3.109900178963118,1739502693.684803,53.93994855880737,2.1627214092279026 +1739502693.7047346,53.95994853973389,26.38098964360499,1739502693.7047386,53.95994853973389,0.034098539524910265,1739502693.7047424,53.95994853973389,86.12592868030077,1739502693.7047462,53.95994853973389,20.876154239478986,1739502693.704748,53.95994853973389,-0.017,1739502693.7047503,53.95994853973389,-3.1323104374610375,1739502693.7047522,53.95994853973389,0.22550553220012773,1739502693.704754,53.95994853973389,0.057139943164241425,1739502693.7047558,53.95994853973389,2.087331187301008,1739502693.704758,53.95994853973389,0.0,1739502693.7047596,53.95994853973389,-0.07539022192689471,1739502693.7047615,53.95994853973389,3.109900178963118,1739502693.7047634,53.95994853973389,2.1627214092279026 +1739502693.7252703,53.9799485206604,26.143608042403464,1739502693.7252736,53.9799485206604,0.04154348841554878,1739502693.7252784,53.9799485206604,86.62107041480232,1739502693.7252827,53.9799485206604,20.39726753471378,1739502693.7252846,53.9799485206604,-0.016956582887282388,1739502693.7252872,53.9799485206604,-3.131412600675192,1739502693.7252889,53.9799485206604,0.23613921663892992,1739502693.725291,53.9799485206604,0.05491021112652436,1739502693.7252927,53.9799485206604,2.0696496848075023,1739502693.7252948,53.9799485206604,0.0,1739502693.7252967,53.9799485206604,-0.08929223175939983,1739502693.7252984,53.9799485206604,3.110669419601192,1739502693.7253006,53.9799485206604,2.154597535645846 +1739502693.7447214,53.999948501586914,26.143608042403464,1739502693.7447252,53.999948501586914,0.04154348841554878,1739502693.7447293,53.999948501586914,86.62107041480232,1739502693.7447329,53.999948501586914,20.39726753471378,1739502693.7447348,53.999948501586914,-0.016956582887282388,1739502693.7447374,53.999948501586914,-3.131412600675192,1739502693.744739,53.999948501586914,0.23613921663892992,1739502693.7447412,53.999948501586914,0.05491021112652436,1739502693.7447429,53.999948501586914,2.0696496848075023,1739502693.7447453,53.999948501586914,0.0,1739502693.744747,53.999948501586914,-0.08494785083834389,1739502693.7447488,53.999948501586914,3.110669419601192,1739502693.7447505,53.999948501586914,2.154597535645846 +1739502693.7652664,54.01994848251343,26.143608042403464,1739502693.76527,54.01994848251343,0.04154348841554878,1739502693.765274,54.01994848251343,86.62107041480232,1739502693.7652776,54.01994848251343,20.39726753471378,1739502693.7652795,54.01994848251343,-0.016956582887282388,1739502693.7652822,54.01994848251343,-3.131412600675192,1739502693.7652838,54.01994848251343,0.23613921663892992,1739502693.7652857,54.01994848251343,0.05491021112652436,1739502693.7652874,54.01994848251343,2.0696496848075023,1739502693.7652895,54.01994848251343,0.0,1739502693.7652912,54.01994848251343,-0.08494785083834389,1739502693.7652936,54.01994848251343,3.110669419601192,1739502693.765296,54.01994848251343,2.154597535645846 +1739502693.7851772,54.03994846343994,26.143608042403464,1739502693.7851803,54.03994846343994,0.04154348841554878,1739502693.7851841,54.03994846343994,86.62107041480232,1739502693.7851877,54.03994846343994,20.39726753471378,1739502693.7851896,54.03994846343994,-0.016956582887282388,1739502693.785192,54.03994846343994,-3.131412600675192,1739502693.7851937,54.03994846343994,0.23613921663892992,1739502693.7851956,54.03994846343994,0.05491021112652436,1739502693.785197,54.03994846343994,2.0696496848075023,1739502693.7851992,54.03994846343994,0.0,1739502693.7852008,54.03994846343994,-0.08494785083834389,1739502693.785203,54.03994846343994,3.110669419601192,1739502693.7852046,54.03994846343994,2.154597535645846 +1739502693.8046992,54.059948444366455,26.143608042403464,1739502693.8047037,54.059948444366455,0.04154348841554878,1739502693.8047087,54.059948444366455,86.62107041480232,1739502693.8047125,54.059948444366455,20.39726753471378,1739502693.8047147,54.059948444366455,-0.016956582887282388,1739502693.804717,54.059948444366455,-3.131412600675192,1739502693.8047187,54.059948444366455,0.23613921663892992,1739502693.8047209,54.059948444366455,0.05491021112652436,1739502693.8047228,54.059948444366455,2.0696496848075023,1739502693.8047247,54.059948444366455,0.0,1739502693.8047266,54.059948444366455,-0.08494785083834389,1739502693.8047285,54.059948444366455,3.110669419601192,1739502693.8047304,54.059948444366455,2.154597535645846 +1739502693.8251474,54.07994842529297,25.90717579281735,1739502693.825151,54.07994842529297,0.04877199322228343,1739502693.825155,54.07994842529297,86.66860775397875,1739502693.8251588,54.07994842529297,20.368301277621928,1739502693.825161,54.07994842529297,-0.01669083740937547,1739502693.8251634,54.07994842529297,-3.1297744073609044,1739502693.8251653,54.07994842529297,0.23230369014075158,1739502693.8251672,54.07994842529297,0.05813788711527428,1739502693.8251688,54.07994842529297,2.0760099948386843,1739502693.825171,54.07994842529297,0.0,1739502693.8251727,54.07994842529297,-0.06219112903330641,1739502693.825175,54.07994842529297,3.1114609313633363,1739502693.8251772,54.07994842529297,2.1453126040987147 +1739502693.844627,54.09994840621948,25.90717579281735,1739502693.8446302,54.09994840621948,0.04877199322228343,1739502693.844634,54.09994840621948,86.66860775397875,1739502693.8446379,54.09994840621948,20.368301277621928,1739502693.8446398,54.09994840621948,-0.01669083740937547,1739502693.8446426,54.09994840621948,-3.1297744073609044,1739502693.8446443,54.09994840621948,0.23230369014075158,1739502693.8446465,54.09994840621948,0.05813788711527428,1739502693.8446481,54.09994840621948,2.0760099948386843,1739502693.8446503,54.09994840621948,0.0,1739502693.8446517,54.09994840621948,-0.0693026092600304,1739502693.8446538,54.09994840621948,3.1114609313633363,1739502693.8446562,54.09994840621948,2.1453126040987147 +1739502693.864914,54.119948387145996,25.90717579281735,1739502693.8649178,54.119948387145996,0.04877199322228343,1739502693.8649223,54.119948387145996,86.66860775397875,1739502693.864926,54.119948387145996,20.368301277621928,1739502693.8649282,54.119948387145996,-0.01669083740937547,1739502693.8649304,54.119948387145996,-3.1297744073609044,1739502693.8649323,54.119948387145996,0.23230369014075158,1739502693.8649342,54.119948387145996,0.05813788711527428,1739502693.8649359,54.119948387145996,2.0760099948386843,1739502693.8649383,54.119948387145996,0.0,1739502693.86494,54.119948387145996,-0.0693026092600304,1739502693.8649418,54.119948387145996,3.1114609313633363,1739502693.864944,54.119948387145996,2.1453126040987147 +1739502693.8847191,54.13994836807251,25.90717579281735,1739502693.8847225,54.13994836807251,0.04877199322228343,1739502693.8847265,54.13994836807251,86.66860775397875,1739502693.88473,54.13994836807251,20.368301277621928,1739502693.8847322,54.13994836807251,-0.01669083740937547,1739502693.8847344,54.13994836807251,-3.1297744073609044,1739502693.8847363,54.13994836807251,0.23230369014075158,1739502693.8847382,54.13994836807251,0.05813788711527428,1739502693.88474,54.13994836807251,2.0760099948386843,1739502693.8847423,54.13994836807251,0.0,1739502693.8847442,54.13994836807251,-0.0693026092600304,1739502693.884746,54.13994836807251,3.1114609313633363,1739502693.8847477,54.13994836807251,2.1453126040987147 +1739502693.9047596,54.15994834899902,25.90717579281735,1739502693.9047632,54.15994834899902,0.04877199322228343,1739502693.9047673,54.15994834899902,86.66860775397875,1739502693.904771,54.15994834899902,20.368301277621928,1739502693.9047728,54.15994834899902,-0.01669083740937547,1739502693.9047751,54.15994834899902,-3.1297744073609044,1739502693.9047773,54.15994834899902,0.23230369014075158,1739502693.904779,54.15994834899902,0.05813788711527428,1739502693.904781,54.15994834899902,2.0760099948386843,1739502693.904783,54.15994834899902,0.0,1739502693.904785,54.15994834899902,-0.0693026092600304,1739502693.9047868,54.15994834899902,3.1114609313633363,1739502693.904789,54.15994834899902,2.1453126040987147 +1739502693.9249556,54.17994832992554,25.90717579281735,1739502693.924959,54.17994832992554,0.04877199322228343,1739502693.9249632,54.17994832992554,86.66860775397875,1739502693.924967,54.17994832992554,20.368301277621928,1739502693.924969,54.17994832992554,-0.01669083740937547,1739502693.9249713,54.17994832992554,-3.1297744073609044,1739502693.9249732,54.17994832992554,0.23230369014075158,1739502693.9249752,54.17994832992554,0.05813788711527428,1739502693.9249768,54.17994832992554,2.0760099948386843,1739502693.9249794,54.17994832992554,0.0,1739502693.9249814,54.17994832992554,-0.0693026092600304,1739502693.9249833,54.17994832992554,3.1114609313633363,1739502693.9249854,54.17994832992554,2.1453126040987147 +1739502693.9447098,54.19994831085205,25.671662474334322,1739502693.9447138,54.19994831085205,0.0557858089115193,1739502693.9447176,54.19994831085205,86.78869174550886,1739502693.9447212,54.19994831085205,20.26311571195668,1739502693.9447231,54.19994831085205,-0.015728324654151634,1739502693.9447255,54.19994831085205,-3.128370993599477,1739502693.9447277,54.19994831085205,0.23014848797804927,1739502693.9447293,54.19994831085205,0.06040509196261467,1739502693.9447312,54.19994831085205,2.079592459309813,1739502693.9447334,54.19994831085205,0.0,1739502693.944735,54.19994831085205,-0.053259731000741495,1739502693.944737,54.19994831085205,3.1122524431254805,1739502693.9447389,54.19994831085205,2.1378655930536254 +1739502693.9646516,54.219948291778564,25.671662474334322,1739502693.9646552,54.219948291778564,0.0557858089115193,1739502693.9646592,54.219948291778564,86.78869174550886,1739502693.964663,54.219948291778564,20.26311571195668,1739502693.964665,54.219948291778564,-0.015728324654151634,1739502693.9646673,54.219948291778564,-3.128370993599477,1739502693.9646692,54.219948291778564,0.23014848797804927,1739502693.9646947,54.219948291778564,0.06040509196261467,1739502693.9646966,54.219948291778564,2.079592459309813,1739502693.9646988,54.219948291778564,0.0,1739502693.9647007,54.219948291778564,-0.058273133743812267,1739502693.9647026,54.219948291778564,3.1122524431254805,1739502693.9647045,54.219948291778564,2.1378655930536254 +1739502693.9847777,54.23994827270508,25.671662474334322,1739502693.9847815,54.23994827270508,0.0557858089115193,1739502693.984786,54.23994827270508,86.78869174550886,1739502693.9847898,54.23994827270508,20.26311571195668,1739502693.9847915,54.23994827270508,-0.015728324654151634,1739502693.984794,54.23994827270508,-3.128370993599477,1739502693.9847958,54.23994827270508,0.23014848797804927,1739502693.984798,54.23994827270508,0.06040509196261467,1739502693.9847994,54.23994827270508,2.079592459309813,1739502693.9848018,54.23994827270508,0.0,1739502693.9848037,54.23994827270508,-0.058273133743812267,1739502693.9848053,54.23994827270508,3.1122524431254805,1739502693.9848073,54.23994827270508,2.1378655930536254 +1739502694.0049493,54.25994825363159,25.671662474334322,1739502694.004953,54.25994825363159,0.0557858089115193,1739502694.0049567,54.25994825363159,86.78869174550886,1739502694.0049605,54.25994825363159,20.26311571195668,1739502694.0049624,54.25994825363159,-0.015728324654151634,1739502694.0049648,54.25994825363159,-3.128370993599477,1739502694.0049667,54.25994825363159,0.23014848797804927,1739502694.0049686,54.25994825363159,0.06040509196261467,1739502694.0049706,54.25994825363159,2.079592459309813,1739502694.0049725,54.25994825363159,0.0,1739502694.0049744,54.25994825363159,-0.058273133743812267,1739502694.0049763,54.25994825363159,3.1122524431254805,1739502694.0049782,54.25994825363159,2.1378655930536254 +1739502694.0249598,54.279948234558105,25.671662474334322,1739502694.0249634,54.279948234558105,0.0557858089115193,1739502694.0249677,54.279948234558105,86.78869174550886,1739502694.0249712,54.279948234558105,20.26311571195668,1739502694.0249734,54.279948234558105,-0.015728324654151634,1739502694.0249755,54.279948234558105,-3.128370993599477,1739502694.0249774,54.279948234558105,0.23014848797804927,1739502694.0249794,54.279948234558105,0.06040509196261467,1739502694.0249813,54.279948234558105,2.079592459309813,1739502694.0249836,54.279948234558105,0.0,1739502694.0249853,54.279948234558105,-0.058273133743812267,1739502694.0249872,54.279948234558105,3.1122524431254805,1739502694.0249894,54.279948234558105,2.1378655930536254 +1739502694.0448008,54.29994821548462,25.436917000673038,1739502694.044804,54.29994821548462,0.06258062407893306,1739502694.044808,54.29994821548462,87.01498342250895,1739502694.0448117,54.29994821548462,20.04959506935105,1739502694.0448136,54.29994821548462,-0.014778136994100438,1739502694.044816,54.29994821548462,-3.1272342310226686,1739502694.044818,54.29994821548462,0.23042663665673538,1739502694.0448196,54.29994821548462,0.060953512588496905,1739502694.0448215,54.29994821548462,2.079129762075362,1739502694.0448236,54.29994821548462,0.0,1739502694.0448253,54.29994821548462,-0.04966126137365473,1739502694.0448275,54.29994821548462,3.113170417768091,1739502694.0448291,54.29994821548462,2.131482235329187 +1739502694.0651464,54.31994819641113,25.436917000673038,1739502694.0651503,54.31994819641113,0.06258062407893306,1739502694.0651543,54.31994819641113,87.01498342250895,1739502694.0651581,54.31994819641113,20.04959506935105,1739502694.0651608,54.31994819641113,-0.014778136994100438,1739502694.065163,54.31994819641113,-3.1272342310226686,1739502694.0651648,54.31994819641113,0.23042663665673538,1739502694.065167,54.31994819641113,0.060953512588496905,1739502694.0651689,54.31994819641113,2.079129762075362,1739502694.065171,54.31994819641113,0.0,1739502694.0651727,54.31994819641113,-0.05235247325382497,1739502694.0651748,54.31994819641113,3.113170417768091,1739502694.0651767,54.31994819641113,2.131482235329187 +1739502694.0847456,54.33994817733765,25.436917000673038,1739502694.084749,54.33994817733765,0.06258062407893306,1739502694.084753,54.33994817733765,87.01498342250895,1739502694.0847569,54.33994817733765,20.04959506935105,1739502694.0847583,54.33994817733765,-0.014778136994100438,1739502694.084761,54.33994817733765,-3.1272342310226686,1739502694.0847628,54.33994817733765,0.23042663665673538,1739502694.0847645,54.33994817733765,0.060953512588496905,1739502694.0847661,54.33994817733765,2.079129762075362,1739502694.0847683,54.33994817733765,0.0,1739502694.08477,54.33994817733765,-0.05235247325382497,1739502694.084772,54.33994817733765,3.113170417768091,1739502694.0847738,54.33994817733765,2.131482235329187 +1739502694.1047132,54.35994815826416,25.436917000673038,1739502694.1047168,54.35994815826416,0.06258062407893306,1739502694.1047208,54.35994815826416,87.01498342250895,1739502694.1047246,54.35994815826416,20.04959506935105,1739502694.1047266,54.35994815826416,-0.014778136994100438,1739502694.1047292,54.35994815826416,-3.1272342310226686,1739502694.104731,54.35994815826416,0.23042663665673538,1739502694.1047328,54.35994815826416,0.060953512588496905,1739502694.1047344,54.35994815826416,2.079129762075362,1739502694.1047366,54.35994815826416,0.0,1739502694.1047382,54.35994815826416,-0.05235247325382497,1739502694.1047404,54.35994815826416,3.113170417768091,1739502694.104742,54.35994815826416,2.131482235329187 +1739502694.1251009,54.379948139190674,25.436917000673038,1739502694.1251044,54.379948139190674,0.06258062407893306,1739502694.1251082,54.379948139190674,87.01498342250895,1739502694.125112,54.379948139190674,20.04959506935105,1739502694.1251142,54.379948139190674,-0.014778136994100438,1739502694.1251166,54.379948139190674,-3.1272342310226686,1739502694.1251187,54.379948139190674,0.23042663665673538,1739502694.1251204,54.379948139190674,0.060953512588496905,1739502694.1251223,54.379948139190674,2.079129762075362,1739502694.1251252,54.379948139190674,0.0,1739502694.125127,54.379948139190674,-0.05235247325382497,1739502694.1251292,54.379948139190674,3.113170417768091,1739502694.1251314,54.379948139190674,2.131482235329187 +1739502694.1447062,54.39994812011719,25.436917000673038,1739502694.1447098,54.39994812011719,0.06258062407893306,1739502694.1447139,54.39994812011719,87.01498342250895,1739502694.1447182,54.39994812011719,20.04959506935105,1739502694.14472,54.39994812011719,-0.014778136994100438,1739502694.1447225,54.39994812011719,-3.1272342310226686,1739502694.1447244,54.39994812011719,0.23042663665673538,1739502694.1447263,54.39994812011719,0.060953512588496905,1739502694.144728,54.39994812011719,2.079129762075362,1739502694.1447303,54.39994812011719,0.0,1739502694.1447322,54.39994812011719,-0.05235247325382497,1739502694.144734,54.39994812011719,3.113170417768091,1739502694.1447358,54.39994812011719,2.131482235329187 +1739502694.1648474,54.4199481010437,25.202827726728685,1739502694.164851,54.4199481010437,0.06913409126463055,1739502694.1648552,54.4199481010437,87.45086999624127,1739502694.1648593,54.4199481010437,19.625078746487414,1739502694.1648614,54.4199481010437,-0.012,1739502694.1648638,54.4199481010437,-3.1270476516590597,1739502694.164866,54.4199481010437,0.23428862310104875,1739502694.1648684,54.4199481010437,0.057816105722524,1739502694.1648703,54.4199481010437,2.0727160183281406,1739502694.1648724,54.4199481010437,0.0,1739502694.1648743,54.4199481010437,-0.05342143598169343,1739502694.1648762,54.4199481010437,3.1141255877480174,1739502694.1648781,54.4199481010437,2.125803403238354 +1739502694.184735,54.439948081970215,25.202827726728685,1739502694.1847386,54.439948081970215,0.06913409126463055,1739502694.1847422,54.439948081970215,87.45086999624127,1739502694.184746,54.439948081970215,19.625078746487414,1739502694.1847477,54.439948081970215,-0.012,1739502694.1847503,54.439948081970215,-3.1270476516590597,1739502694.1847522,54.439948081970215,0.23428862310104875,1739502694.184754,54.439948081970215,0.057816105722524,1739502694.1847558,54.439948081970215,2.0727160183281406,1739502694.1847577,54.439948081970215,0.0,1739502694.1847596,54.439948081970215,-0.053087384910213586,1739502694.1847615,54.439948081970215,3.1141255877480174,1739502694.1847634,54.439948081970215,2.125803403238354 +1739502694.204777,54.45994806289673,25.202827726728685,1739502694.2047806,54.45994806289673,0.06913409126463055,1739502694.2047844,54.45994806289673,87.45086999624127,1739502694.204788,54.45994806289673,19.625078746487414,1739502694.20479,54.45994806289673,-0.012,1739502694.2047923,54.45994806289673,-3.1270476516590597,1739502694.2047942,54.45994806289673,0.23428862310104875,1739502694.204796,54.45994806289673,0.057816105722524,1739502694.2047977,54.45994806289673,2.0727160183281406,1739502694.2048,54.45994806289673,0.0,1739502694.2048016,54.45994806289673,-0.053087384910213586,1739502694.2048032,54.45994806289673,3.1141255877480174,1739502694.2048054,54.45994806289673,2.125803403238354 +1739502694.2252848,54.47994804382324,25.202827726728685,1739502694.2252884,54.47994804382324,0.06913409126463055,1739502694.2252934,54.47994804382324,87.45086999624127,1739502694.2252972,54.47994804382324,19.625078746487414,1739502694.225299,54.47994804382324,-0.012,1739502694.2253015,54.47994804382324,-3.1270476516590597,1739502694.2253036,54.47994804382324,0.23428862310104875,1739502694.2253053,54.47994804382324,0.057816105722524,1739502694.2253072,54.47994804382324,2.0727160183281406,1739502694.2253091,54.47994804382324,0.0,1739502694.225311,54.47994804382324,-0.053087384910213586,1739502694.225313,54.47994804382324,3.1141255877480174,1739502694.2253149,54.47994804382324,2.125803403238354 +1739502694.2446132,54.499948024749756,25.202827726728685,1739502694.2446167,54.499948024749756,0.06913409126463055,1739502694.244621,54.499948024749756,87.45086999624127,1739502694.244625,54.499948024749756,19.625078746487414,1739502694.244627,54.499948024749756,-0.012,1739502694.2446296,54.499948024749756,-3.1270476516590597,1739502694.2446313,54.499948024749756,0.23428862310104875,1739502694.2446334,54.499948024749756,0.057816105722524,1739502694.2446349,54.499948024749756,2.0727160183281406,1739502694.2446373,54.499948024749756,0.0,1739502694.244639,54.499948024749756,-0.053087384910213586,1739502694.244641,54.499948024749756,3.1141255877480174,1739502694.2446427,54.499948024749756,2.125803403238354 +1739502694.265357,54.51994800567627,24.96936517560978,1739502694.2653608,54.51994800567627,0.07544684884385067,1739502694.265366,54.51994800567627,88.18377127531915,1739502694.2653701,54.51994800567627,18.9037943197776,1739502694.2653725,54.51994800567627,-0.011,1739502694.265375,54.51994800567627,-3.127341563535313,1739502694.265377,54.51994800567627,0.2472074149036965,1739502694.2653794,54.51994800567627,0.0515879579104653,1739502694.265381,54.51994800567627,2.0514047450168214,1739502694.2653832,54.51994800567627,0.0,1739502694.2653852,54.51994800567627,-0.07563931843109953,1739502694.2653873,54.51994800567627,3.115080757727944,1739502694.2653892,54.51994800567627,2.1199965796019535 +1739502694.284762,54.53994798660278,24.96936517560978,1739502694.2847655,54.53994798660278,0.07544684884385067,1739502694.2847695,54.53994798660278,88.18377127531915,1739502694.2847733,54.53994798660278,18.9037943197776,1739502694.2847755,54.53994798660278,-0.011,1739502694.2847776,54.53994798660278,-3.127341563535313,1739502694.2847795,54.53994798660278,0.2472074149036965,1739502694.2847812,54.53994798660278,0.0515879579104653,1739502694.2847831,54.53994798660278,2.0514047450168214,1739502694.2847853,54.53994798660278,0.0,1739502694.284787,54.53994798660278,-0.06859183458513218,1739502694.284789,54.53994798660278,3.115080757727944,1739502694.2847908,54.53994798660278,2.1199965796019535 +1739502694.3047419,54.5599479675293,24.96936517560978,1739502694.3047452,54.5599479675293,0.07544684884385067,1739502694.3047493,54.5599479675293,88.18377127531915,1739502694.3047528,54.5599479675293,18.9037943197776,1739502694.3047547,54.5599479675293,-0.011,1739502694.3047569,54.5599479675293,-3.127341563535313,1739502694.3047588,54.5599479675293,0.2472074149036965,1739502694.3047607,54.5599479675293,0.0515879579104653,1739502694.3047624,54.5599479675293,2.0514047450168214,1739502694.3047645,54.5599479675293,0.0,1739502694.3047662,54.5599479675293,-0.06859183458513218,1739502694.3047683,54.5599479675293,3.115080757727944,1739502694.30477,54.5599479675293,2.1199965796019535 +1739502694.324842,54.57994794845581,24.96936517560978,1739502694.3248456,54.57994794845581,0.07544684884385067,1739502694.3248498,54.57994794845581,88.18377127531915,1739502694.3248537,54.57994794845581,18.9037943197776,1739502694.3248556,54.57994794845581,-0.011,1739502694.3248582,54.57994794845581,-3.127341563535313,1739502694.3248599,54.57994794845581,0.2472074149036965,1739502694.3248618,54.57994794845581,0.0515879579104653,1739502694.3248634,54.57994794845581,2.0514047450168214,1739502694.3248656,54.57994794845581,0.0,1739502694.3248675,54.57994794845581,-0.06859183458513218,1739502694.3248696,54.57994794845581,3.115080757727944,1739502694.3248715,54.57994794845581,2.1199965796019535 +1739502694.3449206,54.599947929382324,24.96936517560978,1739502694.3449237,54.599947929382324,0.07544684884385067,1739502694.3449275,54.599947929382324,88.18377127531915,1739502694.3449311,54.599947929382324,18.9037943197776,1739502694.3449328,54.599947929382324,-0.011,1739502694.3449352,54.599947929382324,-3.127341563535313,1739502694.3449368,54.599947929382324,0.2472074149036965,1739502694.344939,54.599947929382324,0.0515879579104653,1739502694.344941,54.599947929382324,2.0514047450168214,1739502694.3449428,54.599947929382324,0.0,1739502694.3449447,54.599947929382324,-0.06859183458513218,1739502694.3449464,54.599947929382324,3.115080757727944,1739502694.3449483,54.599947929382324,2.1199965796019535 +1739502694.3650022,54.61994791030884,24.96936517560978,1739502694.365006,54.61994791030884,0.07544684884385067,1739502694.3650105,54.61994791030884,88.18377127531915,1739502694.3650143,54.61994791030884,18.9037943197776,1739502694.365016,54.61994791030884,-0.011,1739502694.3650188,54.61994791030884,-3.127341563535313,1739502694.365021,54.61994791030884,0.2472074149036965,1739502694.365023,54.61994791030884,0.0515879579104653,1739502694.3650248,54.61994791030884,2.0514047450168214,1739502694.3650274,54.61994791030884,0.0,1739502694.365029,54.61994791030884,-0.06859183458513218,1739502694.365031,54.61994791030884,3.115080757727944,1739502694.365033,54.61994791030884,2.1199965796019535 +1739502694.3848026,54.63994789123535,24.73663426814703,1739502694.384806,54.63994789123535,0.08151738431890809,1739502694.3848097,54.63994789123535,88.18936288763372,1739502694.3848135,54.63994789123535,18.913502859897488,1739502694.3848155,54.63994789123535,-0.011,1739502694.3848176,54.63994789123535,-3.125706080812263,1739502694.3848195,54.63994789123535,0.2412911457540131,1739502694.3848212,54.63994789123535,0.05463007571700557,1739502694.384823,54.63994789123535,2.0611370885994265,1739502694.384825,54.63994789123535,0.0,1739502694.384827,54.63994789123535,-0.04330830734119301,1739502694.3848286,54.63994789123535,3.11603592770787,1739502694.3848307,54.63994789123535,2.11234650338472 +1739502694.4047391,54.659947872161865,24.73663426814703,1739502694.4047425,54.659947872161865,0.08151738431890809,1739502694.4047465,54.659947872161865,88.18936288763372,1739502694.40475,54.659947872161865,18.913502859897488,1739502694.4047518,54.659947872161865,-0.011,1739502694.4047544,54.659947872161865,-3.125706080812263,1739502694.4047563,54.659947872161865,0.2412911457540131,1739502694.404758,54.659947872161865,0.05463007571700557,1739502694.40476,54.659947872161865,2.0611370885994265,1739502694.4047618,54.659947872161865,0.0,1739502694.4047637,54.659947872161865,-0.05120941478529373,1739502694.4047656,54.659947872161865,3.11603592770787,1739502694.4047675,54.659947872161865,2.11234650338472 +1739502694.4249933,54.67994785308838,24.73663426814703,1739502694.4249969,54.67994785308838,0.08151738431890809,1739502694.425001,54.67994785308838,88.18936288763372,1739502694.4250047,54.67994785308838,18.913502859897488,1739502694.4250066,54.67994785308838,-0.011,1739502694.425009,54.67994785308838,-3.125706080812263,1739502694.425011,54.67994785308838,0.2412911457540131,1739502694.4250128,54.67994785308838,0.05463007571700557,1739502694.4250145,54.67994785308838,2.0611370885994265,1739502694.4250166,54.67994785308838,0.0,1739502694.4250183,54.67994785308838,-0.05120941478529373,1739502694.4250205,54.67994785308838,3.11603592770787,1739502694.4250224,54.67994785308838,2.11234650338472 +1739502694.444861,54.69994783401489,24.73663426814703,1739502694.444865,54.69994783401489,0.08151738431890809,1739502694.444869,54.69994783401489,88.18936288763372,1739502694.4448733,54.69994783401489,18.913502859897488,1739502694.4448752,54.69994783401489,-0.011,1739502694.4448776,54.69994783401489,-3.125706080812263,1739502694.4448795,54.69994783401489,0.2412911457540131,1739502694.4448814,54.69994783401489,0.05463007571700557,1739502694.444883,54.69994783401489,2.0611370885994265,1739502694.4448855,54.69994783401489,0.0,1739502694.4448874,54.69994783401489,-0.05120941478529373,1739502694.4448893,54.69994783401489,3.11603592770787,1739502694.4448912,54.69994783401489,2.11234650338472 +1739502694.4649832,54.719947814941406,24.73663426814703,1739502694.4649868,54.719947814941406,0.08151738431890809,1739502694.464991,54.719947814941406,88.18936288763372,1739502694.464995,54.719947814941406,18.913502859897488,1739502694.4649966,54.719947814941406,-0.011,1739502694.4649987,54.719947814941406,-3.125706080812263,1739502694.4650006,54.719947814941406,0.2412911457540131,1739502694.4650028,54.719947814941406,0.05463007571700557,1739502694.4650042,54.719947814941406,2.0611370885994265,1739502694.4650064,54.719947814941406,0.0,1739502694.465008,54.719947814941406,-0.05120941478529373,1739502694.46501,54.719947814941406,3.11603592770787,1739502694.465012,54.719947814941406,2.11234650338472 +1739502694.4849055,54.73994779586792,24.504633490556156,1739502694.484909,54.73994779586792,0.08734711175468224,1739502694.484913,54.73994779586792,88.19493673602334,1739502694.4849167,54.73994779586792,18.91916016754497,1739502694.4849188,54.73994779586792,-0.011,1739502694.484921,54.73994779586792,-3.1239868135023956,1739502694.484923,54.73994779586792,0.23571482517652528,1739502694.484925,54.73994779586792,0.05800152516710299,1739502694.4849265,54.73994779586792,2.0703524774295476,1739502694.4849286,54.73994779586792,0.0,1739502694.4849303,54.73994779586792,-0.029637092939993337,1739502694.4849324,54.73994779586792,3.1169910976877966,1739502694.484934,54.73994779586792,2.106730925366174 +1739502694.504879,54.759947776794434,24.504633490556156,1739502694.5048826,54.759947776794434,0.08734711175468224,1739502694.5048866,54.759947776794434,88.19493673602334,1739502694.5048902,54.759947776794434,18.91916016754497,1739502694.5048919,54.759947776794434,-0.011,1739502694.5048943,54.759947776794434,-3.1239868135023956,1739502694.504896,54.759947776794434,0.23571482517652528,1739502694.504898,54.759947776794434,0.05800152516710299,1739502694.5048997,54.759947776794434,2.0703524774295476,1739502694.504902,54.759947776794434,0.0,1739502694.5049038,54.759947776794434,-0.03637844793662648,1739502694.5049057,54.759947776794434,3.1169910976877966,1739502694.5049078,54.759947776794434,2.106730925366174 +1739502694.5249329,54.77994775772095,24.504633490556156,1739502694.5249362,54.77994775772095,0.08734711175468224,1739502694.5249405,54.77994775772095,88.19493673602334,1739502694.5249445,54.77994775772095,18.91916016754497,1739502694.5249467,54.77994775772095,-0.011,1739502694.5249488,54.77994775772095,-3.1239868135023956,1739502694.5249505,54.77994775772095,0.23571482517652528,1739502694.5249524,54.77994775772095,0.05800152516710299,1739502694.524954,54.77994775772095,2.0703524774295476,1739502694.5249567,54.77994775772095,0.0,1739502694.5249581,54.77994775772095,-0.03637844793662648,1739502694.5249603,54.77994775772095,3.1169910976877966,1739502694.5249622,54.77994775772095,2.106730925366174 +1739502694.5447605,54.79994773864746,24.504633490556156,1739502694.544764,54.79994773864746,0.08734711175468224,1739502694.544768,54.79994773864746,88.19493673602334,1739502694.5447717,54.79994773864746,18.91916016754497,1739502694.5447736,54.79994773864746,-0.011,1739502694.544776,54.79994773864746,-3.1239868135023956,1739502694.5447779,54.79994773864746,0.23571482517652528,1739502694.5447798,54.79994773864746,0.05800152516710299,1739502694.5447817,54.79994773864746,2.0703524774295476,1739502694.5447836,54.79994773864746,0.0,1739502694.5447855,54.79994773864746,-0.03637844793662648,1739502694.5447874,54.79994773864746,3.1169910976877966,1739502694.5447893,54.79994773864746,2.106730925366174 +1739502694.5650675,54.819947719573975,24.504633490556156,1739502694.5650706,54.819947719573975,0.08734711175468224,1739502694.5650747,54.819947719573975,88.19493673602334,1739502694.5650783,54.819947719573975,18.91916016754497,1739502694.5650802,54.819947719573975,-0.011,1739502694.5650823,54.819947719573975,-3.1239868135023956,1739502694.565084,54.819947719573975,0.23571482517652528,1739502694.5650856,54.819947719573975,0.05800152516710299,1739502694.5650876,54.819947719573975,2.0703524774295476,1739502694.5650895,54.819947719573975,0.0,1739502694.5650914,54.819947719573975,-0.03637844793662648,1739502694.565093,54.819947719573975,3.1169910976877966,1739502694.5650952,54.819947719573975,2.106730925366174 +1739502694.584775,54.83994770050049,24.504633490556156,1739502694.5847785,54.83994770050049,0.08734711175468224,1739502694.5847824,54.83994770050049,88.19493673602334,1739502694.584786,54.83994770050049,18.91916016754497,1739502694.584788,54.83994770050049,-0.011,1739502694.5847902,54.83994770050049,-3.1239868135023956,1739502694.5847921,54.83994770050049,0.23571482517652528,1739502694.5847938,54.83994770050049,0.05800152516710299,1739502694.5847957,54.83994770050049,2.0703524774295476,1739502694.5847976,54.83994770050049,0.0,1739502694.5847995,54.83994770050049,-0.03637844793662648,1739502694.5848014,54.83994770050049,3.1169910976877966,1739502694.5848033,54.83994770050049,2.106730925366174 +1739502694.6048625,54.859947681427,24.27314748709074,1739502694.604866,54.859947681427,0.09294264697621557,1739502694.6048703,54.859947681427,88.20049799564173,1739502694.6048741,54.859947681427,18.92129810519192,1739502694.6048763,54.859947681427,-0.011,1739502694.6048787,54.859947681427,-3.122173276619706,1739502694.6048803,54.859947681427,0.23045369107901867,1739502694.6048825,54.859947681427,0.061760666643187356,1739502694.604884,54.859947681427,2.079084762838683,1739502694.604886,54.859947681427,0.0,1739502694.6048877,54.859947681427,-0.018077520239888158,1739502694.60489,54.859947681427,3.117946267667723,1739502694.604892,54.859947681427,2.102881326733499 +1739502694.625187,54.879947662353516,24.27314748709074,1739502694.6251907,54.879947662353516,0.09294264697621557,1739502694.6251955,54.879947662353516,88.20049799564173,1739502694.6251993,54.879947662353516,18.92129810519192,1739502694.6252012,54.879947662353516,-0.011,1739502694.6252036,54.879947662353516,-3.122173276619706,1739502694.6252058,54.879947662353516,0.23045369107901867,1739502694.625208,54.879947662353516,0.061760666643187356,1739502694.6252098,54.879947662353516,2.079084762838683,1739502694.6252122,54.879947662353516,0.0,1739502694.6252139,54.879947662353516,-0.023796563894816103,1739502694.625216,54.879947662353516,3.117946267667723,1739502694.6252182,54.879947662353516,2.102881326733499 +1739502694.6448336,54.89994764328003,24.27314748709074,1739502694.6448371,54.89994764328003,0.09294264697621557,1739502694.6448412,54.89994764328003,88.20049799564173,1739502694.644845,54.89994764328003,18.92129810519192,1739502694.6448476,54.89994764328003,-0.011,1739502694.64485,54.89994764328003,-3.122173276619706,1739502694.644852,54.89994764328003,0.23045369107901867,1739502694.6448538,54.89994764328003,0.061760666643187356,1739502694.6448553,54.89994764328003,2.079084762838683,1739502694.6448576,54.89994764328003,0.0,1739502694.6448593,54.89994764328003,-0.023796563894816103,1739502694.6448615,54.89994764328003,3.117946267667723,1739502694.6448636,54.89994764328003,2.102881326733499 +1739502694.6649148,54.91994762420654,24.27314748709074,1739502694.664918,54.91994762420654,0.09294264697621557,1739502694.6649215,54.91994762420654,88.20049799564173,1739502694.664925,54.91994762420654,18.92129810519192,1739502694.6649275,54.91994762420654,-0.011,1739502694.6649299,54.91994762420654,-3.122173276619706,1739502694.6649315,54.91994762420654,0.23045369107901867,1739502694.6649334,54.91994762420654,0.061760666643187356,1739502694.6649349,54.91994762420654,2.079084762838683,1739502694.6649373,54.91994762420654,0.0,1739502694.6649387,54.91994762420654,-0.023796563894816103,1739502694.6649406,54.91994762420654,3.117946267667723,1739502694.6649423,54.91994762420654,2.102881326733499 +1739502694.684829,54.93994760513306,24.27314748709074,1739502694.6848326,54.93994760513306,0.09294264697621557,1739502694.6848366,54.93994760513306,88.20049799564173,1739502694.6848402,54.93994760513306,18.92129810519192,1739502694.6848419,54.93994760513306,-0.011,1739502694.6848443,54.93994760513306,-3.122173276619706,1739502694.6848464,54.93994760513306,0.23045369107901867,1739502694.684848,54.93994760513306,0.061760666643187356,1739502694.68485,54.93994760513306,2.079084762838683,1739502694.684852,54.93994760513306,0.0,1739502694.6848538,54.93994760513306,-0.023796563894816103,1739502694.6848557,54.93994760513306,3.117946267667723,1739502694.6848576,54.93994760513306,2.102881326733499 +1739502694.7050946,54.95994758605957,24.042025837779523,1739502694.7050982,54.95994758605957,0.0983084789010622,1739502694.705102,54.95994758605957,88.60112018654114,1739502694.7051058,54.95994758605957,18.525906883831848,1739502694.7051075,54.95994758605957,-0.01,1739502694.7051098,54.95994758605957,-3.1219602699668694,1739502694.7051117,54.95994758605957,0.2334373019037135,1739502694.7051136,54.95994758605957,0.05888993020888941,1739502694.7051153,54.95994758605957,2.074128136806082,1739502694.7051175,54.95994758605957,0.0,1739502694.7051191,54.95994758605957,-0.027205079251001112,1739502694.7051213,54.95994758605957,3.1189014376476494,1739502694.7051232,54.95994758605957,2.100268054309901 +1739502694.7256873,54.979947566986084,24.042025837779523,1739502694.7256906,54.979947566986084,0.0983084789010622,1739502694.725695,54.979947566986084,88.60112018654114,1739502694.7256987,54.979947566986084,18.525906883831848,1739502694.7257009,54.979947566986084,-0.01,1739502694.725703,54.979947566986084,-3.1219602699668694,1739502694.725705,54.979947566986084,0.2334373019037135,1739502694.7257068,54.979947566986084,0.05888993020888941,1739502694.7257082,54.979947566986084,2.074128136806082,1739502694.7257106,54.979947566986084,0.0,1739502694.725712,54.979947566986084,-0.026139917503818833,1739502694.7257142,54.979947566986084,3.1189014376476494,1739502694.7257166,54.979947566986084,2.100268054309901 +1739502694.7450821,54.9999475479126,24.042025837779523,1739502694.7450857,54.9999475479126,0.0983084789010622,1739502694.7450895,54.9999475479126,88.60112018654114,1739502694.745093,54.9999475479126,18.525906883831848,1739502694.745095,54.9999475479126,-0.01,1739502694.7450972,54.9999475479126,-3.1219602699668694,1739502694.7450993,54.9999475479126,0.2334373019037135,1739502694.745101,54.9999475479126,0.05888993020888941,1739502694.7451026,54.9999475479126,2.074128136806082,1739502694.7451046,54.9999475479126,0.0,1739502694.7451067,54.9999475479126,-0.026139917503818833,1739502694.7451084,54.9999475479126,3.1189014376476494,1739502694.7451105,54.9999475479126,2.100268054309901 +1739502694.765668,55.01994752883911,24.042025837779523,1739502694.7656715,55.01994752883911,0.0983084789010622,1739502694.7656758,55.01994752883911,88.60112018654114,1739502694.7656796,55.01994752883911,18.525906883831848,1739502694.7656815,55.01994752883911,-0.01,1739502694.7656837,55.01994752883911,-3.1219602699668694,1739502694.7656856,55.01994752883911,0.2334373019037135,1739502694.7656872,55.01994752883911,0.05888993020888941,1739502694.7656891,55.01994752883911,2.074128136806082,1739502694.7656913,55.01994752883911,0.0,1739502694.7656932,55.01994752883911,-0.026139917503818833,1739502694.7656953,55.01994752883911,3.1189014376476494,1739502694.765697,55.01994752883911,2.100268054309901 +1739502694.7851155,55.039947509765625,24.042025837779523,1739502694.7851188,55.039947509765625,0.0983084789010622,1739502694.7851226,55.039947509765625,88.60112018654114,1739502694.7851264,55.039947509765625,18.525906883831848,1739502694.785128,55.039947509765625,-0.01,1739502694.7851307,55.039947509765625,-3.1219602699668694,1739502694.7851326,55.039947509765625,0.2334373019037135,1739502694.7851346,55.039947509765625,0.05888993020888941,1739502694.7851365,55.039947509765625,2.074128136806082,1739502694.7851386,55.039947509765625,0.0,1739502694.7851405,55.039947509765625,-0.026139917503818833,1739502694.7851422,55.039947509765625,3.1189014376476494,1739502694.7851443,55.039947509765625,2.100268054309901 +1739502694.8050678,55.05994749069214,24.042025837779523,1739502694.8050714,55.05994749069214,0.0983084789010622,1739502694.8050752,55.05994749069214,88.60112018654114,1739502694.805079,55.05994749069214,18.525906883831848,1739502694.805081,55.05994749069214,-0.01,1739502694.805083,55.05994749069214,-3.1219602699668694,1739502694.8050852,55.05994749069214,0.2334373019037135,1739502694.8050873,55.05994749069214,0.05888993020888941,1739502694.8050888,55.05994749069214,2.074128136806082,1739502694.805091,55.05994749069214,0.0,1739502694.8050926,55.05994749069214,-0.026139917503818833,1739502694.8050947,55.05994749069214,3.1189014376476494,1739502694.8050964,55.05994749069214,2.100268054309901 +1739502694.8256469,55.07994747161865,23.811198935337504,1739502694.8256502,55.07994747161865,0.10344687779812478,1739502694.8256543,55.07994747161865,88.81953833526894,1739502694.8256583,55.07994747161865,18.31326389099936,1739502694.8256602,55.07994747161865,-0.008279840504944149,1739502694.8256626,55.07994747161865,-3.1212738718266952,1739502694.8256645,55.07994747161865,0.23119428541552067,1739502694.8256667,55.07994747161865,0.05870895474832752,1739502694.8256683,55.07994747161865,2.0778533209538868,1739502694.8256705,55.07994747161865,0.0,1739502694.8256721,55.07994747161865,-0.016527544632892032,1739502694.8256743,55.07994747161865,3.1198566076275758,1739502694.8256762,55.07994747161865,2.097384734078433 +1739502694.8450818,55.099947452545166,23.811198935337504,1739502694.8450856,55.099947452545166,0.10344687779812478,1739502694.8450894,55.099947452545166,88.81953833526894,1739502694.8450935,55.099947452545166,18.31326389099936,1739502694.8450952,55.099947452545166,-0.008279840504944149,1739502694.8450978,55.099947452545166,-3.1212738718266952,1739502694.8450994,55.099947452545166,0.23119428541552067,1739502694.8451014,55.099947452545166,0.05870895474832752,1739502694.845103,55.099947452545166,2.0778533209538868,1739502694.8451052,55.099947452545166,0.0,1739502694.8451068,55.099947452545166,-0.019531413124546315,1739502694.845109,55.099947452545166,3.1198566076275758,1739502694.845111,55.099947452545166,2.097384734078433 +1739502694.8656428,55.11994743347168,23.811198935337504,1739502694.8656464,55.11994743347168,0.10344687779812478,1739502694.8656502,55.11994743347168,88.81953833526894,1739502694.865654,55.11994743347168,18.31326389099936,1739502694.8656561,55.11994743347168,-0.008279840504944149,1739502694.8656583,55.11994743347168,-3.1212738718266952,1739502694.8656602,55.11994743347168,0.23119428541552067,1739502694.865662,55.11994743347168,0.05870895474832752,1739502694.865664,55.11994743347168,2.0778533209538868,1739502694.8656662,55.11994743347168,0.0,1739502694.8656678,55.11994743347168,-0.019531413124546315,1739502694.8656702,55.11994743347168,3.1198566076275758,1739502694.865672,55.11994743347168,2.097384734078433 +1739502694.8849404,55.13994741439819,23.811198935337504,1739502694.8849442,55.13994741439819,0.10344687779812478,1739502694.8849487,55.13994741439819,88.81953833526894,1739502694.8849525,55.13994741439819,18.31326389099936,1739502694.8849547,55.13994741439819,-0.008279840504944149,1739502694.8849576,55.13994741439819,-3.1212738718266952,1739502694.8849595,55.13994741439819,0.23119428541552067,1739502694.8849616,55.13994741439819,0.05870895474832752,1739502694.8849633,55.13994741439819,2.0778533209538868,1739502694.8849654,55.13994741439819,0.0,1739502694.884967,55.13994741439819,-0.019531413124546315,1739502694.8849692,55.13994741439819,3.1198566076275758,1739502694.8849716,55.13994741439819,2.097384734078433 +1739502694.9050467,55.15994739532471,23.811198935337504,1739502694.9050503,55.15994739532471,0.10344687779812478,1739502694.905054,55.15994739532471,88.81953833526894,1739502694.905058,55.15994739532471,18.31326389099936,1739502694.9050596,55.15994739532471,-0.008279840504944149,1739502694.905062,55.15994739532471,-3.1212738718266952,1739502694.9050636,55.15994739532471,0.23119428541552067,1739502694.905066,55.15994739532471,0.05870895474832752,1739502694.9050674,55.15994739532471,2.0778533209538868,1739502694.9050696,55.15994739532471,0.0,1739502694.9050713,55.15994739532471,-0.019531413124546315,1739502694.9050734,55.15994739532471,3.1198566076275758,1739502694.9050753,55.15994739532471,2.097384734078433 +1739502694.9255452,55.17994737625122,23.580647297491975,1739502694.9255488,55.17994737625122,0.10835882190529755,1739502694.9255528,55.17994737625122,89.0427191661582,1739502694.9255567,55.17994737625122,18.094377195133983,1739502694.9255588,55.17994737625122,-0.0063708577237109165,1739502694.9255612,55.17994737625122,-3.120683555526692,1739502694.925563,55.17994737625122,0.22870620085698581,1739502694.9255652,55.17994737625122,0.05832304459435707,1739502694.9255667,55.17994737625122,2.081993339683886,1739502694.925569,55.17994737625122,0.0,1739502694.9255707,55.17994737625122,-0.010394147377643178,1739502694.925573,55.17994737625122,3.120811777607502,1739502694.9255753,55.17994737625122,2.095242884479581 +1739502694.9450066,55.199947357177734,23.580647297491975,1739502694.94501,55.199947357177734,0.10835882190529755,1739502694.945014,55.199947357177734,89.0427191661582,1739502694.9450176,55.199947357177734,18.094377195133983,1739502694.9450197,55.199947357177734,-0.0063708577237109165,1739502694.9450219,55.199947357177734,-3.120683555526692,1739502694.945024,55.199947357177734,0.22870620085698581,1739502694.9450257,55.199947357177734,0.05832304459435707,1739502694.9450276,55.199947357177734,2.081993339683886,1739502694.9450297,55.199947357177734,0.0,1739502694.9450316,55.199947357177734,-0.013249544795694845,1739502694.9450336,55.199947357177734,3.120811777607502,1739502694.9450355,55.199947357177734,2.095242884479581 +1739502694.9653575,55.21994733810425,23.580647297491975,1739502694.965361,55.21994733810425,0.10835882190529755,1739502694.9653652,55.21994733810425,89.0427191661582,1739502694.965369,55.21994733810425,18.094377195133983,1739502694.965371,55.21994733810425,-0.0063708577237109165,1739502694.9653733,55.21994733810425,-3.120683555526692,1739502694.965375,55.21994733810425,0.22870620085698581,1739502694.965377,55.21994733810425,0.05832304459435707,1739502694.9653788,55.21994733810425,2.081993339683886,1739502694.965381,55.21994733810425,0.0,1739502694.9653826,55.21994733810425,-0.013249544795694845,1739502694.9653845,55.21994733810425,3.120811777607502,1739502694.9653864,55.21994733810425,2.095242884479581 +1739502694.9849586,55.23994731903076,23.580647297491975,1739502694.9849622,55.23994731903076,0.10835882190529755,1739502694.984966,55.23994731903076,89.0427191661582,1739502694.98497,55.23994731903076,18.094377195133983,1739502694.9849718,55.23994731903076,-0.0063708577237109165,1739502694.9849741,55.23994731903076,-3.120683555526692,1739502694.984976,55.23994731903076,0.22870620085698581,1739502694.984978,55.23994731903076,0.05832304459435707,1739502694.9849796,55.23994731903076,2.081993339683886,1739502694.9849818,55.23994731903076,0.0,1739502694.9849834,55.23994731903076,-0.013249544795694845,1739502694.9849856,55.23994731903076,3.120811777607502,1739502694.9849877,55.23994731903076,2.095242884479581 +1739502695.0051625,55.259947299957275,23.580647297491975,1739502695.0051658,55.259947299957275,0.10835882190529755,1739502695.0051696,55.259947299957275,89.0427191661582,1739502695.0051737,55.259947299957275,18.094377195133983,1739502695.0051758,55.259947299957275,-0.0063708577237109165,1739502695.005178,55.259947299957275,-3.120683555526692,1739502695.00518,55.259947299957275,0.22870620085698581,1739502695.0051818,55.259947299957275,0.05832304459435707,1739502695.0051835,55.259947299957275,2.081993339683886,1739502695.0051856,55.259947299957275,0.0,1739502695.0051873,55.259947299957275,-0.013249544795694845,1739502695.0051892,55.259947299957275,3.120811777607502,1739502695.0051908,55.259947299957275,2.095242884479581 +1739502695.025293,55.27994728088379,23.580647297491975,1739502695.0252967,55.27994728088379,0.10835882190529755,1739502695.0253007,55.27994728088379,89.0427191661582,1739502695.0253043,55.27994728088379,18.094377195133983,1739502695.0253065,55.27994728088379,-0.0063708577237109165,1739502695.0253084,55.27994728088379,-3.120683555526692,1739502695.0253105,55.27994728088379,0.22870620085698581,1739502695.0253122,55.27994728088379,0.05832304459435707,1739502695.0253139,55.27994728088379,2.081993339683886,1739502695.025316,55.27994728088379,0.0,1739502695.025318,55.27994728088379,-0.013249544795694845,1739502695.02532,55.27994728088379,3.120811777607502,1739502695.025322,55.27994728088379,2.095242884479581 +1739502695.0450785,55.2999472618103,23.350285548830747,1739502695.045082,55.2999472618103,0.11304658426857017,1739502695.0450861,55.2999472618103,89.26296941694471,1739502695.0450897,55.2999472618103,17.87692010849777,1739502695.0450919,55.2999472618103,-0.00537097441148469,1739502695.0450943,55.2999472618103,-3.1199607913062026,1739502695.0450962,55.2999472618103,0.22690051244104054,1739502695.045098,55.2999472618103,0.05813399942045523,1739502695.0450995,55.2999472618103,2.0850030580103556,1739502695.0451016,55.2999472618103,0.0,1739502695.0451033,55.2999472618103,-0.006843901212797248,1739502695.0451055,55.2999472618103,3.1217669475874286,1739502695.0451074,55.2999472618103,2.0938487241552677 +1739502695.064815,55.319947242736816,23.350285548830747,1739502695.0648181,55.319947242736816,0.11304658426857017,1739502695.064822,55.319947242736816,89.26296941694471,1739502695.0648255,55.319947242736816,17.87692010849777,1739502695.0648274,55.319947242736816,-0.00537097441148469,1739502695.06483,55.319947242736816,-3.1199607913062026,1739502695.0648317,55.319947242736816,0.22690051244104054,1739502695.0648339,55.319947242736816,0.05813399942045523,1739502695.0648353,55.319947242736816,2.0850030580103556,1739502695.0648375,55.319947242736816,0.0,1739502695.0648391,55.319947242736816,-0.008845666144912112,1739502695.064841,55.319947242736816,3.1217669475874286,1739502695.064843,55.319947242736816,2.0938487241552677 +1739502695.0850775,55.33994722366333,23.350285548830747,1739502695.085081,55.33994722366333,0.11304658426857017,1739502695.0850852,55.33994722366333,89.26296941694471,1739502695.085089,55.33994722366333,17.87692010849777,1739502695.0850909,55.33994722366333,-0.00537097441148469,1739502695.0850933,55.33994722366333,-3.1199607913062026,1739502695.0850952,55.33994722366333,0.22690051244104054,1739502695.085097,55.33994722366333,0.05813399942045523,1739502695.0850985,55.33994722366333,2.0850030580103556,1739502695.085101,55.33994722366333,0.0,1739502695.0851026,55.33994722366333,-0.008845666144912112,1739502695.0851045,55.33994722366333,3.1217669475874286,1739502695.0851064,55.33994722366333,2.0938487241552677 +1739502695.105005,55.359947204589844,23.350285548830747,1739502695.1050084,55.359947204589844,0.11304658426857017,1739502695.1050127,55.359947204589844,89.26296941694471,1739502695.1050165,55.359947204589844,17.87692010849777,1739502695.1050184,55.359947204589844,-0.00537097441148469,1739502695.1050208,55.359947204589844,-3.1199607913062026,1739502695.1050224,55.359947204589844,0.22690051244104054,1739502695.1050243,55.359947204589844,0.05813399942045523,1739502695.105026,55.359947204589844,2.0850030580103556,1739502695.1050282,55.359947204589844,0.0,1739502695.1050298,55.359947204589844,-0.008845666144912112,1739502695.1050317,55.359947204589844,3.1217669475874286,1739502695.1050334,55.359947204589844,2.0938487241552677 +1739502695.125318,55.37994718551636,23.350285548830747,1739502695.1253216,55.37994718551636,0.11304658426857017,1739502695.1253262,55.37994718551636,89.26296941694471,1739502695.12533,55.37994718551636,17.87692010849777,1739502695.1253316,55.37994718551636,-0.00537097441148469,1739502695.125334,55.37994718551636,-3.1199607913062026,1739502695.1253362,55.37994718551636,0.22690051244104054,1739502695.1253378,55.37994718551636,0.05813399942045523,1739502695.1253397,55.37994718551636,2.0850030580103556,1739502695.1253417,55.37994718551636,0.0,1739502695.1253436,55.37994718551636,-0.008845666144912112,1739502695.1253455,55.37994718551636,3.1217669475874286,1739502695.1253476,55.37994718551636,2.0938487241552677 +1739502695.1454663,55.39994716644287,23.12005487601691,1739502695.1454694,55.39994716644287,0.11751167899115789,1739502695.145473,55.39994716644287,89.30476287497007,1739502695.1454766,55.39994716644287,17.837070628221152,1739502695.1454785,55.39994716644287,-0.005018324143549998,1739502695.1454806,55.39994716644287,-3.1184034798960405,1739502695.1454825,55.39994716644287,0.22219501543352957,1739502695.1454842,55.39994716644287,0.061100292328902975,1739502695.145486,55.39994716644287,2.0928666300503145,1739502695.1454885,55.39994716644287,0.0,1739502695.1454902,55.39994716644287,0.004004927837437433,1739502695.145492,55.39994716644287,3.122722117567355,1739502695.1454937,55.39994716644287,2.0928775154653336 +1739502695.1652656,55.419947147369385,23.12005487601691,1739502695.1652687,55.419947147369385,0.11751167899115789,1739502695.1652725,55.419947147369385,89.30476287497007,1739502695.165276,55.419947147369385,17.837070628221152,1739502695.165278,55.419947147369385,-0.005018324143549998,1739502695.1652803,55.419947147369385,-3.1184034798960405,1739502695.165282,55.419947147369385,0.22219501543352957,1739502695.165284,55.419947147369385,0.061100292328902975,1739502695.1652853,55.419947147369385,2.0928666300503145,1739502695.1652875,55.419947147369385,0.0,1739502695.1652892,55.419947147369385,-1.0885415019146194e-05,1739502695.165291,55.419947147369385,3.122722117567355,1739502695.1652927,55.419947147369385,2.0928775154653336 +1739502695.1850846,55.4399471282959,23.12005487601691,1739502695.1850882,55.4399471282959,0.11751167899115789,1739502695.1850927,55.4399471282959,89.30476287497007,1739502695.1850965,55.4399471282959,17.837070628221152,1739502695.1850982,55.4399471282959,-0.005018324143549998,1739502695.1851006,55.4399471282959,-3.1184034798960405,1739502695.1851027,55.4399471282959,0.22219501543352957,1739502695.1851044,55.4399471282959,0.061100292328902975,1739502695.1851063,55.4399471282959,2.0928666300503145,1739502695.1851082,55.4399471282959,0.0,1739502695.18511,55.4399471282959,-1.0885415019146194e-05,1739502695.185112,55.4399471282959,3.122722117567355,1739502695.1851141,55.4399471282959,2.0928775154653336 +1739502695.2050414,55.45994710922241,23.12005487601691,1739502695.2050447,55.45994710922241,0.11751167899115789,1739502695.2050488,55.45994710922241,89.30476287497007,1739502695.2050524,55.45994710922241,17.837070628221152,1739502695.2050545,55.45994710922241,-0.005018324143549998,1739502695.2050567,55.45994710922241,-3.1184034798960405,1739502695.2050588,55.45994710922241,0.22219501543352957,1739502695.2050607,55.45994710922241,0.061100292328902975,1739502695.2050622,55.45994710922241,2.0928666300503145,1739502695.2050648,55.45994710922241,0.0,1739502695.2050664,55.45994710922241,-1.0885415019146194e-05,1739502695.2050686,55.45994710922241,3.122722117567355,1739502695.2050703,55.45994710922241,2.0928775154653336 +1739502695.2250814,55.479947090148926,23.12005487601691,1739502695.2250843,55.479947090148926,0.11751167899115789,1739502695.2250886,55.479947090148926,89.30476287497007,1739502695.2250922,55.479947090148926,17.837070628221152,1739502695.2250938,55.479947090148926,-0.005018324143549998,1739502695.2250962,55.479947090148926,-3.1184034798960405,1739502695.225098,55.479947090148926,0.22219501543352957,1739502695.2250998,55.479947090148926,0.061100292328902975,1739502695.2251012,55.479947090148926,2.0928666300503145,1739502695.2251034,55.479947090148926,0.0,1739502695.225105,55.479947090148926,-1.0885415019146194e-05,1739502695.225107,55.479947090148926,3.122722117567355,1739502695.225109,55.479947090148926,2.0928775154653336 +1739502695.245043,55.49994707107544,23.12005487601691,1739502695.2450469,55.49994707107544,0.11751167899115789,1739502695.2450507,55.49994707107544,89.30476287497007,1739502695.2450545,55.49994707107544,17.837070628221152,1739502695.2450566,55.49994707107544,-0.005018324143549998,1739502695.2450588,55.49994707107544,-3.1184034798960405,1739502695.2450607,55.49994707107544,0.22219501543352957,1739502695.2450626,55.49994707107544,0.061100292328902975,1739502695.2450643,55.49994707107544,2.0928666300503145,1739502695.2450662,55.49994707107544,0.0,1739502695.245068,55.49994707107544,-1.0885415019146194e-05,1739502695.2450702,55.49994707107544,3.122722117567355,1739502695.2450724,55.49994707107544,2.0928775154653336 +1739502695.2655146,55.51994705200195,22.889869942888467,1739502695.2655184,55.51994705200195,0.1217559335047893,1739502695.265523,55.51994705200195,89.54360380475535,1739502695.265527,55.51994705200195,17.598082336471528,1739502695.2655292,55.51994705200195,-0.0028910146865002966,1739502695.265532,55.51994705200195,-3.1180422179740686,1739502695.265534,55.51994705200195,0.21942618602837527,1739502695.2655358,55.51994705200195,0.06013755895229046,1739502695.2655377,55.51994705200195,2.097507600708225,1739502695.2655404,55.51994705200195,0.0,1739502695.2655425,55.51994705200195,0.006625544852091455,1739502695.2655444,55.51994705200195,3.1236772875472814,1739502695.2655466,55.51994705200195,2.0929559416743513 +1739502695.285037,55.53994703292847,22.889869942888467,1739502695.285041,55.53994703292847,0.1217559335047893,1739502695.285045,55.53994703292847,89.54360380475535,1739502695.2850485,55.53994703292847,17.598082336471528,1739502695.2850504,55.53994703292847,-0.0028910146865002966,1739502695.2850528,55.53994703292847,-3.1180422179740686,1739502695.2850547,55.53994703292847,0.21942618602837527,1739502695.2850566,55.53994703292847,0.06013755895229046,1739502695.285058,55.53994703292847,2.097507600708225,1739502695.2850604,55.53994703292847,0.0,1739502695.285062,55.53994703292847,0.004551659033873889,1739502695.285064,55.53994703292847,3.1236772875472814,1739502695.285066,55.53994703292847,2.0929559416743513 +1739502695.3050976,55.55994701385498,22.889869942888467,1739502695.3051012,55.55994701385498,0.1217559335047893,1739502695.3051052,55.55994701385498,89.54360380475535,1739502695.305109,55.55994701385498,17.598082336471528,1739502695.3051107,55.55994701385498,-0.0028910146865002966,1739502695.3051133,55.55994701385498,-3.1180422179740686,1739502695.3051152,55.55994701385498,0.21942618602837527,1739502695.305117,55.55994701385498,0.06013755895229046,1739502695.3051188,55.55994701385498,2.097507600708225,1739502695.3051207,55.55994701385498,0.0,1739502695.3051226,55.55994701385498,0.004551659033873889,1739502695.3051245,55.55994701385498,3.1236772875472814,1739502695.305127,55.55994701385498,2.0929559416743513 +1739502695.3253994,55.579946994781494,22.889869942888467,1739502695.3254027,55.579946994781494,0.1217559335047893,1739502695.3254066,55.579946994781494,89.54360380475535,1739502695.3254104,55.579946994781494,17.598082336471528,1739502695.3254123,55.579946994781494,-0.0028910146865002966,1739502695.3254144,55.579946994781494,-3.1180422179740686,1739502695.3254166,55.579946994781494,0.21942618602837527,1739502695.325418,55.579946994781494,0.06013755895229046,1739502695.3254197,55.579946994781494,2.097507600708225,1739502695.3254218,55.579946994781494,0.0,1739502695.3254237,55.579946994781494,0.004551659033873889,1739502695.3254254,55.579946994781494,3.1236772875472814,1739502695.3254275,55.579946994781494,2.0929559416743513 +1739502695.3450108,55.59994697570801,22.889869942888467,1739502695.3450143,55.59994697570801,0.1217559335047893,1739502695.3450184,55.59994697570801,89.54360380475535,1739502695.345022,55.59994697570801,17.598082336471528,1739502695.3450236,55.59994697570801,-0.0028910146865002966,1739502695.3450263,55.59994697570801,-3.1180422179740686,1739502695.3450282,55.59994697570801,0.21942618602837527,1739502695.34503,55.59994697570801,0.06013755895229046,1739502695.3450317,55.59994697570801,2.097507600708225,1739502695.345034,55.59994697570801,0.0,1739502695.3450358,55.59994697570801,0.004551659033873889,1739502695.345038,55.59994697570801,3.1236772875472814,1739502695.3450396,55.59994697570801,2.0929559416743513 +1739502695.3655663,55.61994695663452,22.65965605038508,1739502695.3655698,55.61994695663452,0.12578075359450214,1739502695.3655744,55.61994695663452,89.82283913305785,1739502695.3655782,55.61994695663452,17.31786877727733,1739502695.36558,55.61994695663452,-0.0006315823891529422,1739502695.365583,55.61994695663452,-3.1179322681202293,1739502695.3655849,55.61994695663452,0.21698757143365321,1739502695.3655868,55.61994695663452,0.05836130082252747,1739502695.3655887,55.61994695663452,2.1016036049575155,1739502695.3655908,55.61994695663452,0.0,1739502695.3655925,55.61994695663452,0.009790554540681208,1739502695.3655946,55.61994695663452,3.1246324575272078,1739502695.3655972,55.61994695663452,2.0934502063361147 +1739502695.3851686,55.639946937561035,22.65965605038508,1739502695.3851721,55.639946937561035,0.12578075359450214,1739502695.3851764,55.639946937561035,89.82283913305785,1739502695.38518,55.639946937561035,17.31786877727733,1739502695.3851817,55.639946937561035,-0.0006315823891529422,1739502695.3851843,55.639946937561035,-3.1179322681202293,1739502695.385186,55.639946937561035,0.21698757143365321,1739502695.3851879,55.639946937561035,0.05836130082252747,1739502695.3851895,55.639946937561035,2.1016036049575155,1739502695.385192,55.639946937561035,0.0,1739502695.3851938,55.639946937561035,0.008153398621400854,1739502695.3851957,55.639946937561035,3.1246324575272078,1739502695.3851979,55.639946937561035,2.0934502063361147 +1739502695.4049757,55.65994691848755,22.65965605038508,1739502695.4049792,55.65994691848755,0.12578075359450214,1739502695.404983,55.65994691848755,89.82283913305785,1739502695.4049866,55.65994691848755,17.31786877727733,1739502695.4049885,55.65994691848755,-0.0006315823891529422,1739502695.4049907,55.65994691848755,-3.1179322681202293,1739502695.404993,55.65994691848755,0.21698757143365321,1739502695.4049947,55.65994691848755,0.05836130082252747,1739502695.4049966,55.65994691848755,2.1016036049575155,1739502695.4049985,55.65994691848755,0.0,1739502695.4050004,55.65994691848755,0.008153398621400854,1739502695.4050028,55.65994691848755,3.1246324575272078,1739502695.4050045,55.65994691848755,2.0934502063361147 +1739502695.4253068,55.67994689941406,22.65965605038508,1739502695.4253104,55.67994689941406,0.12578075359450214,1739502695.425315,55.67994689941406,89.82283913305785,1739502695.4253185,55.67994689941406,17.31786877727733,1739502695.4253204,55.67994689941406,-0.0006315823891529422,1739502695.4253232,55.67994689941406,-3.1179322681202293,1739502695.4253254,55.67994689941406,0.21698757143365321,1739502695.4253273,55.67994689941406,0.05836130082252747,1739502695.425329,55.67994689941406,2.1016036049575155,1739502695.425331,55.67994689941406,0.0,1739502695.4253333,55.67994689941406,0.008153398621400854,1739502695.4253354,55.67994689941406,3.1246324575272078,1739502695.4253373,55.67994689941406,2.0934502063361147 +1739502695.445039,55.699946880340576,22.65965605038508,1739502695.4450428,55.699946880340576,0.12578075359450214,1739502695.4450471,55.699946880340576,89.82283913305785,1739502695.4450507,55.699946880340576,17.31786877727733,1739502695.4450526,55.699946880340576,-0.0006315823891529422,1739502695.445055,55.699946880340576,-3.1179322681202293,1739502695.4450576,55.699946880340576,0.21698757143365321,1739502695.4450593,55.699946880340576,0.05836130082252747,1739502695.4450612,55.699946880340576,2.1016036049575155,1739502695.445063,55.699946880340576,0.0,1739502695.4450653,55.699946880340576,0.008153398621400854,1739502695.445067,55.699946880340576,3.1246324575272078,1739502695.445069,55.699946880340576,2.0934502063361147 +1739502695.4656408,55.71994686126709,22.65965605038508,1739502695.4656448,55.71994686126709,0.12578075359450214,1739502695.4656487,55.71994686126709,89.82283913305785,1739502695.4656527,55.71994686126709,17.31786877727733,1739502695.4656549,55.71994686126709,-0.0006315823891529422,1739502695.4656572,55.71994686126709,-3.1179322681202293,1739502695.4656591,55.71994686126709,0.21698757143365321,1739502695.4656608,55.71994686126709,0.05836130082252747,1739502695.4656627,55.71994686126709,2.1016036049575155,1739502695.4656649,55.71994686126709,0.0,1739502695.4656665,55.71994686126709,0.008153398621400854,1739502695.4656687,55.71994686126709,3.1246324575272078,1739502695.4656706,55.71994686126709,2.0934502063361147 +1739502695.485111,55.7399468421936,22.42936016906471,1739502695.4851143,55.7399468421936,0.1295869683105053,1739502695.4851184,55.7399468421936,90.61032320337185,1739502695.485122,55.7399468421936,16.528559976098457,1739502695.4851239,55.7399468421936,0.00532576291441987,1739502695.4851263,55.7399468421936,-3.12053740037919,1739502695.4851282,55.7399468421936,0.2186837192788358,1739502695.48513,55.7399468421936,0.04820875554129231,1739502695.4851317,55.7399468421936,2.098753834506794,1739502695.485134,55.7399468421936,0.0,1739502695.4851353,55.7399468421936,0.00266249651776475,1739502695.4851375,55.7399468421936,3.125587627507134,1739502695.4851391,55.7399468421936,2.094375429956606 +1739502695.5051212,55.75994682312012,22.42936016906471,1739502695.5051246,55.75994682312012,0.1295869683105053,1739502695.5051286,55.75994682312012,90.61032320337185,1739502695.5051324,55.75994682312012,16.528559976098457,1739502695.5051346,55.75994682312012,0.00532576291441987,1739502695.505137,55.75994682312012,-3.12053740037919,1739502695.5051386,55.75994682312012,0.2186837192788358,1739502695.5051405,55.75994682312012,0.04820875554129231,1739502695.5051425,55.75994682312012,2.098753834506794,1739502695.5051446,55.75994682312012,0.0,1739502695.5051463,55.75994682312012,0.004378404550188009,1739502695.5051482,55.75994682312012,3.125587627507134,1739502695.5051508,55.75994682312012,2.094375429956606 +1739502695.5256321,55.77994680404663,22.42936016906471,1739502695.5256364,55.77994680404663,0.1295869683105053,1739502695.5256407,55.77994680404663,90.61032320337185,1739502695.5256445,55.77994680404663,16.528559976098457,1739502695.5256464,55.77994680404663,0.00532576291441987,1739502695.5256486,55.77994680404663,-3.12053740037919,1739502695.5256507,55.77994680404663,0.2186837192788358,1739502695.5256524,55.77994680404663,0.04820875554129231,1739502695.525654,55.77994680404663,2.098753834506794,1739502695.5256562,55.77994680404663,0.0,1739502695.5256581,55.77994680404663,0.004378404550188009,1739502695.5256603,55.77994680404663,3.125587627507134,1739502695.525662,55.77994680404663,2.094375429956606 +1739502695.5453825,55.799946784973145,22.42936016906471,1739502695.5453868,55.799946784973145,0.1295869683105053,1739502695.5453916,55.799946784973145,90.61032320337185,1739502695.5453954,55.799946784973145,16.528559976098457,1739502695.5453975,55.799946784973145,0.00532576291441987,1739502695.5454001,55.799946784973145,-3.12053740037919,1739502695.5454018,55.799946784973145,0.2186837192788358,1739502695.545404,55.799946784973145,0.04820875554129231,1739502695.5454056,55.799946784973145,2.098753834506794,1739502695.5454078,55.799946784973145,0.0,1739502695.5454094,55.799946784973145,0.004378404550188009,1739502695.5454125,55.799946784973145,3.125587627507134,1739502695.5454144,55.799946784973145,2.094375429956606 +1739502695.565681,55.81994676589966,22.42936016906471,1739502695.5656848,55.81994676589966,0.1295869683105053,1739502695.565689,55.81994676589966,90.61032320337185,1739502695.565693,55.81994676589966,16.528559976098457,1739502695.565695,55.81994676589966,0.00532576291441987,1739502695.5656972,55.81994676589966,-3.12053740037919,1739502695.5656993,55.81994676589966,0.2186837192788358,1739502695.565701,55.81994676589966,0.04820875554129231,1739502695.565703,55.81994676589966,2.098753834506794,1739502695.565705,55.81994676589966,0.0,1739502695.5657067,55.81994676589966,0.004378404550188009,1739502695.5657086,55.81994676589966,3.125587627507134,1739502695.5657105,55.81994676589966,2.094375429956606 +1739502695.5853274,55.83994674682617,22.198982028236397,1739502695.5853307,55.83994674682617,0.13317443952927377,1739502695.5853348,55.83994674682617,90.62576212627856,1739502695.5853386,55.83994674682617,16.51215778437048,1739502695.5853407,55.83994674682617,0.005464764539233233,1739502695.5853426,55.83994674682617,-3.119139311078765,1739502695.5853448,55.83994674682617,0.21327786800647877,1739502695.5853465,55.83994674682617,0.05061826014128602,1739502695.5853484,55.83994674682617,2.107849930055061,1739502695.5853505,55.83994674682617,0.0,1739502695.5853524,55.83994674682617,0.016908105226804013,1739502695.5853543,55.83994674682617,3.1265427974870605,1739502695.585356,55.83994674682617,2.0948573588569235 +1739502695.605039,55.859946727752686,22.198982028236397,1739502695.6050425,55.859946727752686,0.13317443952927377,1739502695.6050465,55.859946727752686,90.62576212627856,1739502695.6050503,55.859946727752686,16.51215778437048,1739502695.6050522,55.859946727752686,0.005464764539233233,1739502695.6050544,55.859946727752686,-3.119139311078765,1739502695.6050565,55.859946727752686,0.21327786800647877,1739502695.6050587,55.859946727752686,0.05061826014128602,1739502695.6050603,55.859946727752686,2.107849930055061,1739502695.6050625,55.859946727752686,0.0,1739502695.6050642,55.859946727752686,0.012992571198137348,1739502695.6050665,55.859946727752686,3.1265427974870605,1739502695.6050684,55.859946727752686,2.0948573588569235 +1739502695.625439,55.8799467086792,22.198982028236397,1739502695.6254423,55.8799467086792,0.13317443952927377,1739502695.6254466,55.8799467086792,90.62576212627856,1739502695.6254501,55.8799467086792,16.51215778437048,1739502695.625452,55.8799467086792,0.005464764539233233,1739502695.6254544,55.8799467086792,-3.119139311078765,1739502695.625456,55.8799467086792,0.21327786800647877,1739502695.6254582,55.8799467086792,0.05061826014128602,1739502695.62546,55.8799467086792,2.107849930055061,1739502695.625462,55.8799467086792,0.0,1739502695.6254637,55.8799467086792,0.012992571198137348,1739502695.6254659,55.8799467086792,3.1265427974870605,1739502695.625468,55.8799467086792,2.0948573588569235 +1739502695.645077,55.89994668960571,22.198982028236397,1739502695.6450808,55.89994668960571,0.13317443952927377,1739502695.6450846,55.89994668960571,90.62576212627856,1739502695.6450884,55.89994668960571,16.51215778437048,1739502695.6450906,55.89994668960571,0.005464764539233233,1739502695.645093,55.89994668960571,-3.119139311078765,1739502695.6450946,55.89994668960571,0.21327786800647877,1739502695.6450965,55.89994668960571,0.05061826014128602,1739502695.6450982,55.89994668960571,2.107849930055061,1739502695.6451004,55.89994668960571,0.0,1739502695.645102,55.89994668960571,0.012992571198137348,1739502695.6451042,55.89994668960571,3.1265427974870605,1739502695.6451058,55.89994668960571,2.0948573588569235 +1739502695.665899,55.91994667053223,22.198982028236397,1739502695.665903,55.91994667053223,0.13317443952927377,1739502695.6659076,55.91994667053223,90.62576212627856,1739502695.6659112,55.91994667053223,16.51215778437048,1739502695.6659133,55.91994667053223,0.005464764539233233,1739502695.6659157,55.91994667053223,-3.119139311078765,1739502695.6659179,55.91994667053223,0.21327786800647877,1739502695.66592,55.91994667053223,0.05061826014128602,1739502695.6659214,55.91994667053223,2.107849930055061,1739502695.6659238,55.91994667053223,0.0,1739502695.6659257,55.91994667053223,0.012992571198137348,1739502695.6659276,55.91994667053223,3.1265427974870605,1739502695.6659298,55.91994667053223,2.0948573588569235 +1739502695.6850832,55.93994665145874,22.198982028236397,1739502695.6850865,55.93994665145874,0.13317443952927377,1739502695.6850908,55.93994665145874,90.62576212627856,1739502695.6850946,55.93994665145874,16.51215778437048,1739502695.6850965,55.93994665145874,0.005464764539233233,1739502695.6850986,55.93994665145874,-3.119139311078765,1739502695.6851008,55.93994665145874,0.21327786800647877,1739502695.6851027,55.93994665145874,0.05061826014128602,1739502695.6851041,55.93994665145874,2.107849930055061,1739502695.6851063,55.93994665145874,0.0,1739502695.685108,55.93994665145874,0.012992571198137348,1739502695.68511,55.93994665145874,3.1265427974870605,1739502695.685112,55.93994665145874,2.0948573588569235 +1739502695.7053409,55.959946632385254,21.968493674810173,1739502695.7053447,55.959946632385254,0.13654341244023893,1739502695.7053492,55.959946632385254,90.64120821493103,1739502695.7053533,55.959946632385254,16.49371183221706,1739502695.7053552,55.959946632385254,0.005621086167652045,1739502695.7053576,55.959946632385254,-3.117683503974718,1739502695.7053595,55.959946632385254,0.20807209870278515,1739502695.7053614,55.959946632385254,0.053277947192523156,1739502695.7053638,55.959946632385254,2.1166466191246123,1739502695.7053657,55.959946632385254,0.0,1739502695.7053678,55.959946632385254,0.02360555783034631,1739502695.7053697,55.959946632385254,3.127497967466987,1739502695.7053716,55.959946632385254,2.0963576217913378 +1739502695.7255857,55.97994661331177,21.968493674810173,1739502695.7255893,55.97994661331177,0.13654341244023893,1739502695.7255933,55.97994661331177,90.64120821493103,1739502695.7255974,55.97994661331177,16.49371183221706,1739502695.7255995,55.97994661331177,0.005621086167652045,1739502695.7256021,55.97994661331177,-3.117683503974718,1739502695.7256038,55.97994661331177,0.20807209870278515,1739502695.7256057,55.97994661331177,0.053277947192523156,1739502695.7256074,55.97994661331177,2.1166466191246123,1739502695.7256095,55.97994661331177,0.0,1739502695.7256114,55.97994661331177,0.020288997333274494,1739502695.7256138,55.97994661331177,3.127497967466987,1739502695.7256155,55.97994661331177,2.0963576217913378 +1739502695.74495,55.99994659423828,21.968493674810173,1739502695.7449539,55.99994659423828,0.13654341244023893,1739502695.7449584,55.99994659423828,90.64120821493103,1739502695.7449622,55.99994659423828,16.49371183221706,1739502695.7449644,55.99994659423828,0.005621086167652045,1739502695.744967,55.99994659423828,-3.117683503974718,1739502695.744969,55.99994659423828,0.20807209870278515,1739502695.744971,55.99994659423828,0.053277947192523156,1739502695.7449727,55.99994659423828,2.1166466191246123,1739502695.7449749,55.99994659423828,0.0,1739502695.744977,55.99994659423828,0.020288997333274494,1739502695.7449787,55.99994659423828,3.127497967466987,1739502695.744981,55.99994659423828,2.0963576217913378 +1739502695.7657213,56.019946575164795,21.968493674810173,1739502695.7657254,56.019946575164795,0.13654341244023893,1739502695.7657301,56.019946575164795,90.64120821493103,1739502695.7657342,56.019946575164795,16.49371183221706,1739502695.765736,56.019946575164795,0.005621086167652045,1739502695.7657385,56.019946575164795,-3.117683503974718,1739502695.7657406,56.019946575164795,0.20807209870278515,1739502695.7657423,56.019946575164795,0.053277947192523156,1739502695.7657442,56.019946575164795,2.1166466191246123,1739502695.765746,56.019946575164795,0.0,1739502695.765748,56.019946575164795,0.020288997333274494,1739502695.76575,56.019946575164795,3.127497967466987,1739502695.7657523,56.019946575164795,2.0963576217913378 +1739502695.7850647,56.03994655609131,21.968493674810173,1739502695.785068,56.03994655609131,0.13654341244023893,1739502695.7850718,56.03994655609131,90.64120821493103,1739502695.7850757,56.03994655609131,16.49371183221706,1739502695.7850776,56.03994655609131,0.005621086167652045,1739502695.7850797,56.03994655609131,-3.117683503974718,1739502695.7850816,56.03994655609131,0.20807209870278515,1739502695.7850833,56.03994655609131,0.053277947192523156,1739502695.7850852,56.03994655609131,2.1166466191246123,1739502695.7850873,56.03994655609131,0.0,1739502695.785089,56.03994655609131,0.020288997333274494,1739502695.7850912,56.03994655609131,3.127497967466987,1739502695.7850928,56.03994655609131,2.0963576217913378 +1739502695.805106,56.05994653701782,21.737806373453065,1739502695.8051095,56.05994653701782,0.13969489691279957,1739502695.8051138,56.05994653701782,90.99916479616732,1739502695.8051174,56.05994653701782,16.131344346234762,1739502695.8051193,56.05994653701782,0.008,1739502695.805122,56.05994653701782,-3.118107132344626,1739502695.8051236,56.05994653701782,0.2053476073423042,1739502695.8051255,56.05994653701782,0.050141011297182986,1739502695.8051274,56.05994653701782,2.121265078819243,1739502695.8051295,56.05994653701782,0.0,1739502695.8051312,56.05994653701782,0.023786815528130407,1739502695.805133,56.05994653701782,3.1284531374469133,1739502695.805135,56.05994653701782,2.0985713321936768 +1739502695.8255835,56.079946517944336,21.737806373453065,1739502695.8255873,56.079946517944336,0.13969489691279957,1739502695.8255913,56.079946517944336,90.99916479616732,1739502695.825595,56.079946517944336,16.131344346234762,1739502695.8255968,56.079946517944336,0.008,1739502695.8255994,56.079946517944336,-3.118107132344626,1739502695.8256013,56.079946517944336,0.2053476073423042,1739502695.825603,56.079946517944336,0.050141011297182986,1739502695.825605,56.079946517944336,2.121265078819243,1739502695.8256068,56.079946517944336,0.0,1739502695.8256087,56.079946517944336,0.022693746625566114,1739502695.8256106,56.079946517944336,3.1284531374469133,1739502695.8256125,56.079946517944336,2.0985713321936768 +1739502695.8450723,56.09994649887085,21.737806373453065,1739502695.845076,56.09994649887085,0.13969489691279957,1739502695.84508,56.09994649887085,90.99916479616732,1739502695.8450835,56.09994649887085,16.131344346234762,1739502695.8450854,56.09994649887085,0.008,1739502695.8450878,56.09994649887085,-3.118107132344626,1739502695.8450897,56.09994649887085,0.2053476073423042,1739502695.8450916,56.09994649887085,0.050141011297182986,1739502695.8450935,56.09994649887085,2.121265078819243,1739502695.8450954,56.09994649887085,0.0,1739502695.8450973,56.09994649887085,0.022693746625566114,1739502695.845099,56.09994649887085,3.1284531374469133,1739502695.845101,56.09994649887085,2.0985713321936768 +1739502695.865141,56.11994647979736,21.737806373453065,1739502695.865144,56.11994647979736,0.13969489691279957,1739502695.8651476,56.11994647979736,90.99916479616732,1739502695.8651514,56.11994647979736,16.131344346234762,1739502695.8651533,56.11994647979736,0.008,1739502695.865156,56.11994647979736,-3.118107132344626,1739502695.8651578,56.11994647979736,0.2053476073423042,1739502695.8651597,56.11994647979736,0.050141011297182986,1739502695.8651614,56.11994647979736,2.121265078819243,1739502695.8651638,56.11994647979736,0.0,1739502695.8651655,56.11994647979736,0.022693746625566114,1739502695.8651674,56.11994647979736,3.1284531374469133,1739502695.865169,56.11994647979736,2.0985713321936768 +1739502695.8851466,56.13994646072388,21.737806373453065,1739502695.8851502,56.13994646072388,0.13969489691279957,1739502695.8851542,56.13994646072388,90.99916479616732,1739502695.885158,56.13994646072388,16.131344346234762,1739502695.8851602,56.13994646072388,0.008,1739502695.8851626,56.13994646072388,-3.118107132344626,1739502695.8851645,56.13994646072388,0.2053476073423042,1739502695.8851664,56.13994646072388,0.050141011297182986,1739502695.885168,56.13994646072388,2.121265078819243,1739502695.8851705,56.13994646072388,0.0,1739502695.8851721,56.13994646072388,0.022693746625566114,1739502695.885174,56.13994646072388,3.1284531374469133,1739502695.8851762,56.13994646072388,2.0985713321936768 +1739502695.905053,56.15994644165039,21.737806373453065,1739502695.9050567,56.15994644165039,0.13969489691279957,1739502695.9050608,56.15994644165039,90.99916479616732,1739502695.9050643,56.15994644165039,16.131344346234762,1739502695.9050663,56.15994644165039,0.008,1739502695.9050686,56.15994644165039,-3.118107132344626,1739502695.9050705,56.15994644165039,0.2053476073423042,1739502695.9050725,56.15994644165039,0.050141011297182986,1739502695.9050741,56.15994644165039,2.121265078819243,1739502695.9050763,56.15994644165039,0.0,1739502695.905078,56.15994644165039,0.022693746625566114,1739502695.9050798,56.15994644165039,3.1284531374469133,1739502695.9050817,56.15994644165039,2.0985713321936768 +1739502695.9254613,56.179946422576904,21.506855636790856,1739502695.9254646,56.179946422576904,0.14262934256766613,1739502695.9254684,56.179946422576904,91.02503421311914,1739502695.9254723,56.179946422576904,16.10046186254194,1739502695.9254742,56.179946422576904,0.008,1739502695.9254763,56.179946422576904,-3.1166959238101417,1739502695.9254785,56.179946422576904,0.20049109261292253,1739502695.9254801,56.179946422576904,0.052641366382421007,1739502695.925482,56.179946422576904,2.1295226737647277,1739502695.925484,56.179946422576904,0.0,1739502695.9254858,56.179946422576904,0.03105892959129225,1739502695.9254878,56.179946422576904,3.1294083074268397,1739502695.92549,56.179946422576904,2.1010778655641764 +1739502695.9451036,56.19994640350342,21.506855636790856,1739502695.9451072,56.19994640350342,0.14262934256766613,1739502695.9451115,56.19994640350342,91.02503421311914,1739502695.945115,56.19994640350342,16.10046186254194,1739502695.945117,56.19994640350342,0.008,1739502695.9451194,56.19994640350342,-3.1166959238101417,1739502695.9451213,56.19994640350342,0.20049109261292253,1739502695.9451234,56.19994640350342,0.052641366382421007,1739502695.945125,56.19994640350342,2.1295226737647277,1739502695.9451275,56.19994640350342,0.0,1739502695.9451292,56.19994640350342,0.028444808200551286,1739502695.9451313,56.19994640350342,3.1294083074268397,1739502695.945133,56.19994640350342,2.1010778655641764 +1739502695.9655242,56.21994638442993,21.506855636790856,1739502695.9655278,56.21994638442993,0.14262934256766613,1739502695.965532,56.21994638442993,91.02503421311914,1739502695.965536,56.21994638442993,16.10046186254194,1739502695.9655378,56.21994638442993,0.008,1739502695.9655402,56.21994638442993,-3.1166959238101417,1739502695.965542,56.21994638442993,0.20049109261292253,1739502695.965544,56.21994638442993,0.052641366382421007,1739502695.9655457,56.21994638442993,2.1295226737647277,1739502695.965548,56.21994638442993,0.0,1739502695.9655497,56.21994638442993,0.028444808200551286,1739502695.9655519,56.21994638442993,3.1294083074268397,1739502695.9655538,56.21994638442993,2.1010778655641764 +1739502695.988137,56.239946365356445,21.506855636790856,1739502695.9881425,56.239946365356445,0.14262934256766613,1739502695.9881496,56.239946365356445,91.02503421311914,1739502695.988158,56.239946365356445,16.10046186254194,1739502695.9881628,56.239946365356445,0.008,1739502695.9881685,56.239946365356445,-3.1166959238101417,1739502695.9881737,56.239946365356445,0.20049109261292253,1739502695.9881792,56.239946365356445,0.052641366382421007,1739502695.9881842,56.239946365356445,2.1295226737647277,1739502695.9881897,56.239946365356445,0.0,1739502695.9881954,56.239946365356445,0.028444808200551286,1739502695.9882007,56.239946365356445,3.1294083074268397,1739502695.9882061,56.239946365356445,2.1010778655641764 +1739502696.005594,56.25994634628296,21.506855636790856,1739502696.0055983,56.25994634628296,0.14262934256766613,1739502696.0056026,56.25994634628296,91.02503421311914,1739502696.0056067,56.25994634628296,16.10046186254194,1739502696.0056093,56.25994634628296,0.008,1739502696.0056121,56.25994634628296,-3.1166959238101417,1739502696.005614,56.25994634628296,0.20049109261292253,1739502696.0056162,56.25994634628296,0.052641366382421007,1739502696.005618,56.25994634628296,2.1295226737647277,1739502696.0056205,56.25994634628296,0.0,1739502696.0056229,56.25994634628296,0.028444808200551286,1739502696.0056248,56.25994634628296,3.1294083074268397,1739502696.0056272,56.25994634628296,2.1010778655641764 +1739502696.0254178,56.27994632720947,21.2755985583672,1739502696.0254211,56.27994632720947,0.145346752186839,1739502696.0254252,56.27994632720947,91.35020061220109,1739502696.0254292,56.27994632720947,15.769085385701782,1739502696.0254314,56.27994632720947,0.009,1739502696.025434,56.27994632720947,-3.116836715828113,1739502696.0254362,56.27994632720947,0.1981704630960128,1739502696.0254383,56.27994632720947,0.05015798974896722,1739502696.0254402,56.27994632720947,2.13347981238818,1739502696.0254426,56.27994632720947,0.0,1739502696.0254445,56.27994632720947,0.02968111843260792,1739502696.025447,56.27994632720947,3.130363477406766,1739502696.0254493,56.27994632720947,2.104185041156399 +1739502696.045584,56.299946308135986,21.2755985583672,1739502696.0455873,56.299946308135986,0.145346752186839,1739502696.045592,56.299946308135986,91.35020061220109,1739502696.0455961,56.299946308135986,15.769085385701782,1739502696.0455983,56.299946308135986,0.009,1739502696.0456007,56.299946308135986,-3.116836715828113,1739502696.045603,56.299946308135986,0.1981704630960128,1739502696.0456054,56.299946308135986,0.05015798974896722,1739502696.0456073,56.299946308135986,2.13347981238818,1739502696.0456097,56.299946308135986,0.0,1739502696.0456119,56.299946308135986,0.029294771231781258,1739502696.0456138,56.299946308135986,3.130363477406766,1739502696.0456161,56.299946308135986,2.104185041156399 +1739502696.066074,56.3199462890625,21.2755985583672,1739502696.0660777,56.3199462890625,0.145346752186839,1739502696.066082,56.3199462890625,91.35020061220109,1739502696.066086,56.3199462890625,15.769085385701782,1739502696.0660882,56.3199462890625,0.009,1739502696.0660908,56.3199462890625,-3.116836715828113,1739502696.066093,56.3199462890625,0.1981704630960128,1739502696.066095,56.3199462890625,0.05015798974896722,1739502696.0660968,56.3199462890625,2.13347981238818,1739502696.0660994,56.3199462890625,0.0,1739502696.0661016,56.3199462890625,0.029294771231781258,1739502696.0661037,56.3199462890625,3.130363477406766,1739502696.066106,56.3199462890625,2.104185041156399 +1739502696.08477,56.339946269989014,21.2755985583672,1739502696.0847723,56.339946269989014,0.145346752186839,1739502696.0847752,56.339946269989014,91.35020061220109,1739502696.084778,56.339946269989014,15.769085385701782,1739502696.0847793,56.339946269989014,0.009,1739502696.0847807,56.339946269989014,-3.116836715828113,1739502696.0847824,56.339946269989014,0.1981704630960128,1739502696.0847836,56.339946269989014,0.05015798974896722,1739502696.0847852,56.339946269989014,2.13347981238818,1739502696.0847867,56.339946269989014,0.0,1739502696.084788,56.339946269989014,0.029294771231781258,1739502696.0847895,56.339946269989014,3.130363477406766,1739502696.084791,56.339946269989014,2.104185041156399 +1739502696.1042087,56.35994625091553,21.2755985583672,1739502696.1042109,56.35994625091553,0.145346752186839,1739502696.1042135,56.35994625091553,91.35020061220109,1739502696.104216,56.35994625091553,15.769085385701782,1739502696.1042175,56.35994625091553,0.009,1739502696.1042192,56.35994625091553,-3.116836715828113,1739502696.1042204,56.35994625091553,0.1981704630960128,1739502696.1042216,56.35994625091553,0.05015798974896722,1739502696.104223,56.35994625091553,2.13347981238818,1739502696.1042242,56.35994625091553,0.0,1739502696.1042256,56.35994625091553,0.029294771231781258,1739502696.104227,56.35994625091553,3.130363477406766,1739502696.1042283,56.35994625091553,2.104185041156399 +1739502696.1243553,56.37994623184204,21.2755985583672,1739502696.1243582,56.37994623184204,0.145346752186839,1739502696.124361,56.37994623184204,91.35020061220109,1739502696.1243653,56.37994623184204,15.769085385701782,1739502696.124369,56.37994623184204,0.009,1739502696.1243734,56.37994623184204,-3.116836715828113,1739502696.1243753,56.37994623184204,0.1981704630960128,1739502696.124377,56.37994623184204,0.05015798974896722,1739502696.124379,56.37994623184204,2.13347981238818,1739502696.1243806,56.37994623184204,0.0,1739502696.1243827,56.37994623184204,0.029294771231781258,1739502696.1243849,56.37994623184204,3.130363477406766,1739502696.124389,56.37994623184204,2.104185041156399 +1739502696.1442392,56.399946212768555,21.043990299761077,1739502696.1442416,56.399946212768555,0.14784703440297164,1739502696.144245,56.399946212768555,91.47651271134418,1739502696.1442478,56.399946212768555,15.636342715720906,1739502696.1442492,56.399946212768555,0.009,1739502696.1442509,56.399946212768555,-3.1159222428927906,1739502696.1442523,56.399946212768555,0.19439693387211185,1739502696.1442537,56.399946212768555,0.05101592722616963,1739502696.144255,56.399946212768555,2.13993014242962,1739502696.1442568,56.399946212768555,0.0,1739502696.144258,56.399946212768555,0.034000292085118136,1739502696.1442597,56.399946212768555,3.1313186473866925,1739502696.144261,56.399946212768555,2.107400326575289 +1739502696.1643429,56.41994619369507,21.043990299761077,1739502696.164345,56.41994619369507,0.14784703440297164,1739502696.164348,56.41994619369507,91.47651271134418,1739502696.1643505,56.41994619369507,15.636342715720906,1739502696.164352,56.41994619369507,0.009,1739502696.1643534,56.41994619369507,-3.1159222428927906,1739502696.1643548,56.41994619369507,0.19439693387211185,1739502696.1643565,56.41994619369507,0.05101592722616963,1739502696.1643577,56.41994619369507,2.13993014242962,1739502696.164359,56.41994619369507,0.0,1739502696.1643605,56.41994619369507,0.03252981585433101,1739502696.1643617,56.41994619369507,3.1313186473866925,1739502696.1643631,56.41994619369507,2.107400326575289 +1739502696.1841242,56.43994617462158,21.043990299761077,1739502696.1841261,56.43994617462158,0.14784703440297164,1739502696.1841292,56.43994617462158,91.47651271134418,1739502696.1841319,56.43994617462158,15.636342715720906,1739502696.1841333,56.43994617462158,0.009,1739502696.1841352,56.43994617462158,-3.1159222428927906,1739502696.1841364,56.43994617462158,0.19439693387211185,1739502696.1841378,56.43994617462158,0.05101592722616963,1739502696.184139,56.43994617462158,2.13993014242962,1739502696.1841404,56.43994617462158,0.0,1739502696.1841419,56.43994617462158,0.03252981585433101,1739502696.184143,56.43994617462158,3.1313186473866925,1739502696.1841447,56.43994617462158,2.107400326575289 +1739502696.2040515,56.459946155548096,21.043990299761077,1739502696.2040534,56.459946155548096,0.14784703440297164,1739502696.204056,56.459946155548096,91.47651271134418,1739502696.2040591,56.459946155548096,15.636342715720906,1739502696.2040603,56.459946155548096,0.009,1739502696.204062,56.459946155548096,-3.1159222428927906,1739502696.2040632,56.459946155548096,0.19439693387211185,1739502696.2040646,56.459946155548096,0.05101592722616963,1739502696.2040658,56.459946155548096,2.13993014242962,1739502696.2040672,56.459946155548096,0.0,1739502696.204069,56.459946155548096,0.03252981585433101,1739502696.20407,56.459946155548096,3.1313186473866925,1739502696.2040715,56.459946155548096,2.107400326575289 +1739502696.224513,56.47994613647461,21.043990299761077,1739502696.224516,56.47994613647461,0.14784703440297164,1739502696.2245193,56.47994613647461,91.47651271134418,1739502696.2245219,56.47994613647461,15.636342715720906,1739502696.2245235,56.47994613647461,0.009,1739502696.224526,56.47994613647461,-3.1159222428927906,1739502696.2245271,56.47994613647461,0.19439693387211185,1739502696.2245286,56.47994613647461,0.05101592722616963,1739502696.22453,56.47994613647461,2.13993014242962,1739502696.2245314,56.47994613647461,0.0,1739502696.2245333,56.47994613647461,0.03252981585433101,1739502696.2245347,56.47994613647461,3.1313186473866925,1739502696.2245362,56.47994613647461,2.107400326575289 +1739502696.2443027,56.49994611740112,20.81201010841919,1739502696.2443051,56.49994611740112,0.15012972452527773,1739502696.244308,56.49994611740112,91.80068006073196,1739502696.2443109,56.49994611740112,15.305063313457232,1739502696.2443123,56.49994611740112,0.009,1739502696.244314,56.49994611740112,-3.11597068097556,1739502696.2443154,56.49994611740112,0.19244118918876196,1739502696.2443168,56.49994611740112,0.04869834512986396,1739502696.2443185,56.49994611740112,2.143280888626741,1739502696.24432,56.49994611740112,0.0,1739502696.2443213,56.49994611740112,0.03223122632413852,1739502696.2443228,56.49994611740112,3.132273817366619,1739502696.2443242,56.49994611740112,2.110956353013239 +1739502696.2670739,56.51994609832764,20.81201010841919,1739502696.2670777,56.51994609832764,0.15012972452527773,1739502696.2670825,56.51994609832764,91.80068006073196,1739502696.267088,56.51994609832764,15.305063313457232,1739502696.267091,56.51994609832764,0.009,1739502696.2670949,56.51994609832764,-3.11597068097556,1739502696.2670984,56.51994609832764,0.19244118918876196,1739502696.267102,56.51994609832764,0.04869834512986396,1739502696.2671053,56.51994609832764,2.143280888626741,1739502696.2671092,56.51994609832764,0.0,1739502696.2671127,56.51994609832764,0.032324535613502015,1739502696.2671165,56.51994609832764,3.132273817366619,1739502696.26712,56.51994609832764,2.110956353013239 +1739502696.2862265,56.53994607925415,20.81201010841919,1739502696.2862303,56.53994607925415,0.15012972452527773,1739502696.2862353,56.53994607925415,91.80068006073196,1739502696.2862406,56.53994607925415,15.305063313457232,1739502696.2862437,56.53994607925415,0.009,1739502696.2862475,56.53994607925415,-3.11597068097556,1739502696.2862508,56.53994607925415,0.19244118918876196,1739502696.2862544,56.53994607925415,0.04869834512986396,1739502696.2862577,56.53994607925415,2.143280888626741,1739502696.2862613,56.53994607925415,0.0,1739502696.2862647,56.53994607925415,0.032324535613502015,1739502696.2862682,56.53994607925415,3.132273817366619,1739502696.2862716,56.53994607925415,2.110956353013239 +1739502696.3055134,56.559946060180664,20.81201010841919,1739502696.3055186,56.559946060180664,0.15012972452527773,1739502696.3055239,56.559946060180664,91.80068006073196,1739502696.3055296,56.559946060180664,15.305063313457232,1739502696.3055334,56.559946060180664,0.009,1739502696.3055367,56.559946060180664,-3.11597068097556,1739502696.3055415,56.559946060180664,0.19244118918876196,1739502696.3055456,56.559946060180664,0.04869834512986396,1739502696.305549,56.559946060180664,2.143280888626741,1739502696.3055525,56.559946060180664,0.0,1739502696.3055558,56.559946060180664,0.032324535613502015,1739502696.3055594,56.559946060180664,3.132273817366619,1739502696.3055627,56.559946060180664,2.110956353013239 +1739502696.3268843,56.57994604110718,20.81201010841919,1739502696.326888,56.57994604110718,0.15012972452527773,1739502696.3268929,56.57994604110718,91.80068006073196,1739502696.326898,56.57994604110718,15.305063313457232,1739502696.326901,56.57994604110718,0.009,1739502696.3269048,56.57994604110718,-3.11597068097556,1739502696.3269083,56.57994604110718,0.19244118918876196,1739502696.3269117,56.57994604110718,0.04869834512986396,1739502696.326915,56.57994604110718,2.143280888626741,1739502696.3269186,56.57994604110718,0.0,1739502696.3269224,56.57994604110718,0.032324535613502015,1739502696.3269258,56.57994604110718,3.132273817366619,1739502696.3269293,56.57994604110718,2.110956353013239 +1739502696.3456395,56.59994602203369,20.81201010841919,1739502696.3456423,56.59994602203369,0.15012972452527773,1739502696.345645,56.59994602203369,91.80068006073196,1739502696.345648,56.59994602203369,15.305063313457232,1739502696.3456495,56.59994602203369,0.009,1739502696.3456516,56.59994602203369,-3.11597068097556,1739502696.345653,56.59994602203369,0.19244118918876196,1739502696.3456545,56.59994602203369,0.04869834512986396,1739502696.345656,56.59994602203369,2.143280888626741,1739502696.3456573,56.59994602203369,0.0,1739502696.3456585,56.59994602203369,0.032324535613502015,1739502696.34566,56.59994602203369,3.132273817366619,1739502696.3456612,56.59994602203369,2.110956353013239 +1739502696.3653789,56.619946002960205,20.57963697251532,1739502696.3653815,56.619946002960205,0.15219430628934116,1739502696.365384,56.619946002960205,91.86416252911172,1739502696.365387,56.619946002960205,15.234505854804958,1739502696.3653884,56.619946002960205,0.009,1739502696.36539,56.619946002960205,-3.1148093882827905,1739502696.3653917,56.619946002960205,0.18789366953770886,1739502696.365393,56.619946002960205,0.050466605893591254,1739502696.3653946,56.619946002960205,2.15109237874014,1739502696.3653963,56.619946002960205,0.0,1739502696.3653975,56.619946002960205,0.038541257432983325,1739502696.365399,56.619946002960205,3.1332289873465453,1739502696.3654003,56.619946002960205,2.1144938481494955 +1739502696.3867254,56.63994598388672,20.57963697251532,1739502696.3867302,56.63994598388672,0.15219430628934116,1739502696.3867364,56.63994598388672,91.86416252911172,1739502696.3867414,56.63994598388672,15.234505854804958,1739502696.3867443,56.63994598388672,0.009,1739502696.3867493,56.63994598388672,-3.1148093882827905,1739502696.3867526,56.63994598388672,0.18789366953770886,1739502696.3867555,56.63994598388672,0.050466605893591254,1739502696.3867586,56.63994598388672,2.15109237874014,1739502696.3867621,56.63994598388672,0.0,1739502696.386765,56.63994598388672,0.03659853059064444,1739502696.38677,56.63994598388672,3.1332289873465453,1739502696.3867726,56.63994598388672,2.1144938481494955 +1739502696.4054198,56.65994596481323,20.57963697251532,1739502696.4054224,56.65994596481323,0.15219430628934116,1739502696.405425,56.65994596481323,91.86416252911172,1739502696.4054275,56.65994596481323,15.234505854804958,1739502696.4054286,56.65994596481323,0.009,1739502696.4054303,56.65994596481323,-3.1148093882827905,1739502696.4054315,56.65994596481323,0.18789366953770886,1739502696.405433,56.65994596481323,0.050466605893591254,1739502696.405434,56.65994596481323,2.15109237874014,1739502696.4054353,56.65994596481323,0.0,1739502696.4054365,56.65994596481323,0.03659853059064444,1739502696.4054377,56.65994596481323,3.1332289873465453,1739502696.405439,56.65994596481323,2.1144938481494955 +1739502696.4243252,56.679945945739746,20.57963697251532,1739502696.4243274,56.679945945739746,0.15219430628934116,1739502696.4243305,56.679945945739746,91.86416252911172,1739502696.4243333,56.679945945739746,15.234505854804958,1739502696.4243345,56.679945945739746,0.009,1739502696.4243362,56.679945945739746,-3.1148093882827905,1739502696.4243376,56.679945945739746,0.18789366953770886,1739502696.4243393,56.679945945739746,0.050466605893591254,1739502696.4243402,56.679945945739746,2.15109237874014,1739502696.424342,56.679945945739746,0.0,1739502696.4243433,56.679945945739746,0.03659853059064444,1739502696.4243448,56.679945945739746,3.1332289873465453,1739502696.4243462,56.679945945739746,2.1144938481494955 +1739502696.444224,56.69994592666626,20.57963697251532,1739502696.444226,56.69994592666626,0.15219430628934116,1739502696.4442291,56.69994592666626,91.86416252911172,1739502696.444232,56.69994592666626,15.234505854804958,1739502696.4442332,56.69994592666626,0.009,1739502696.444235,56.69994592666626,-3.1148093882827905,1739502696.4442363,56.69994592666626,0.18789366953770886,1739502696.4442375,56.69994592666626,0.050466605893591254,1739502696.444239,56.69994592666626,2.15109237874014,1739502696.4442403,56.69994592666626,0.0,1739502696.4442415,56.69994592666626,0.03659853059064444,1739502696.444243,56.69994592666626,3.1332289873465453,1739502696.4442441,56.69994592666626,2.1144938481494955 +1739502696.4644048,56.71994590759277,20.346850530940756,1739502696.4644084,56.71994590759277,0.1540401896477741,1739502696.4644117,56.71994590759277,92.1493227839405,1739502696.4644148,56.71994590759277,14.941345044836725,1739502696.4644163,56.71994590759277,0.009,1739502696.464418,56.71994590759277,-3.1147671517602937,1739502696.4644194,56.71994590759277,0.185082510205166,1739502696.4644208,56.71994590759277,0.048607514111852074,1739502696.4644222,56.71994590759277,2.1559354733156386,1739502696.464424,56.71994590759277,0.0,1739502696.4644253,56.71994590759277,0.03782444660076693,1739502696.4644265,56.71994590759277,3.1341841573264717,1739502696.4644277,56.71994590759277,2.1184941257192142 +1739502696.4841373,56.73994588851929,20.346850530940756,1739502696.4841392,56.73994588851929,0.1540401896477741,1739502696.484142,56.73994588851929,92.1493227839405,1739502696.4841447,56.73994588851929,14.941345044836725,1739502696.484146,56.73994588851929,0.009,1739502696.4841478,56.73994588851929,-3.1147671517602937,1739502696.484149,56.73994588851929,0.185082510205166,1739502696.4841502,56.73994588851929,0.048607514111852074,1739502696.4841516,56.73994588851929,2.1559354733156386,1739502696.484153,56.73994588851929,0.0,1739502696.4841545,56.73994588851929,0.03744134759642437,1739502696.4841557,56.73994588851929,3.1341841573264717,1739502696.4841568,56.73994588851929,2.1184941257192142 +1739502696.5042121,56.7599458694458,20.346850530940756,1739502696.5042143,56.7599458694458,0.1540401896477741,1739502696.5042171,56.7599458694458,92.1493227839405,1739502696.5042195,56.7599458694458,14.941345044836725,1739502696.5042212,56.7599458694458,0.009,1739502696.5042226,56.7599458694458,-3.1147671517602937,1739502696.5042243,56.7599458694458,0.185082510205166,1739502696.5042255,56.7599458694458,0.048607514111852074,1739502696.5042264,56.7599458694458,2.1559354733156386,1739502696.504228,56.7599458694458,0.0,1739502696.5042293,56.7599458694458,0.03744134759642437,1739502696.5042307,56.7599458694458,3.1341841573264717,1739502696.504232,56.7599458694458,2.1184941257192142 +1739502696.5243313,56.779945850372314,20.346850530940756,1739502696.5243337,56.779945850372314,0.1540401896477741,1739502696.5243368,56.779945850372314,92.1493227839405,1739502696.5243394,56.779945850372314,14.941345044836725,1739502696.5243406,56.779945850372314,0.009,1739502696.5243425,56.779945850372314,-3.1147671517602937,1739502696.5243437,56.779945850372314,0.185082510205166,1739502696.5243454,56.779945850372314,0.048607514111852074,1739502696.5243464,56.779945850372314,2.1559354733156386,1739502696.524348,56.779945850372314,0.0,1739502696.5243492,56.779945850372314,0.03744134759642437,1739502696.5243506,56.779945850372314,3.1341841573264717,1739502696.524352,56.779945850372314,2.1184941257192142 +1739502696.5443463,56.79994583129883,20.346850530940756,1739502696.5443494,56.79994583129883,0.1540401896477741,1739502696.5443525,56.79994583129883,92.1493227839405,1739502696.5443556,56.79994583129883,14.941345044836725,1739502696.5443568,56.79994583129883,0.009,1739502696.5443587,56.79994583129883,-3.1147671517602937,1739502696.54436,56.79994583129883,0.185082510205166,1739502696.5443614,56.79994583129883,0.048607514111852074,1739502696.5443628,56.79994583129883,2.1559354733156386,1739502696.5443645,56.79994583129883,0.0,1739502696.544366,56.79994583129883,0.03744134759642437,1739502696.544367,56.79994583129883,3.1341841573264717,1739502696.5443687,56.79994583129883,2.1184941257192142 +1739502696.5643919,56.81994581222534,20.346850530940756,1739502696.5643947,56.81994581222534,0.1540401896477741,1739502696.5643978,56.81994581222534,92.1493227839405,1739502696.5644004,56.81994581222534,14.941345044836725,1739502696.5644019,56.81994581222534,0.009,1739502696.5644038,56.81994581222534,-3.1147671517602937,1739502696.564405,56.81994581222534,0.185082510205166,1739502696.5644062,56.81994581222534,0.048607514111852074,1739502696.5644076,56.81994581222534,2.1559354733156386,1739502696.5644093,56.81994581222534,0.0,1739502696.5644107,56.81994581222534,0.03744134759642437,1739502696.564412,56.81994581222534,3.1341841573264717,1739502696.5644135,56.81994581222534,2.1184941257192142 +1739502696.5842814,56.839945793151855,20.113615775453987,1739502696.5842838,56.839945793151855,0.15566683606806375,1739502696.5842867,56.839945793151855,92.9571393689625,1739502696.5842893,56.839945793151855,14.125314121847195,1739502696.5842907,56.839945793151855,0.009,1739502696.5842927,56.839945793151855,-3.1171053234363684,1739502696.5842938,56.839945793151855,0.1853079783048427,1739502696.5842955,56.839945793151855,0.039660871694944505,1739502696.5842965,56.839945793151855,2.1555466326458044,1739502696.5842981,56.839945793151855,0.0,1739502696.5842996,56.839945793151855,0.030901695242229143,1739502696.5843008,56.839945793151855,3.135139327306398,1739502696.5843022,56.839945793151855,2.1226012947029727 +1739502696.6042402,56.85994577407837,20.113615775453987,1739502696.6042423,56.85994577407837,0.15566683606806375,1739502696.6042454,56.85994577407837,92.9571393689625,1739502696.604248,56.85994577407837,14.125314121847195,1739502696.6042492,56.85994577407837,0.009,1739502696.6042511,56.85994577407837,-3.1171053234363684,1739502696.6042523,56.85994577407837,0.1853079783048427,1739502696.604254,56.85994577407837,0.039660871694944505,1739502696.6042552,56.85994577407837,2.1555466326458044,1739502696.6042569,56.85994577407837,0.0,1739502696.604258,56.85994577407837,0.03294533794283172,1739502696.6042593,56.85994577407837,3.135139327306398,1739502696.604261,56.85994577407837,2.1226012947029727 +1739502696.624243,56.87994575500488,20.113615775453987,1739502696.6242454,56.87994575500488,0.15566683606806375,1739502696.6242487,56.87994575500488,92.9571393689625,1739502696.6242514,56.87994575500488,14.125314121847195,1739502696.6242526,56.87994575500488,0.009,1739502696.6242545,56.87994575500488,-3.1171053234363684,1739502696.6242557,56.87994575500488,0.1853079783048427,1739502696.624257,56.87994575500488,0.039660871694944505,1739502696.624258,56.87994575500488,2.1555466326458044,1739502696.6242595,56.87994575500488,0.0,1739502696.624261,56.87994575500488,0.03294533794283172,1739502696.6242628,56.87994575500488,3.135139327306398,1739502696.6242642,56.87994575500488,2.1226012947029727 +1739502696.646124,56.8999457359314,20.113615775453987,1739502696.6461265,56.8999457359314,0.15566683606806375,1739502696.6461291,56.8999457359314,92.9571393689625,1739502696.646132,56.8999457359314,14.125314121847195,1739502696.6461334,56.8999457359314,0.009,1739502696.6461356,56.8999457359314,-3.1171053234363684,1739502696.6461368,56.8999457359314,0.1853079783048427,1739502696.6461382,56.8999457359314,0.039660871694944505,1739502696.6461394,56.8999457359314,2.1555466326458044,1739502696.6461408,56.8999457359314,0.0,1739502696.6461422,56.8999457359314,0.03294533794283172,1739502696.6461437,56.8999457359314,3.135139327306398,1739502696.6461453,56.8999457359314,2.1226012947029727 +1739502696.66429,56.91994571685791,20.113615775453987,1739502696.6642926,56.91994571685791,0.15566683606806375,1739502696.664296,56.91994571685791,92.9571393689625,1739502696.6642985,56.91994571685791,14.125314121847195,1739502696.6642997,56.91994571685791,0.009,1739502696.6643016,56.91994571685791,-3.1171053234363684,1739502696.6643033,56.91994571685791,0.1853079783048427,1739502696.6643047,56.91994571685791,0.039660871694944505,1739502696.6643057,56.91994571685791,2.1555466326458044,1739502696.664307,56.91994571685791,0.0,1739502696.6643085,56.91994571685791,0.03294533794283172,1739502696.66431,56.91994571685791,3.135139327306398,1739502696.6643114,56.91994571685791,2.1226012947029727 +1739502696.6842704,56.939945697784424,19.87995253967947,1739502696.6842732,56.939945697784424,0.15707327787066294,1739502696.6842763,56.939945697784424,92.98261006810372,1739502696.6842787,56.939945697784424,14.092628416036966,1739502696.6842802,56.939945697784424,0.00899685098336412,1739502696.6842818,56.939945697784424,-3.116011897589119,1739502696.684283,56.939945697784424,0.17989364103278757,1739502696.6842842,56.939945697784424,0.04122017831510667,1739502696.6842854,56.939945697784424,2.164903567837543,1739502696.684287,56.939945697784424,0.0,1739502696.6842883,56.939945697784424,0.04130814070526446,1739502696.6842892,56.939945697784424,3.1360944972863245,1739502696.6842906,56.939945697784424,2.1262088047090026 +1739502696.7049255,56.95994567871094,19.87995253967947,1739502696.704928,56.95994567871094,0.15707327787066294,1739502696.7049305,56.95994567871094,92.98261006810372,1739502696.704933,56.95994567871094,14.092628416036966,1739502696.7049341,56.95994567871094,0.00899685098336412,1739502696.7049358,56.95994567871094,-3.116011897589119,1739502696.704937,56.95994567871094,0.17989364103278757,1739502696.7049382,56.95994567871094,0.04122017831510667,1739502696.7049394,56.95994567871094,2.164903567837543,1739502696.7049408,56.95994567871094,0.0,1739502696.7049417,56.95994567871094,0.038694763128540366,1739502696.7049432,56.95994567871094,3.1360944972863245,1739502696.7049444,56.95994567871094,2.1262088047090026 +1739502696.7241893,56.97994565963745,19.87995253967947,1739502696.7241914,56.97994565963745,0.15707327787066294,1739502696.7241948,56.97994565963745,92.98261006810372,1739502696.7241974,56.97994565963745,14.092628416036966,1739502696.7241986,56.97994565963745,0.00899685098336412,1739502696.7242005,56.97994565963745,-3.116011897589119,1739502696.7242017,56.97994565963745,0.17989364103278757,1739502696.724203,56.97994565963745,0.04122017831510667,1739502696.7242043,56.97994565963745,2.164903567837543,1739502696.7242057,56.97994565963745,0.0,1739502696.7242072,56.97994565963745,0.038694763128540366,1739502696.7242088,56.97994565963745,3.1360944972863245,1739502696.7242103,56.97994565963745,2.1262088047090026 +1739502696.744386,56.999945640563965,19.87995253967947,1739502696.7443886,56.999945640563965,0.15707327787066294,1739502696.7443917,56.999945640563965,92.98261006810372,1739502696.7443948,56.999945640563965,14.092628416036966,1739502696.744396,56.999945640563965,0.00899685098336412,1739502696.7443976,56.999945640563965,-3.116011897589119,1739502696.7443988,56.999945640563965,0.17989364103278757,1739502696.7444,56.999945640563965,0.04122017831510667,1739502696.7444015,56.999945640563965,2.164903567837543,1739502696.744403,56.999945640563965,0.0,1739502696.7444043,56.999945640563965,0.038694763128540366,1739502696.7444055,56.999945640563965,3.1360944972863245,1739502696.744407,56.999945640563965,2.1262088047090026 +1739502696.7644088,57.01994562149048,19.87995253967947,1739502696.7644122,57.01994562149048,0.15707327787066294,1739502696.7644153,57.01994562149048,92.98261006810372,1739502696.764418,57.01994562149048,14.092628416036966,1739502696.7644193,57.01994562149048,0.00899685098336412,1739502696.7644212,57.01994562149048,-3.116011897589119,1739502696.7644227,57.01994562149048,0.17989364103278757,1739502696.7644238,57.01994562149048,0.04122017831510667,1739502696.7644253,57.01994562149048,2.164903567837543,1739502696.7644267,57.01994562149048,0.0,1739502696.7644281,57.01994562149048,0.038694763128540366,1739502696.7644293,57.01994562149048,3.1360944972863245,1739502696.7644305,57.01994562149048,2.1262088047090026 +1739502696.7842705,57.03994560241699,19.87995253967947,1739502696.784273,57.03994560241699,0.15707327787066294,1739502696.7842755,57.03994560241699,92.98261006810372,1739502696.7842782,57.03994560241699,14.092628416036966,1739502696.7842796,57.03994560241699,0.00899685098336412,1739502696.784281,57.03994560241699,-3.116011897589119,1739502696.7842827,57.03994560241699,0.17989364103278757,1739502696.7842839,57.03994560241699,0.04122017831510667,1739502696.7842848,57.03994560241699,2.164903567837543,1739502696.7842867,57.03994560241699,0.0,1739502696.784288,57.03994560241699,0.038694763128540366,1739502696.7842894,57.03994560241699,3.1360944972863245,1739502696.7842906,57.03994560241699,2.1262088047090026 +1739502696.8042376,57.059945583343506,19.645855404118304,1739502696.80424,57.059945583343506,0.1582587159995823,1739502696.8042426,57.059945583343506,93.00812784131803,1739502696.8042452,57.059945583343506,14.058534684289473,1739502696.8042464,57.059945583343506,0.008707921053300616,1739502696.804248,57.059945583343506,-3.1148329410457762,1739502696.8042493,57.059945583343506,0.1749322859830654,1739502696.8042507,57.059945583343506,0.04300146155955674,1739502696.804252,57.059945583343506,2.173513327162557,1739502696.8042533,57.059945583343506,0.0,1739502696.8042545,57.059945583343506,0.04498010017223328,1739502696.8042557,57.059945583343506,3.137049667266251,1739502696.804257,57.059945583343506,2.1304973961042872 +1739502696.8243546,57.07994556427002,19.645855404118304,1739502696.824357,57.07994556427002,0.1582587159995823,1739502696.82436,57.07994556427002,93.00812784131803,1739502696.8243625,57.07994556427002,14.058534684289473,1739502696.8243637,57.07994556427002,0.008707921053300616,1739502696.8243656,57.07994556427002,-3.1148329410457762,1739502696.824367,57.07994556427002,0.1749322859830654,1739502696.8243685,57.07994556427002,0.04300146155955674,1739502696.8243694,57.07994556427002,2.173513327162557,1739502696.8243709,57.07994556427002,0.0,1739502696.8243723,57.07994556427002,0.04301593105826962,1739502696.8243737,57.07994556427002,3.137049667266251,1739502696.8243752,57.07994556427002,2.1304973961042872 +1739502696.8444397,57.09994554519653,19.645855404118304,1739502696.8444424,57.09994554519653,0.1582587159995823,1739502696.8444455,57.09994554519653,93.00812784131803,1739502696.8444483,57.09994554519653,14.058534684289473,1739502696.8444498,57.09994554519653,0.008707921053300616,1739502696.8444514,57.09994554519653,-3.1148329410457762,1739502696.8444526,57.09994554519653,0.1749322859830654,1739502696.844454,57.09994554519653,0.04300146155955674,1739502696.8444555,57.09994554519653,2.173513327162557,1739502696.844457,57.09994554519653,0.0,1739502696.8444583,57.09994554519653,0.04301593105826962,1739502696.8444598,57.09994554519653,3.137049667266251,1739502696.844461,57.09994554519653,2.1304973961042872 +1739502696.8643975,57.11994552612305,19.645855404118304,1739502696.8644006,57.11994552612305,0.1582587159995823,1739502696.8644037,57.11994552612305,93.00812784131803,1739502696.8644066,57.11994552612305,14.058534684289473,1739502696.8644078,57.11994552612305,0.008707921053300616,1739502696.8644097,57.11994552612305,-3.1148329410457762,1739502696.8644109,57.11994552612305,0.1749322859830654,1739502696.864412,57.11994552612305,0.04300146155955674,1739502696.8644135,57.11994552612305,2.173513327162557,1739502696.8644152,57.11994552612305,0.0,1739502696.8644166,57.11994552612305,0.04301593105826962,1739502696.864418,57.11994552612305,3.137049667266251,1739502696.8644197,57.11994552612305,2.1304973961042872 +1739502696.8841755,57.13994550704956,19.645855404118304,1739502696.8841777,57.13994550704956,0.1582587159995823,1739502696.8841805,57.13994550704956,93.00812784131803,1739502696.8841834,57.13994550704956,14.058534684289473,1739502696.8841846,57.13994550704956,0.008707921053300616,1739502696.884186,57.13994550704956,-3.1148329410457762,1739502696.8841877,57.13994550704956,0.1749322859830654,1739502696.884189,57.13994550704956,0.04300146155955674,1739502696.8841903,57.13994550704956,2.173513327162557,1739502696.884192,57.13994550704956,0.0,1739502696.8841932,57.13994550704956,0.04301593105826962,1739502696.8841949,57.13994550704956,3.137049667266251,1739502696.884196,57.13994550704956,2.1304973961042872 +1739502696.9042127,57.159945487976074,19.411268119123843,1739502696.904215,57.159945487976074,0.15922255684691056,1739502696.904218,57.159945487976074,93.03369881922326,1739502696.9042203,57.159945487976074,14.023560712964322,1739502696.9042218,57.159945487976074,0.008411531465799347,1739502696.9042232,57.159945487976074,-3.113608272856083,1739502696.9042249,57.159945487976074,0.1701401179458365,1739502696.904226,57.159945487976074,0.04497666542928524,1739502696.9042275,57.159945487976074,2.181861993097123,1739502696.9042292,57.159945487976074,0.0,1739502696.9042304,57.159945487976074,0.048319992699861175,1739502696.9042318,57.159945487976074,3.1380048372461773,1739502696.9042332,57.159945487976074,2.135199520747014 +1739502696.9243674,57.17994546890259,19.411268119123843,1739502696.9243698,57.17994546890259,0.15922255684691056,1739502696.9243731,57.17994546890259,93.03369881922326,1739502696.924376,57.17994546890259,14.023560712964322,1739502696.9243774,57.17994546890259,0.008411531465799347,1739502696.9243789,57.17994546890259,-3.113608272856083,1739502696.9243803,57.17994546890259,0.1701401179458365,1739502696.9243822,57.17994546890259,0.04497666542928524,1739502696.9243832,57.17994546890259,2.181861993097123,1739502696.924385,57.17994546890259,0.0,1739502696.924386,57.17994546890259,0.046662472350108786,1739502696.9243877,57.17994546890259,3.1380048372461773,1739502696.924389,57.17994546890259,2.135199520747014 +1739502696.9442637,57.1999454498291,19.411268119123843,1739502696.944266,57.1999454498291,0.15922255684691056,1739502696.9442687,57.1999454498291,93.03369881922326,1739502696.9442713,57.1999454498291,14.023560712964322,1739502696.9442728,57.1999454498291,0.008411531465799347,1739502696.9442744,57.1999454498291,-3.113608272856083,1739502696.9442756,57.1999454498291,0.1701401179458365,1739502696.944277,57.1999454498291,0.04497666542928524,1739502696.9442782,57.1999454498291,2.181861993097123,1739502696.94428,57.1999454498291,0.0,1739502696.944281,57.1999454498291,0.046662472350108786,1739502696.9442825,57.1999454498291,3.1380048372461773,1739502696.944284,57.1999454498291,2.135199520747014 +1739502696.9643657,57.219945430755615,19.411268119123843,1739502696.9643686,57.219945430755615,0.15922255684691056,1739502696.9643722,57.219945430755615,93.03369881922326,1739502696.9643753,57.219945430755615,14.023560712964322,1739502696.9643767,57.219945430755615,0.008411531465799347,1739502696.9643784,57.219945430755615,-3.113608272856083,1739502696.9643798,57.219945430755615,0.1701401179458365,1739502696.9643815,57.219945430755615,0.04497666542928524,1739502696.9643826,57.219945430755615,2.181861993097123,1739502696.9643846,57.219945430755615,0.0,1739502696.964386,57.219945430755615,0.046662472350108786,1739502696.9643874,57.219945430755615,3.1380048372461773,1739502696.9643888,57.219945430755615,2.135199520747014 +1739502696.9841883,57.23994541168213,19.411268119123843,1739502696.9841905,57.23994541168213,0.15922255684691056,1739502696.9841933,57.23994541168213,93.03369881922326,1739502696.9841962,57.23994541168213,14.023560712964322,1739502696.9841974,57.23994541168213,0.008411531465799347,1739502696.9841993,57.23994541168213,-3.113608272856083,1739502696.9842005,57.23994541168213,0.1701401179458365,1739502696.9842017,57.23994541168213,0.04497666542928524,1739502696.984203,57.23994541168213,2.181861993097123,1739502696.9842045,57.23994541168213,0.0,1739502696.9842057,57.23994541168213,0.046662472350108786,1739502696.9842074,57.23994541168213,3.1380048372461773,1739502696.9842086,57.23994541168213,2.135199520747014 +1739502697.0042627,57.25994539260864,19.411268119123843,1739502697.0042653,57.25994539260864,0.15922255684691056,1739502697.004268,57.25994539260864,93.03369881922326,1739502697.0042708,57.25994539260864,14.023560712964322,1739502697.0042722,57.25994539260864,0.008411531465799347,1739502697.004274,57.25994539260864,-3.113608272856083,1739502697.004275,57.25994539260864,0.1701401179458365,1739502697.0042765,57.25994539260864,0.04497666542928524,1739502697.0042777,57.25994539260864,2.181861993097123,1739502697.0042794,57.25994539260864,0.0,1739502697.0042806,57.25994539260864,0.046662472350108786,1739502697.004282,57.25994539260864,3.1380048372461773,1739502697.0042837,57.25994539260864,2.135199520747014 +1739502697.0244598,57.279945373535156,19.176138281961148,1739502697.0244627,57.279945373535156,0.15996403150200322,1739502697.0244656,57.279945373535156,93.35248170708678,1739502697.0244684,57.279945373535156,13.694495574359227,1739502697.0244699,57.279945373535156,0.008,1739502697.0244715,57.279945373535156,-3.1138773996107547,1739502697.0244732,57.279945373535156,0.16639471495526992,1739502697.0244744,57.279945373535156,0.04249292369993626,1739502697.0244756,57.279945373535156,2.188409359155557,1739502697.0244772,57.279945373535156,0.0,1739502697.0244784,57.279945373535156,0.04870664578055196,1739502697.02448,57.279945373535156,3.1389600072261037,1739502697.0244813,57.279945373535156,2.1403415179908514 +1739502697.0443654,57.29994535446167,19.176138281961148,1739502697.044368,57.29994535446167,0.15996403150200322,1739502697.0443711,57.29994535446167,93.35248170708678,1739502697.044374,57.29994535446167,13.694495574359227,1739502697.044376,57.29994535446167,0.008,1739502697.0443776,57.29994535446167,-3.1138773996107547,1739502697.0443792,57.29994535446167,0.16639471495526992,1739502697.0443807,57.29994535446167,0.04249292369993626,1739502697.0443816,57.29994535446167,2.188409359155557,1739502697.0443838,57.29994535446167,0.0,1739502697.0443852,57.29994535446167,0.04806784116470553,1739502697.0443866,57.29994535446167,3.1389600072261037,1739502697.044388,57.29994535446167,2.1403415179908514 +1739502697.0643742,57.319945335388184,19.176138281961148,1739502697.0643768,57.319945335388184,0.15996403150200322,1739502697.0643802,57.319945335388184,93.35248170708678,1739502697.064383,57.319945335388184,13.694495574359227,1739502697.0643842,57.319945335388184,0.008,1739502697.064386,57.319945335388184,-3.1138773996107547,1739502697.064387,57.319945335388184,0.16639471495526992,1739502697.0643885,57.319945335388184,0.04249292369993626,1739502697.06439,57.319945335388184,2.188409359155557,1739502697.0643914,57.319945335388184,0.0,1739502697.0643926,57.319945335388184,0.04806784116470553,1739502697.0643942,57.319945335388184,3.1389600072261037,1739502697.0643954,57.319945335388184,2.1403415179908514 +1739502697.0843306,57.3399453163147,19.176138281961148,1739502697.084333,57.3399453163147,0.15996403150200322,1739502697.0843358,57.3399453163147,93.35248170708678,1739502697.0843382,57.3399453163147,13.694495574359227,1739502697.0843394,57.3399453163147,0.008,1739502697.084341,57.3399453163147,-3.1138773996107547,1739502697.0843422,57.3399453163147,0.16639471495526992,1739502697.0843434,57.3399453163147,0.04249292369993626,1739502697.0843446,57.3399453163147,2.188409359155557,1739502697.084346,57.3399453163147,0.0,1739502697.0843475,57.3399453163147,0.04806784116470553,1739502697.0843487,57.3399453163147,3.1389600072261037,1739502697.0843499,57.3399453163147,2.1403415179908514 +1739502697.1041803,57.35994529724121,19.176138281961148,1739502697.1041822,57.35994529724121,0.15996403150200322,1739502697.104185,57.35994529724121,93.35248170708678,1739502697.1041877,57.35994529724121,13.694495574359227,1739502697.104189,57.35994529724121,0.008,1739502697.1041903,57.35994529724121,-3.1138773996107547,1739502697.104192,57.35994529724121,0.16639471495526992,1739502697.1041932,57.35994529724121,0.04249292369993626,1739502697.1041946,57.35994529724121,2.188409359155557,1739502697.1041958,57.35994529724121,0.0,1739502697.104197,57.35994529724121,0.04806784116470553,1739502697.1041987,57.35994529724121,3.1389600072261037,1739502697.1042,57.35994529724121,2.1403415179908514 +1739502697.1244743,57.379945278167725,18.94043844743375,1739502697.1244776,57.379945278167725,0.16048216752555966,1739502697.1244805,57.379945278167725,93.67389625679455,1739502697.1244833,57.379945278167725,13.362571272581635,1739502697.1244848,57.379945278167725,0.007,1739502697.1244864,57.379945278167725,-3.1140833128009717,1739502697.1244879,57.379945278167725,0.1628386876511877,1739502697.1244893,57.379945278167725,0.0401631557998839,1739502697.1244905,57.379945278167725,2.194643857716679,1739502697.1244926,57.379945278167725,0.0,1739502697.124494,57.379945278167725,0.04948963913476089,1739502697.1244953,57.379945278167725,3.13991517720603,1739502697.1244967,57.379945278167725,2.1455985307388743 +1739502697.144362,57.39994525909424,18.94043844743375,1739502697.1443646,57.39994525909424,0.16048216752555966,1739502697.1443675,57.39994525909424,93.67389625679455,1739502697.1443698,57.39994525909424,13.362571272581635,1739502697.1443715,57.39994525909424,0.007,1739502697.144373,57.39994525909424,-3.1140833128009717,1739502697.1443744,57.39994525909424,0.1628386876511877,1739502697.1443758,57.39994525909424,0.0401631557998839,1739502697.1443768,57.39994525909424,2.194643857716679,1739502697.1443787,57.39994525909424,0.0,1739502697.1443799,57.39994525909424,0.04904532697780484,1739502697.1443813,57.39994525909424,3.13991517720603,1739502697.1443825,57.39994525909424,2.1455985307388743 +1739502697.1642957,57.41994524002075,18.94043844743375,1739502697.1642983,57.41994524002075,0.16048216752555966,1739502697.1643014,57.41994524002075,93.67389625679455,1739502697.164304,57.41994524002075,13.362571272581635,1739502697.1643054,57.41994524002075,0.007,1739502697.1643069,57.41994524002075,-3.1140833128009717,1739502697.1643083,57.41994524002075,0.1628386876511877,1739502697.1643097,57.41994524002075,0.0401631557998839,1739502697.164311,57.41994524002075,2.194643857716679,1739502697.1643138,57.41994524002075,0.0,1739502697.1643155,57.41994524002075,0.04904532697780484,1739502697.164317,57.41994524002075,3.13991517720603,1739502697.1643186,57.41994524002075,2.1455985307388743 +1739502697.1842248,57.439945220947266,18.94043844743375,1739502697.184227,57.439945220947266,0.16048216752555966,1739502697.18423,57.439945220947266,93.67389625679455,1739502697.1842327,57.439945220947266,13.362571272581635,1739502697.184234,57.439945220947266,0.007,1739502697.1842358,57.439945220947266,-3.1140833128009717,1739502697.184237,57.439945220947266,0.1628386876511877,1739502697.1842384,57.439945220947266,0.0401631557998839,1739502697.1842396,57.439945220947266,2.194643857716679,1739502697.184241,57.439945220947266,0.0,1739502697.1842425,57.439945220947266,0.04904532697780484,1739502697.1842437,57.439945220947266,3.13991517720603,1739502697.184245,57.439945220947266,2.1455985307388743 +1739502697.2041137,57.45994520187378,18.94043844743375,1739502697.2041159,57.45994520187378,0.16048216752555966,1739502697.2041185,57.45994520187378,93.67389625679455,1739502697.204121,57.45994520187378,13.362571272581635,1739502697.2041223,57.45994520187378,0.007,1739502697.204124,57.45994520187378,-3.1140833128009717,1739502697.2041252,57.45994520187378,0.1628386876511877,1739502697.2041268,57.45994520187378,0.0401631557998839,1739502697.204128,57.45994520187378,2.194643857716679,1739502697.2041292,57.45994520187378,0.0,1739502697.2041306,57.45994520187378,0.04904532697780484,1739502697.2041318,57.45994520187378,3.13991517720603,1739502697.204133,57.45994520187378,2.1455985307388743 +1739502697.2243366,57.47994518280029,18.94043844743375,1739502697.2243397,57.47994518280029,0.16048216752555966,1739502697.2243433,57.47994518280029,93.67389625679455,1739502697.224346,57.47994518280029,13.362571272581635,1739502697.2243474,57.47994518280029,0.007,1739502697.2243493,57.47994518280029,-3.1140833128009717,1739502697.2243505,57.47994518280029,0.1628386876511877,1739502697.224352,57.47994518280029,0.0401631557998839,1739502697.2243533,57.47994518280029,2.194643857716679,1739502697.2243547,57.47994518280029,0.0,1739502697.2243562,57.47994518280029,0.04904532697780484,1739502697.2243574,57.47994518280029,3.13991517720603,1739502697.2243588,57.47994518280029,2.1455985307388743 +1739502697.2442377,57.49994516372681,18.70415296106543,1739502697.2442398,57.49994516372681,0.1607758966578281,1739502697.2442431,57.49994516372681,94.08523246317583,1739502697.2442458,57.49994516372681,12.940481756336604,1739502697.244248,57.49994516372681,0.006,1739502697.2442493,57.49994516372681,-3.1147454058564668,1739502697.2442508,57.49994516372681,0.15893899254126195,1739502697.2442522,57.49994516372681,0.03671626782049933,1739502697.2442534,57.49994516372681,2.2015013024682695,1739502697.2442548,57.49994516372681,0.0,1739502697.244256,57.49994516372681,0.05119609577384467,1739502697.2442575,57.49994516372681,3.1408703471859565,1739502697.2442589,57.49994516372681,2.1509773223838606 +1739502697.264423,57.51994514465332,18.70415296106543,1739502697.2644258,57.51994514465332,0.1607758966578281,1739502697.2644293,57.51994514465332,94.08523246317583,1739502697.264432,57.51994514465332,12.940481756336604,1739502697.2644331,57.51994514465332,0.006,1739502697.2644346,57.51994514465332,-3.1147454058564668,1739502697.2644362,57.51994514465332,0.15893899254126195,1739502697.2644374,57.51994514465332,0.03671626782049933,1739502697.2644389,57.51994514465332,2.2015013024682695,1739502697.2644403,57.51994514465332,0.0,1739502697.2644415,57.51994514465332,0.05052398008440884,1739502697.2644432,57.51994514465332,3.1408703471859565,1739502697.2644444,57.51994514465332,2.1509773223838606 +1739502697.28437,57.539945125579834,18.70415296106543,1739502697.2843726,57.539945125579834,0.1607758966578281,1739502697.2843752,57.539945125579834,94.08523246317583,1739502697.2843778,57.539945125579834,12.940481756336604,1739502697.2843792,57.539945125579834,0.006,1739502697.2843812,57.539945125579834,-3.1147454058564668,1739502697.2843826,57.539945125579834,0.15893899254126195,1739502697.2843838,57.539945125579834,0.03671626782049933,1739502697.284385,57.539945125579834,2.2015013024682695,1739502697.2843866,57.539945125579834,0.0,1739502697.2843878,57.539945125579834,0.05052398008440884,1739502697.284389,57.539945125579834,3.1408703471859565,1739502697.2843907,57.539945125579834,2.1509773223838606 +1739502697.304103,57.55994510650635,18.70415296106543,1739502697.3041053,57.55994510650635,0.1607758966578281,1739502697.3041077,57.55994510650635,94.08523246317583,1739502697.3041103,57.55994510650635,12.940481756336604,1739502697.304112,57.55994510650635,0.006,1739502697.3041134,57.55994510650635,-3.1147454058564668,1739502697.3041146,57.55994510650635,0.15893899254126195,1739502697.304116,57.55994510650635,0.03671626782049933,1739502697.3041172,57.55994510650635,2.2015013024682695,1739502697.3041189,57.55994510650635,0.0,1739502697.3041198,57.55994510650635,0.05052398008440884,1739502697.3041213,57.55994510650635,3.1408703471859565,1739502697.3041227,57.55994510650635,2.1509773223838606 +1739502697.3242683,57.57994508743286,18.70415296106543,1739502697.324271,57.57994508743286,0.1607758966578281,1739502697.3242736,57.57994508743286,94.08523246317583,1739502697.3242762,57.57994508743286,12.940481756336604,1739502697.3242774,57.57994508743286,0.006,1739502697.3242793,57.57994508743286,-3.1147454058564668,1739502697.3242805,57.57994508743286,0.15893899254126195,1739502697.324282,57.57994508743286,0.03671626782049933,1739502697.324283,57.57994508743286,2.2015013024682695,1739502697.3242843,57.57994508743286,0.0,1739502697.324286,57.57994508743286,0.05052398008440884,1739502697.3242872,57.57994508743286,3.1408703471859565,1739502697.3242886,57.57994508743286,2.1509773223838606 +1739502697.3441374,57.599945068359375,18.467269198514625,1739502697.3441398,57.599945068359375,0.16084410383332415,1739502697.3441424,57.599945068359375,94.12218639834093,1739502697.3441448,57.599945068359375,12.892476652418473,1739502697.3441463,57.599945068359375,0.006,1739502697.3441477,57.599945068359375,-3.113824032497421,1739502697.3441489,57.599945068359375,0.1535459335185706,1739502697.3441503,57.599945068359375,0.037912643836378934,1739502697.3441515,57.599945068359375,2.211020083011009,1739502697.3441532,57.599945068359375,0.0,1739502697.3441544,57.599945068359375,0.05633226714810977,1739502697.3441556,57.599945068359375,3.141825517165883,1739502697.344157,57.599945068359375,2.1565029067603723 +1739502697.3643231,57.61994504928589,18.467269198514625,1739502697.3643253,57.61994504928589,0.16084410383332415,1739502697.3643281,57.61994504928589,94.12218639834093,1739502697.364331,57.61994504928589,12.892476652418473,1739502697.3643322,57.61994504928589,0.006,1739502697.3643339,57.61994504928589,-3.113824032497421,1739502697.3643353,57.61994504928589,0.1535459335185706,1739502697.3643367,57.61994504928589,0.037912643836378934,1739502697.364338,57.61994504928589,2.211020083011009,1739502697.3643394,57.61994504928589,0.0,1739502697.3643408,57.61994504928589,0.0545171762506369,1739502697.3643422,57.61994504928589,3.141825517165883,1739502697.3643436,57.61994504928589,2.1565029067603723 +1739502697.3844004,57.6399450302124,18.467269198514625,1739502697.384403,57.6399450302124,0.16084410383332415,1739502697.3844068,57.6399450302124,94.12218639834093,1739502697.3844097,57.6399450302124,12.892476652418473,1739502697.3844109,57.6399450302124,0.006,1739502697.3844128,57.6399450302124,-3.113824032497421,1739502697.3844144,57.6399450302124,0.1535459335185706,1739502697.3844156,57.6399450302124,0.037912643836378934,1739502697.3844173,57.6399450302124,2.211020083011009,1739502697.3844187,57.6399450302124,0.0,1739502697.3844202,57.6399450302124,0.0545171762506369,1739502697.3844216,57.6399450302124,3.141825517165883,1739502697.3844235,57.6399450302124,2.1565029067603723 +1739502697.404163,57.659945011138916,18.467269198514625,1739502697.4041653,57.659945011138916,0.16084410383332415,1739502697.4041681,57.659945011138916,94.12218639834093,1739502697.404171,57.659945011138916,12.892476652418473,1739502697.4041727,57.659945011138916,0.006,1739502697.404174,57.659945011138916,-3.113824032497421,1739502697.4041753,57.659945011138916,0.1535459335185706,1739502697.4041767,57.659945011138916,0.037912643836378934,1739502697.404178,57.659945011138916,2.211020083011009,1739502697.4041796,57.659945011138916,0.0,1739502697.4041808,57.659945011138916,0.0545171762506369,1739502697.404182,57.659945011138916,3.141825517165883,1739502697.4041834,57.659945011138916,2.1565029067603723 +1739502697.4243622,57.67994499206543,18.467269198514625,1739502697.424365,57.67994499206543,0.16084410383332415,1739502697.4243689,57.67994499206543,94.12218639834093,1739502697.4243717,57.67994499206543,12.892476652418473,1739502697.424373,57.67994499206543,0.006,1739502697.4243748,57.67994499206543,-3.113824032497421,1739502697.4243762,57.67994499206543,0.1535459335185706,1739502697.4243777,57.67994499206543,0.037912643836378934,1739502697.4243789,57.67994499206543,2.211020083011009,1739502697.4243803,57.67994499206543,0.0,1739502697.424382,57.67994499206543,0.0545171762506369,1739502697.4243832,57.67994499206543,3.141825517165883,1739502697.4243848,57.67994499206543,2.1565029067603723 +1739502697.4442022,57.69994497299194,18.467269198514625,1739502697.4442046,57.69994497299194,0.16084410383332415,1739502697.4442074,57.69994497299194,94.12218639834093,1739502697.4442103,57.69994497299194,12.892476652418473,1739502697.4442115,57.69994497299194,0.006,1739502697.4442132,57.69994497299194,-3.113824032497421,1739502697.4442146,57.69994497299194,0.1535459335185706,1739502697.444216,57.69994497299194,0.037912643836378934,1739502697.4442174,57.69994497299194,2.211020083011009,1739502697.4442189,57.69994497299194,0.0,1739502697.4442198,57.69994497299194,0.0545171762506369,1739502697.4442215,57.69994497299194,3.141825517165883,1739502697.4442227,57.69994497299194,2.1565029067603723 +1739502697.46445,57.71994495391846,18.22975149754553,1739502697.4644532,57.71994495391846,0.16068561988930607,1739502697.4644566,57.71994495391846,94.5487055206979,1739502697.464459,57.71994495391846,12.453951741111077,1739502697.4644606,57.71994495391846,0.005,1739502697.4644625,57.71994495391846,-3.114644362826468,1739502697.464464,57.71994495391846,0.1488236677108165,1739502697.4644651,57.71994495391846,0.03423534326848249,1739502697.4644666,57.71994495391846,2.219388700222603,1739502697.4644682,57.71994495391846,0.0,1739502697.4644694,57.71994495391846,0.057955146919382125,1739502697.464471,57.71994495391846,3.1427806871458093,1739502697.4644725,57.71994495391846,2.1625079198416133 +1739502697.484371,57.73994493484497,18.22975149754553,1739502697.4843736,57.73994493484497,0.16068561988930607,1739502697.4843764,57.73994493484497,94.5487055206979,1739502697.4843788,57.73994493484497,12.453951741111077,1739502697.4843802,57.73994493484497,0.005,1739502697.484382,57.73994493484497,-3.114644362826468,1739502697.4843836,57.73994493484497,0.1488236677108165,1739502697.4843848,57.73994493484497,0.03423534326848249,1739502697.484386,57.73994493484497,2.219388700222603,1739502697.4843876,57.73994493484497,0.0,1739502697.4843888,57.73994493484497,0.05688078038098965,1739502697.4843903,57.73994493484497,3.1427806871458093,1739502697.4843917,57.73994493484497,2.1625079198416133 +1739502697.5043032,57.759944915771484,18.22975149754553,1739502697.5043054,57.759944915771484,0.16068561988930607,1739502697.5043082,57.759944915771484,94.5487055206979,1739502697.504311,57.759944915771484,12.453951741111077,1739502697.5043123,57.759944915771484,0.005,1739502697.5043142,57.759944915771484,-3.114644362826468,1739502697.5043154,57.759944915771484,0.1488236677108165,1739502697.504317,57.759944915771484,0.03423534326848249,1739502697.504318,57.759944915771484,2.219388700222603,1739502697.5043194,57.759944915771484,0.0,1739502697.5043209,57.759944915771484,0.05688078038098965,1739502697.504322,57.759944915771484,3.1427806871458093,1739502697.5043235,57.759944915771484,2.1625079198416133 +1739502697.5243983,57.779944896698,18.22975149754553,1739502697.5244012,57.779944896698,0.16068561988930607,1739502697.5244043,57.779944896698,94.5487055206979,1739502697.5244071,57.779944896698,12.453951741111077,1739502697.5244086,57.779944896698,0.005,1739502697.5244105,57.779944896698,-3.114644362826468,1739502697.5244117,57.779944896698,0.1488236677108165,1739502697.524413,57.779944896698,0.03423534326848249,1739502697.5244143,57.779944896698,2.219388700222603,1739502697.524416,57.779944896698,0.0,1739502697.5244172,57.779944896698,0.05688078038098965,1739502697.5244188,57.779944896698,3.1427806871458093,1739502697.5244203,57.779944896698,2.1625079198416133 +1739502697.5442863,57.79994487762451,18.22975149754553,1739502697.5442889,57.79994487762451,0.16068561988930607,1739502697.5442915,57.79994487762451,94.5487055206979,1739502697.5442946,57.79994487762451,12.453951741111077,1739502697.544296,57.79994487762451,0.005,1739502697.5442977,57.79994487762451,-3.114644362826468,1739502697.5442991,57.79994487762451,0.1488236677108165,1739502697.5443006,57.79994487762451,0.03423534326848249,1739502697.5443017,57.79994487762451,2.219388700222603,1739502697.5443034,57.79994487762451,0.0,1739502697.5443044,57.79994487762451,0.05688078038098965,1739502697.5443058,57.79994487762451,3.1427806871458093,1739502697.5443072,57.79994487762451,2.1625079198416133 +1739502697.564456,57.819944858551025,17.99156506930546,1739502697.564459,57.819944858551025,0.16029917894149115,1739502697.5644622,57.819944858551025,94.57562020064807,1739502697.564465,57.819944858551025,12.414596782833021,1739502697.564467,57.819944858551025,0.005,1739502697.5644686,57.819944858551025,-3.113753324320556,1739502697.56447,57.819944858551025,0.14334625327103384,1739502697.5644715,57.819944858551025,0.035366693811517524,1739502697.564473,57.819944858551025,2.229135248351711,1739502697.5644748,57.819944858551025,0.0,1739502697.5644763,57.819944858551025,0.06201010404080795,1739502697.5644777,57.819944858551025,3.1437358571257357,1739502697.5644794,57.819944858551025,2.168728059005549 +1739502697.5843399,57.83994483947754,17.99156506930546,1739502697.5843425,57.83994483947754,0.16029917894149115,1739502697.5843456,57.83994483947754,94.57562020064807,1739502697.5843482,57.83994483947754,12.414596782833021,1739502697.5843494,57.83994483947754,0.005,1739502697.5843513,57.83994483947754,-3.113753324320556,1739502697.5843527,57.83994483947754,0.14334625327103384,1739502697.5843542,57.83994483947754,0.035366693811517524,1739502697.584355,57.83994483947754,2.229135248351711,1739502697.5843568,57.83994483947754,0.0,1739502697.5843582,57.83994483947754,0.06040718934616196,1739502697.5843594,57.83994483947754,3.1437358571257357,1739502697.5843613,57.83994483947754,2.168728059005549 +1739502697.6042192,57.85994482040405,17.99156506930546,1739502697.6042213,57.85994482040405,0.16029917894149115,1739502697.6042244,57.85994482040405,94.57562020064807,1739502697.604227,57.85994482040405,12.414596782833021,1739502697.6042283,57.85994482040405,0.005,1739502697.60423,57.85994482040405,-3.113753324320556,1739502697.604231,57.85994482040405,0.14334625327103384,1739502697.6042328,57.85994482040405,0.035366693811517524,1739502697.6042337,57.85994482040405,2.229135248351711,1739502697.6042352,57.85994482040405,0.0,1739502697.6042366,57.85994482040405,0.06040718934616196,1739502697.604238,57.85994482040405,3.1437358571257357,1739502697.6042395,57.85994482040405,2.168728059005549 +1739502697.624346,57.879944801330566,17.99156506930546,1739502697.6243489,57.879944801330566,0.16029917894149115,1739502697.624352,57.879944801330566,94.57562020064807,1739502697.6243553,57.879944801330566,12.414596782833021,1739502697.6243567,57.879944801330566,0.005,1739502697.6243584,57.879944801330566,-3.113753324320556,1739502697.6243598,57.879944801330566,0.14334625327103384,1739502697.6243618,57.879944801330566,0.035366693811517524,1739502697.6243632,57.879944801330566,2.229135248351711,1739502697.6243653,57.879944801330566,0.0,1739502697.6243665,57.879944801330566,0.06040718934616196,1739502697.6243682,57.879944801330566,3.1437358571257357,1739502697.6243696,57.879944801330566,2.168728059005549 +1739502697.6442904,57.89994478225708,17.99156506930546,1739502697.644293,57.89994478225708,0.16029917894149115,1739502697.644296,57.89994478225708,94.57562020064807,1739502697.6442988,57.89994478225708,12.414596782833021,1739502697.6443,57.89994478225708,0.005,1739502697.644302,57.89994478225708,-3.113753324320556,1739502697.644303,57.89994478225708,0.14334625327103384,1739502697.6443043,57.89994478225708,0.035366693811517524,1739502697.6443057,57.89994478225708,2.229135248351711,1739502697.6443071,57.89994478225708,0.0,1739502697.6443088,57.89994478225708,0.06040718934616196,1739502697.6443102,57.89994478225708,3.1437358571257357,1739502697.6443117,57.89994478225708,2.168728059005549 +1739502697.6643488,57.919944763183594,17.99156506930546,1739502697.6643517,57.919944763183594,0.16029917894149115,1739502697.6643546,57.919944763183594,94.57562020064807,1739502697.6643574,57.919944763183594,12.414596782833021,1739502697.6643586,57.919944763183594,0.005,1739502697.6643605,57.919944763183594,-3.113753324320556,1739502697.6643617,57.919944763183594,0.14334625327103384,1739502697.6643631,57.919944763183594,0.035366693811517524,1739502697.6643648,57.919944763183594,2.229135248351711,1739502697.6643665,57.919944763183594,0.0,1739502697.664368,57.919944763183594,0.06040718934616196,1739502697.6643696,57.919944763183594,3.1437358571257357,1739502697.664371,57.919944763183594,2.168728059005549 +1739502697.684302,57.93994474411011,17.752671441705576,1739502697.6843045,57.93994474411011,0.15968340225137645,1739502697.6843069,57.93994474411011,95.17480758703775,1739502697.6843097,57.93994474411011,11.802129355359632,1739502697.6843114,57.93994474411011,0.002597725675291024,1739502697.6843128,57.93994474411011,-3.1152002343085816,1739502697.684314,57.93994474411011,0.1386479500653867,1739502697.6843154,57.93994474411011,0.03005000428070026,1739502697.6843166,57.93994474411011,2.2375295366604515,1739502697.6843183,57.93994474411011,0.0,1739502697.6843195,57.93994474411011,0.06295071382140714,1739502697.684321,57.93994474411011,3.144691027105662,1739502697.6843224,57.93994474411011,2.175373674758704 +1739502697.7042527,57.95994472503662,17.752671441705576,1739502697.7042549,57.95994472503662,0.15968340225137645,1739502697.704258,57.95994472503662,95.17480758703775,1739502697.7042606,57.95994472503662,11.802129355359632,1739502697.7042623,57.95994472503662,0.002597725675291024,1739502697.7042637,57.95994472503662,-3.1152002343085816,1739502697.704265,57.95994472503662,0.1386479500653867,1739502697.7042665,57.95994472503662,0.03005000428070026,1739502697.7042677,57.95994472503662,2.2375295366604515,1739502697.7042694,57.95994472503662,0.0,1739502697.7042706,57.95994472503662,0.06215586190174749,1739502697.704272,57.95994472503662,3.144691027105662,1739502697.7042737,57.95994472503662,2.175373674758704 +1739502697.7244148,57.979944705963135,17.752671441705576,1739502697.7244177,57.979944705963135,0.15968340225137645,1739502697.7244208,57.979944705963135,95.17480758703775,1739502697.7244236,57.979944705963135,11.802129355359632,1739502697.724425,57.979944705963135,0.002597725675291024,1739502697.7244267,57.979944705963135,-3.1152002343085816,1739502697.724428,57.979944705963135,0.1386479500653867,1739502697.7244296,57.979944705963135,0.03005000428070026,1739502697.7244308,57.979944705963135,2.2375295366604515,1739502697.7244327,57.979944705963135,0.0,1739502697.724434,57.979944705963135,0.06215586190174749,1739502697.7244356,57.979944705963135,3.144691027105662,1739502697.7244372,57.979944705963135,2.175373674758704 +1739502697.746394,57.99994468688965,17.752671441705576,1739502697.7463977,57.99994468688965,0.15968340225137645,1739502697.7464027,57.99994468688965,95.17480758703775,1739502697.746408,57.99994468688965,11.802129355359632,1739502697.7464108,57.99994468688965,0.002597725675291024,1739502697.7464147,57.99994468688965,-3.1152002343085816,1739502697.746418,57.99994468688965,0.1386479500653867,1739502697.7464213,57.99994468688965,0.03005000428070026,1739502697.7464247,57.99994468688965,2.2375295366604515,1739502697.7464283,57.99994468688965,0.0,1739502697.7464316,57.99994468688965,0.06215586190174749,1739502697.746435,57.99994468688965,3.144691027105662,1739502697.7464385,57.99994468688965,2.175373674758704 +1739502697.7643502,58.01994466781616,17.752671441705576,1739502697.7643528,58.01994466781616,0.15968340225137645,1739502697.764356,58.01994466781616,95.17480758703775,1739502697.7643583,58.01994466781616,11.802129355359632,1739502697.7643597,58.01994466781616,0.002597725675291024,1739502697.7643611,58.01994466781616,-3.1152002343085816,1739502697.7643626,58.01994466781616,0.1386479500653867,1739502697.7643638,58.01994466781616,0.03005000428070026,1739502697.764365,58.01994466781616,2.2375295366604515,1739502697.7643666,58.01994466781616,0.0,1739502697.7643678,58.01994466781616,0.06215586190174749,1739502697.7643695,58.01994466781616,3.144691027105662,1739502697.7643707,58.01994466781616,2.175373674758704 +1739502697.7842195,58.039944648742676,17.513041955351085,1739502697.7842216,58.039944648742676,0.15883683841653884,1739502697.7842243,58.039944648742676,95.21793920145387,1739502697.784227,58.039944648742676,11.74540464628213,1739502697.7842283,58.039944648742676,0.0021210474477489963,1739502697.78423,58.039944648742676,-3.1144277622868874,1739502697.7842312,58.039944648742676,0.13333519878003774,1739502697.7842324,58.039944648742676,0.030759155672440756,1739502697.7842338,58.039944648742676,2.2470597252603923,1739502697.7842352,58.039944648742676,0.0,1739502697.7842362,58.039944648742676,0.06613061197662486,1739502697.7842379,58.039944648742676,3.1456461970855885,1739502697.784239,58.039944648742676,2.1821712234965576 +1739502697.8041868,58.05994462966919,17.513041955351085,1739502697.8041892,58.05994462966919,0.15883683841653884,1739502697.8041918,58.05994462966919,95.21793920145387,1739502697.8041942,58.05994462966919,11.74540464628213,1739502697.804196,58.05994462966919,0.0021210474477489963,1739502697.8041973,58.05994462966919,-3.1144277622868874,1739502697.8041987,58.05994462966919,0.13333519878003774,1739502697.8042,58.05994462966919,0.030759155672440756,1739502697.8042011,58.05994462966919,2.2470597252603923,1739502697.8042026,58.05994462966919,0.0,1739502697.8042037,58.05994462966919,0.06488850176383476,1739502697.804205,58.05994462966919,3.1456461970855885,1739502697.8042064,58.05994462966919,2.1821712234965576 +1739502697.8245196,58.0799446105957,17.513041955351085,1739502697.8245227,58.0799446105957,0.15883683841653884,1739502697.824526,58.0799446105957,95.21793920145387,1739502697.824529,58.0799446105957,11.74540464628213,1739502697.8245304,58.0799446105957,0.0021210474477489963,1739502697.8245323,58.0799446105957,-3.1144277622868874,1739502697.8245335,58.0799446105957,0.13333519878003774,1739502697.8245351,58.0799446105957,0.030759155672440756,1739502697.8245363,58.0799446105957,2.2470597252603923,1739502697.8245382,58.0799446105957,0.0,1739502697.8245394,58.0799446105957,0.06488850176383476,1739502697.8245409,58.0799446105957,3.1456461970855885,1739502697.8245425,58.0799446105957,2.1821712234965576 +1739502697.8446891,58.09994459152222,17.513041955351085,1739502697.8446925,58.09994459152222,0.15883683841653884,1739502697.844696,58.09994459152222,95.21793920145387,1739502697.8446991,58.09994459152222,11.74540464628213,1739502697.8447006,58.09994459152222,0.0021210474477489963,1739502697.8447025,58.09994459152222,-3.1144277622868874,1739502697.8447042,58.09994459152222,0.13333519878003774,1739502697.8447058,58.09994459152222,0.030759155672440756,1739502697.8447073,58.09994459152222,2.2470597252603923,1739502697.8447092,58.09994459152222,0.0,1739502697.8447104,58.09994459152222,0.06488850176383476,1739502697.8447123,58.09994459152222,3.1456461970855885,1739502697.8447137,58.09994459152222,2.1821712234965576 +1739502697.8671107,58.11994457244873,17.513041955351085,1739502697.8671155,58.11994457244873,0.15883683841653884,1739502697.867121,58.11994457244873,95.21793920145387,1739502697.8671267,58.11994457244873,11.74540464628213,1739502697.86713,58.11994457244873,0.0021210474477489963,1739502697.867134,58.11994457244873,-3.1144277622868874,1739502697.8671386,58.11994457244873,0.13333519878003774,1739502697.8671424,58.11994457244873,0.030759155672440756,1739502697.8671465,58.11994457244873,2.2470597252603923,1739502697.8671505,58.11994457244873,0.0,1739502697.8671544,58.11994457244873,0.06488850176383476,1739502697.8671584,58.11994457244873,3.1456461970855885,1739502697.8671625,58.11994457244873,2.1821712234965576 +1739502697.884602,58.139944553375244,17.513041955351085,1739502697.8846052,58.139944553375244,0.15883683841653884,1739502697.8846085,58.139944553375244,95.21793920145387,1739502697.8846116,58.139944553375244,11.74540464628213,1739502697.884613,58.139944553375244,0.0021210474477489963,1739502697.8846152,58.139944553375244,-3.1144277622868874,1739502697.8846166,58.139944553375244,0.13333519878003774,1739502697.8846185,58.139944553375244,0.030759155672440756,1739502697.8846197,58.139944553375244,2.2470597252603923,1739502697.8846219,58.139944553375244,0.0,1739502697.8846233,58.139944553375244,0.06488850176383476,1739502697.884625,58.139944553375244,3.1456461970855885,1739502697.8846264,58.139944553375244,2.1821712234965576 +1739502697.9045985,58.15994453430176,17.27264731455648,1739502697.9046016,58.15994453430176,0.1577579474711639,1739502697.9046047,58.15994453430176,95.261208079015,1739502697.9046078,58.15994453430176,11.68787977050024,1739502697.9046092,58.15994453430176,0.001637645130254119,1739502697.9046113,58.15994453430176,-3.113645267643962,1739502697.9046128,58.15994453430176,0.12814596053538105,1739502697.9046144,58.15994453430176,0.0315283103231483,1739502697.9046159,58.15994453430176,2.256407537657062,1739502697.9046178,58.15994453430176,0.0,1739502697.904619,58.15994453430176,0.06811584491202732,1739502697.904621,58.15994453430176,3.146601367065515,1739502697.9046226,58.15994453430176,2.1893002381400986 +1739502697.9268508,58.17994451522827,17.27264731455648,1739502697.9268546,58.17994451522827,0.1577579474711639,1739502697.9268596,58.17994451522827,95.261208079015,1739502697.9268649,58.17994451522827,11.68787977050024,1739502697.926868,58.17994451522827,0.001637645130254119,1739502697.9268718,58.17994451522827,-3.113645267643962,1739502697.9268754,58.17994451522827,0.12814596053538105,1739502697.9268787,58.17994451522827,0.0315283103231483,1739502697.9268823,58.17994451522827,2.256407537657062,1739502697.9268858,58.17994451522827,0.0,1739502697.9268894,58.17994451522827,0.06710729951696326,1739502697.926893,58.17994451522827,3.146601367065515,1739502697.9268963,58.17994451522827,2.1893002381400986 +1739502697.9443815,58.199944496154785,17.27264731455648,1739502697.944384,58.199944496154785,0.1577579474711639,1739502697.944388,58.199944496154785,95.261208079015,1739502697.944391,58.199944496154785,11.68787977050024,1739502697.9443922,58.199944496154785,0.001637645130254119,1739502697.9443939,58.199944496154785,-3.113645267643962,1739502697.9443955,58.199944496154785,0.12814596053538105,1739502697.9443967,58.199944496154785,0.0315283103231483,1739502697.9443982,58.199944496154785,2.256407537657062,1739502697.9443996,58.199944496154785,0.0,1739502697.9444013,58.199944496154785,0.06710729951696326,1739502697.9444025,58.199944496154785,3.146601367065515,1739502697.9444036,58.199944496154785,2.1893002381400986 +1739502697.964226,58.2199444770813,17.27264731455648,1739502697.9642284,58.2199444770813,0.1577579474711639,1739502697.9642315,58.2199444770813,95.261208079015,1739502697.9642339,58.2199444770813,11.68787977050024,1739502697.964235,58.2199444770813,0.001637645130254119,1739502697.9642367,58.2199444770813,-3.113645267643962,1739502697.9642382,58.2199444770813,0.12814596053538105,1739502697.9642394,58.2199444770813,0.0315283103231483,1739502697.9642403,58.2199444770813,2.256407537657062,1739502697.9642422,58.2199444770813,0.0,1739502697.9642432,58.2199444770813,0.06710729951696326,1739502697.9642444,58.2199444770813,3.146601367065515,1739502697.9642458,58.2199444770813,2.1893002381400986 +1739502697.984219,58.23994445800781,17.27264731455648,1739502697.9842217,58.23994445800781,0.1577579474711639,1739502697.9842246,58.23994445800781,95.261208079015,1739502697.9842272,58.23994445800781,11.68787977050024,1739502697.9842284,58.23994445800781,0.001637645130254119,1739502697.9842305,58.23994445800781,-3.113645267643962,1739502697.9842317,58.23994445800781,0.12814596053538105,1739502697.9842331,58.23994445800781,0.0315283103231483,1739502697.9842343,58.23994445800781,2.256407537657062,1739502697.9842358,58.23994445800781,0.0,1739502697.984237,58.23994445800781,0.06710729951696326,1739502697.9842386,58.23994445800781,3.146601367065515,1739502697.9842398,58.23994445800781,2.1893002381400986 +1739502698.0043323,58.259944438934326,17.03146098340464,1739502698.0043347,58.259944438934326,0.15644512196260596,1739502698.004337,58.259944438934326,95.77222192140539,1739502698.00434,58.259944438934326,11.162200595001085,1739502698.0043414,58.259944438934326,-0.001,1739502698.0043428,58.259944438934326,-3.1147737084480664,1739502698.004344,58.259944438934326,0.1224389445473073,1739502698.0043457,58.259944438934326,0.027276564432544823,1739502698.0043466,58.259944438934326,2.266732973807172,1739502698.0043483,58.259944438934326,0.0,1739502698.0043495,58.259944438934326,0.07145167496965411,1739502698.0043507,58.259944438934326,3.1475565370454412,1739502698.0043523,58.259944438934326,2.1966389170566076 +1739502698.024312,58.27994441986084,17.03146098340464,1739502698.0243146,58.27994441986084,0.15644512196260596,1739502698.0243187,58.27994441986084,95.77222192140539,1739502698.0243218,58.27994441986084,11.162200595001085,1739502698.0243232,58.27994441986084,-0.001,1739502698.024325,58.27994441986084,-3.1147737084480664,1739502698.0243263,58.27994441986084,0.1224389445473073,1739502698.024328,58.27994441986084,0.027276564432544823,1739502698.024329,58.27994441986084,2.266732973807172,1739502698.0243304,58.27994441986084,0.0,1739502698.0243318,58.27994441986084,0.07009405675056435,1739502698.024333,58.27994441986084,3.1475565370454412,1739502698.0243344,58.27994441986084,2.1966389170566076 +1739502698.0443416,58.29994440078735,17.03146098340464,1739502698.044344,58.29994440078735,0.15644512196260596,1739502698.044347,58.29994440078735,95.77222192140539,1739502698.04435,58.29994440078735,11.162200595001085,1739502698.0443516,58.29994440078735,-0.001,1739502698.0443532,58.29994440078735,-3.1147737084480664,1739502698.044355,58.29994440078735,0.1224389445473073,1739502698.0443563,58.29994440078735,0.027276564432544823,1739502698.0443575,58.29994440078735,2.266732973807172,1739502698.0443594,58.29994440078735,0.0,1739502698.0443606,58.29994440078735,0.07009405675056435,1739502698.0443623,58.29994440078735,3.1475565370454412,1739502698.0443635,58.29994440078735,2.1966389170566076 +1739502698.0642385,58.31994438171387,17.03146098340464,1739502698.064241,58.31994438171387,0.15644512196260596,1739502698.064244,58.31994438171387,95.77222192140539,1739502698.0642464,58.31994438171387,11.162200595001085,1739502698.0642478,58.31994438171387,-0.001,1739502698.0642493,58.31994438171387,-3.1147737084480664,1739502698.0642505,58.31994438171387,0.1224389445473073,1739502698.064252,58.31994438171387,0.027276564432544823,1739502698.0642529,58.31994438171387,2.266732973807172,1739502698.0642545,58.31994438171387,0.0,1739502698.0642557,58.31994438171387,0.07009405675056435,1739502698.0642567,58.31994438171387,3.1475565370454412,1739502698.064258,58.31994438171387,2.1966389170566076 +1739502698.0841846,58.33994436264038,17.03146098340464,1739502698.084187,58.33994436264038,0.15644512196260596,1739502698.08419,58.33994436264038,95.77222192140539,1739502698.0841925,58.33994436264038,11.162200595001085,1739502698.0841937,58.33994436264038,-0.001,1739502698.0841954,58.33994436264038,-3.1147737084480664,1739502698.0841968,58.33994436264038,0.1224389445473073,1739502698.0841982,58.33994436264038,0.027276564432544823,1739502698.0841992,58.33994436264038,2.266732973807172,1739502698.0842009,58.33994436264038,0.0,1739502698.084202,58.33994436264038,0.07009405675056435,1739502698.0842032,58.33994436264038,3.1475565370454412,1739502698.0842044,58.33994436264038,2.1966389170566076 +1739502698.10419,58.359944343566895,17.03146098340464,1739502698.1041925,58.359944343566895,0.15644512196260596,1739502698.1041949,58.359944343566895,95.77222192140539,1739502698.1041973,58.359944343566895,11.162200595001085,1739502698.1041987,58.359944343566895,-0.001,1739502698.1042001,58.359944343566895,-3.1147737084480664,1739502698.1042016,58.359944343566895,0.1224389445473073,1739502698.1042027,58.359944343566895,0.027276564432544823,1739502698.1042037,58.359944343566895,2.266732973807172,1739502698.1042056,58.359944343566895,0.0,1739502698.1042068,58.359944343566895,0.07009405675056435,1739502698.1042082,58.359944343566895,3.1475565370454412,1739502698.1042094,58.359944343566895,2.1966389170566076 +1739502698.124312,58.37994432449341,16.78944866383005,1739502698.1243143,58.37994432449341,0.1548966266854368,1739502698.1243176,58.37994432449341,95.7942434939914,1739502698.1243203,58.37994432449341,11.124777628712337,1739502698.1243217,58.37994432449341,-0.0012463102887249181,1739502698.1243236,58.37994432449341,-3.1140352881953084,1739502698.1243248,58.37994432449341,0.11694535058817138,1739502698.1243265,58.37994432449341,0.02796741725333051,1739502698.1243274,58.37994432449341,2.276716905260982,1739502698.1243289,58.37994432449341,0.0,1739502698.12433,58.37994432449341,0.07341449991512795,1739502698.1243312,58.37994432449341,3.1485117070253676,1739502698.1243324,58.37994432449341,2.2043400445151096 +1739502698.1443813,58.39994430541992,16.78944866383005,1739502698.1443837,58.39994430541992,0.1548966266854368,1739502698.1443868,58.39994430541992,95.7942434939914,1739502698.1443894,58.39994430541992,11.124777628712337,1739502698.1443908,58.39994430541992,-0.0012463102887249181,1739502698.1443925,58.39994430541992,-3.1140352881953084,1739502698.144394,58.39994430541992,0.11694535058817138,1739502698.1443956,58.39994430541992,0.02796741725333051,1739502698.1443968,58.39994430541992,2.276716905260982,1739502698.1443985,58.39994430541992,0.0,1739502698.1443996,58.39994430541992,0.07237686074587257,1739502698.144401,58.39994430541992,3.1485117070253676,1739502698.1444027,58.39994430541992,2.2043400445151096 +1739502698.1643026,58.419944286346436,16.78944866383005,1739502698.1643054,58.419944286346436,0.1548966266854368,1739502698.1643085,58.419944286346436,95.7942434939914,1739502698.1643114,58.419944286346436,11.124777628712337,1739502698.1643124,58.419944286346436,-0.0012463102887249181,1739502698.1643143,58.419944286346436,-3.1140352881953084,1739502698.164316,58.419944286346436,0.11694535058817138,1739502698.1643171,58.419944286346436,0.02796741725333051,1739502698.1643186,58.419944286346436,2.276716905260982,1739502698.16432,58.419944286346436,0.0,1739502698.1643212,58.419944286346436,0.07237686074587257,1739502698.1643229,58.419944286346436,3.1485117070253676,1739502698.164324,58.419944286346436,2.2043400445151096 +1739502698.1843185,58.43994426727295,16.78944866383005,1739502698.184321,58.43994426727295,0.1548966266854368,1739502698.184324,58.43994426727295,95.7942434939914,1739502698.184327,58.43994426727295,11.124777628712337,1739502698.184328,58.43994426727295,-0.0012463102887249181,1739502698.1843297,58.43994426727295,-3.1140352881953084,1739502698.1843312,58.43994426727295,0.11694535058817138,1739502698.1843326,58.43994426727295,0.02796741725333051,1739502698.1843338,58.43994426727295,2.276716905260982,1739502698.1843355,58.43994426727295,0.0,1739502698.1843367,58.43994426727295,0.07237686074587257,1739502698.184338,58.43994426727295,3.1485117070253676,1739502698.1843395,58.43994426727295,2.2043400445151096 +1739502698.204331,58.45994424819946,16.78944866383005,1739502698.2043335,58.45994424819946,0.1548966266854368,1739502698.2043364,58.45994424819946,95.7942434939914,1739502698.204339,58.45994424819946,11.124777628712337,1739502698.2043405,58.45994424819946,-0.0012463102887249181,1739502698.2043421,58.45994424819946,-3.1140352881953084,1739502698.2043433,58.45994424819946,0.11694535058817138,1739502698.2043447,58.45994424819946,0.02796741725333051,1739502698.2043462,58.45994424819946,2.276716905260982,1739502698.2043476,58.45994424819946,0.0,1739502698.2043486,58.45994424819946,0.07237686074587257,1739502698.2043502,58.45994424819946,3.1485117070253676,1739502698.2043514,58.45994424819946,2.2043400445151096 +1739502698.2243848,58.47994422912598,16.546582120143828,1739502698.2243876,58.47994422912598,0.15311067407925005,1739502698.2243912,58.47994422912598,96.13946426573212,1739502698.2243938,58.47994422912598,10.763738587669343,1739502698.2243953,58.47994422912598,-0.00411984380109797,1739502698.2243967,58.47994422912598,-3.114410214708233,1739502698.2243984,58.47994422912598,0.1116907120978291,1739502698.2243998,58.47994422912598,0.02563090236230953,1739502698.224401,58.47994422912598,2.286307709045867,1739502698.2244024,58.47994422912598,0.0,1739502698.2244039,58.47994422912598,0.07481455695140087,1739502698.2244055,58.47994422912598,3.149466877005294,1739502698.2244067,58.47994422912598,2.212254932658156 +1739502698.2443147,58.49994421005249,16.546582120143828,1739502698.2443173,58.49994421005249,0.15311067407925005,1739502698.24432,58.49994421005249,96.13946426573212,1739502698.2443228,58.49994421005249,10.763738587669343,1739502698.2443244,58.49994421005249,-0.00411984380109797,1739502698.2443259,58.49994421005249,-3.114410214708233,1739502698.2443273,58.49994421005249,0.1116907120978291,1739502698.244329,58.49994421005249,0.02563090236230953,1739502698.24433,58.49994421005249,2.286307709045867,1739502698.2443318,58.49994421005249,0.0,1739502698.244333,58.49994421005249,0.07405277638771102,1739502698.2443347,58.49994421005249,3.149466877005294,1739502698.244336,58.49994421005249,2.212254932658156 +1739502698.2662177,58.519944190979004,16.546582120143828,1739502698.266221,58.519944190979004,0.15311067407925005,1739502698.2662256,58.519944190979004,96.13946426573212,1739502698.2662308,58.519944190979004,10.763738587669343,1739502698.2662334,58.519944190979004,-0.00411984380109797,1739502698.266237,58.519944190979004,-3.114410214708233,1739502698.2662404,58.519944190979004,0.1116907120978291,1739502698.2662432,58.519944190979004,0.02563090236230953,1739502698.2662466,58.519944190979004,2.286307709045867,1739502698.26625,58.519944190979004,0.0,1739502698.266253,58.519944190979004,0.07405277638771102,1739502698.2662563,58.519944190979004,3.149466877005294,1739502698.2662597,58.519944190979004,2.212254932658156 +1739502698.2842047,58.53994417190552,16.546582120143828,1739502698.2842073,58.53994417190552,0.15311067407925005,1739502698.28421,58.53994417190552,96.13946426573212,1739502698.2842126,58.53994417190552,10.763738587669343,1739502698.2842135,58.53994417190552,-0.00411984380109797,1739502698.2842155,58.53994417190552,-3.114410214708233,1739502698.284217,58.53994417190552,0.1116907120978291,1739502698.284218,58.53994417190552,0.02563090236230953,1739502698.2842195,58.53994417190552,2.286307709045867,1739502698.284221,58.53994417190552,0.0,1739502698.2842221,58.53994417190552,0.07405277638771102,1739502698.2842233,58.53994417190552,3.149466877005294,1739502698.2842247,58.53994417190552,2.212254932658156 +1739502698.3041973,58.55994415283203,16.546582120143828,1739502698.3041997,58.55994415283203,0.15311067407925005,1739502698.3042023,58.55994415283203,96.13946426573212,1739502698.3042054,58.55994415283203,10.763738587669343,1739502698.3042066,58.55994415283203,-0.00411984380109797,1739502698.304208,58.55994415283203,-3.114410214708233,1739502698.3042097,58.55994415283203,0.1116907120978291,1739502698.304211,58.55994415283203,0.02563090236230953,1739502698.3042119,58.55994415283203,2.286307709045867,1739502698.3042135,58.55994415283203,0.0,1739502698.304215,58.55994415283203,0.07405277638771102,1739502698.3042164,58.55994415283203,3.149466877005294,1739502698.3042176,58.55994415283203,2.212254932658156 +1739502698.324376,58.579944133758545,16.546582120143828,1739502698.3243787,58.579944133758545,0.15311067407925005,1739502698.3243816,58.579944133758545,96.13946426573212,1739502698.3243845,58.579944133758545,10.763738587669343,1739502698.324386,58.579944133758545,-0.00411984380109797,1739502698.3243876,58.579944133758545,-3.114410214708233,1739502698.3243897,58.579944133758545,0.1116907120978291,1739502698.324391,58.579944133758545,0.02563090236230953,1739502698.324392,58.579944133758545,2.286307709045867,1739502698.3243937,58.579944133758545,0.0,1739502698.324395,58.579944133758545,0.07405277638771102,1739502698.324397,58.579944133758545,3.149466877005294,1739502698.3243983,58.579944133758545,2.212254932658156 +1739502698.344467,58.59994411468506,16.30283491841427,1739502698.3444695,58.59994411468506,0.1510854097519152,1739502698.3444724,58.59994411468506,96.68887458366592,1739502698.344475,58.59994411468506,10.198100285184454,1739502698.3444765,58.59994411468506,-0.008379810867678618,1739502698.3444781,58.59994411468506,-3.1154770277007335,1739502698.3444796,58.59994411468506,0.10555860153468892,1739502698.344481,58.59994411468506,0.02173789229950718,1739502698.3444824,58.59994411468506,2.2975511782985167,1739502698.3444836,58.59994411468506,0.0,1739502698.3444848,58.59994411468506,0.07859221329639225,1739502698.3444865,58.59994411468506,3.1504220469852204,1739502698.3444877,58.59994411468506,2.2203775399661776 +1739502698.3644028,58.61994409561157,16.30283491841427,1739502698.3644052,58.61994409561157,0.1510854097519152,1739502698.364408,58.61994409561157,96.68887458366592,1739502698.3644109,58.61994409561157,10.198100285184454,1739502698.364412,58.61994409561157,-0.008379810867678618,1739502698.364414,58.61994409561157,-3.1154770277007335,1739502698.3644154,58.61994409561157,0.10555860153468892,1739502698.3644168,58.61994409561157,0.02173789229950718,1739502698.364418,58.61994409561157,2.2975511782985167,1739502698.3644197,58.61994409561157,0.0,1739502698.364421,58.61994409561157,0.07717363833233915,1739502698.364422,58.61994409561157,3.1504220469852204,1739502698.3644238,58.61994409561157,2.2203775399661776 +1739502698.3842106,58.639944076538086,16.30283491841427,1739502698.3842127,58.639944076538086,0.1510854097519152,1739502698.3842156,58.639944076538086,96.68887458366592,1739502698.3842185,58.639944076538086,10.198100285184454,1739502698.3842196,58.639944076538086,-0.008379810867678618,1739502698.384221,58.639944076538086,-3.1154770277007335,1739502698.3842227,58.639944076538086,0.10555860153468892,1739502698.384224,58.639944076538086,0.02173789229950718,1739502698.3842254,58.639944076538086,2.2975511782985167,1739502698.3842268,58.639944076538086,0.0,1739502698.384228,58.639944076538086,0.07717363833233915,1739502698.3842294,58.639944076538086,3.1504220469852204,1739502698.3842306,58.639944076538086,2.2203775399661776 +1739502698.404196,58.6599440574646,16.30283491841427,1739502698.4041984,58.6599440574646,0.1510854097519152,1739502698.4042013,58.6599440574646,96.68887458366592,1739502698.4042041,58.6599440574646,10.198100285184454,1739502698.4042053,58.6599440574646,-0.008379810867678618,1739502698.4042068,58.6599440574646,-3.1154770277007335,1739502698.4042084,58.6599440574646,0.10555860153468892,1739502698.4042099,58.6599440574646,0.02173789229950718,1739502698.4042113,58.6599440574646,2.2975511782985167,1739502698.4042125,58.6599440574646,0.0,1739502698.4042137,58.6599440574646,0.07717363833233915,1739502698.4042153,58.6599440574646,3.1504220469852204,1739502698.4042165,58.6599440574646,2.2203775399661776 +1739502698.4244032,58.67994403839111,16.30283491841427,1739502698.424406,58.67994403839111,0.1510854097519152,1739502698.4244096,58.67994403839111,96.68887458366592,1739502698.4244125,58.67994403839111,10.198100285184454,1739502698.424414,58.67994403839111,-0.008379810867678618,1739502698.4244163,58.67994403839111,-3.1154770277007335,1739502698.4244177,58.67994403839111,0.10555860153468892,1739502698.4244192,58.67994403839111,0.02173789229950718,1739502698.4244204,58.67994403839111,2.2975511782985167,1739502698.424422,58.67994403839111,0.0,1739502698.4244237,58.67994403839111,0.07717363833233915,1739502698.4244251,58.67994403839111,3.1504220469852204,1739502698.4244268,58.67994403839111,2.2203775399661776 +1739502698.4442549,58.69994401931763,16.05818210946566,1739502698.4442575,58.69994401931763,0.1488189150674799,1739502698.4442604,58.69994401931763,97.12015342946545,1739502698.4442635,58.69994401931763,9.749948252229741,1739502698.4442647,58.69994401931763,-0.009678404642120835,1739502698.4442666,58.69994401931763,-3.1164724720332737,1739502698.4442677,58.69994401931763,0.09676740359434742,1739502698.444269,58.69994401931763,0.018663584471521583,1739502698.4442704,58.69994401931763,2.313766714805801,1739502698.4442718,58.69994401931763,0.0,1739502698.4442732,58.69994401931763,0.088485318416231,1739502698.4442744,58.69994401931763,3.151377216965147,1739502698.4442759,58.69994401931763,2.2288162987334488 +1739502698.4643955,58.71994400024414,16.05818210946566,1739502698.4643981,58.71994400024414,0.1488189150674799,1739502698.4644012,58.71994400024414,97.12015342946545,1739502698.4644036,58.71994400024414,9.749948252229741,1739502698.4644053,58.71994400024414,-0.009678404642120835,1739502698.464407,58.71994400024414,-3.1164724720332737,1739502698.4644084,58.71994400024414,0.09676740359434742,1739502698.4644098,58.71994400024414,0.018663584471521583,1739502698.4644108,58.71994400024414,2.313766714805801,1739502698.4644125,58.71994400024414,0.0,1739502698.4644136,58.71994400024414,0.08495041607235221,1739502698.4644153,58.71994400024414,3.151377216965147,1739502698.4644167,58.71994400024414,2.2288162987334488 +1739502698.484395,58.739943981170654,16.05818210946566,1739502698.484398,58.739943981170654,0.1488189150674799,1739502698.484401,58.739943981170654,97.12015342946545,1739502698.484404,58.739943981170654,9.749948252229741,1739502698.4844055,58.739943981170654,-0.009678404642120835,1739502698.4844072,58.739943981170654,-3.1164724720332737,1739502698.4844086,58.739943981170654,0.09676740359434742,1739502698.48441,58.739943981170654,0.018663584471521583,1739502698.4844115,58.739943981170654,2.313766714805801,1739502698.4844131,58.739943981170654,0.0,1739502698.4844146,58.739943981170654,0.08495041607235221,1739502698.484416,58.739943981170654,3.151377216965147,1739502698.4844177,58.739943981170654,2.2288162987334488 +1739502698.5043302,58.75994396209717,16.05818210946566,1739502698.5043325,58.75994396209717,0.1488189150674799,1739502698.5043354,58.75994396209717,97.12015342946545,1739502698.5043383,58.75994396209717,9.749948252229741,1739502698.5043395,58.75994396209717,-0.009678404642120835,1739502698.504341,58.75994396209717,-3.1164724720332737,1739502698.5043426,58.75994396209717,0.09676740359434742,1739502698.5043437,58.75994396209717,0.018663584471521583,1739502698.5043452,58.75994396209717,2.313766714805801,1739502698.5043466,58.75994396209717,0.0,1739502698.5043478,58.75994396209717,0.08495041607235221,1739502698.5043492,58.75994396209717,3.151377216965147,1739502698.5043507,58.75994396209717,2.2288162987334488 +1739502698.5261211,58.77994394302368,16.05818210946566,1739502698.5261245,58.77994394302368,0.1488189150674799,1739502698.5261292,58.77994394302368,97.12015342946545,1739502698.526134,58.77994394302368,9.749948252229741,1739502698.526137,58.77994394302368,-0.009678404642120835,1739502698.5261407,58.77994394302368,-3.1164724720332737,1739502698.526144,58.77994394302368,0.09676740359434742,1739502698.5261474,58.77994394302368,0.018663584471521583,1739502698.5261507,58.77994394302368,2.313766714805801,1739502698.526154,58.77994394302368,0.0,1739502698.5261574,58.77994394302368,0.08495041607235221,1739502698.5261607,58.77994394302368,3.151377216965147,1739502698.526164,58.77994394302368,2.2288162987334488 +1739502698.5442064,58.799943923950195,16.05818210946566,1739502698.5442085,58.799943923950195,0.1488189150674799,1739502698.5442114,58.799943923950195,97.12015342946545,1739502698.5442142,58.799943923950195,9.749948252229741,1739502698.5442154,58.799943923950195,-0.009678404642120835,1739502698.544217,58.799943923950195,-3.1164724720332737,1739502698.5442185,58.799943923950195,0.09676740359434742,1739502698.54422,58.799943923950195,0.018663584471521583,1739502698.5442212,58.799943923950195,2.313766714805801,1739502698.5442228,58.799943923950195,0.0,1739502698.544224,58.799943923950195,0.08495041607235221,1739502698.5442252,58.799943923950195,3.151377216965147,1739502698.5442266,58.799943923950195,2.2288162987334488 +1739502698.5684733,58.81994390487671,15.81255255905506,1739502698.5684795,58.81994390487671,0.14630872403483242,1739502698.5684867,58.81994390487671,97.13169550814371,1739502698.5684938,58.81994390487671,9.719666222008174,1739502698.5684974,58.81994390487671,-0.009935032016879874,1739502698.5685015,58.81994390487671,-3.115954636976303,1739502698.5685048,58.81994390487671,0.09080002870143285,1739502698.5685081,58.81994390487671,0.018771971592297477,1739502698.5685115,58.81994390487671,2.324838813043948,1739502698.568515,58.81994390487671,0.0,1739502698.5685184,58.81994390487671,0.08742544048151213,1739502698.568522,58.81994390487671,3.1523323869450732,1739502698.5685256,58.81994390487671,2.2381868181974087 +1739502698.589031,58.83994388580322,15.81255255905506,1739502698.5890338,58.83994388580322,0.14630872403483242,1739502698.5890374,58.83994388580322,97.13169550814371,1739502698.589041,58.83994388580322,9.719666222008174,1739502698.589043,58.83994388580322,-0.009935032016879874,1739502698.589045,58.83994388580322,-3.115954636976303,1739502698.5890467,58.83994388580322,0.09080002870143285,1739502698.5890486,58.83994388580322,0.018771971592297477,1739502698.58905,58.83994388580322,2.324838813043948,1739502698.5890522,58.83994388580322,0.0,1739502698.5890539,58.83994388580322,0.08665199484653918,1739502698.5890558,58.83994388580322,3.1523323869450732,1739502698.5890577,58.83994388580322,2.2381868181974087 +1739502698.604338,58.859943866729736,15.81255255905506,1739502698.6043406,58.859943866729736,0.14630872403483242,1739502698.6043434,58.859943866729736,97.13169550814371,1739502698.6043458,58.859943866729736,9.719666222008174,1739502698.6043472,58.859943866729736,-0.009935032016879874,1739502698.6043487,58.859943866729736,-3.115954636976303,1739502698.6043499,58.859943866729736,0.09080002870143285,1739502698.6043513,58.859943866729736,0.018771971592297477,1739502698.6043525,58.859943866729736,2.324838813043948,1739502698.6043541,58.859943866729736,0.0,1739502698.6043553,58.859943866729736,0.08665199484653918,1739502698.6043565,58.859943866729736,3.1523323869450732,1739502698.604358,58.859943866729736,2.2381868181974087 +1739502698.625616,58.87994384765625,15.81255255905506,1739502698.6256185,58.87994384765625,0.14630872403483242,1739502698.6256213,58.87994384765625,97.13169550814371,1739502698.6256237,58.87994384765625,9.719666222008174,1739502698.6256251,58.87994384765625,-0.009935032016879874,1739502698.6256268,58.87994384765625,-3.115954636976303,1739502698.6256282,58.87994384765625,0.09080002870143285,1739502698.6256294,58.87994384765625,0.018771971592297477,1739502698.6256304,58.87994384765625,2.324838813043948,1739502698.6256323,58.87994384765625,0.0,1739502698.6256332,58.87994384765625,0.08665199484653918,1739502698.625635,58.87994384765625,3.1523323869450732,1739502698.625636,58.87994384765625,2.2381868181974087 +1739502698.6442542,58.899943828582764,15.81255255905506,1739502698.644257,58.899943828582764,0.14630872403483242,1739502698.64426,58.899943828582764,97.13169550814371,1739502698.6442626,58.899943828582764,9.719666222008174,1739502698.644264,58.899943828582764,-0.009935032016879874,1739502698.6442657,58.899943828582764,-3.115954636976303,1739502698.644267,58.899943828582764,0.09080002870143285,1739502698.6442683,58.899943828582764,0.018771971592297477,1739502698.6442695,58.899943828582764,2.324838813043948,1739502698.6442711,58.899943828582764,0.0,1739502698.6442726,58.899943828582764,0.08665199484653918,1739502698.644274,58.899943828582764,3.1523323869450732,1739502698.6442754,58.899943828582764,2.2381868181974087 +1739502698.6644115,58.91994380950928,15.56589345298601,1739502698.6644142,58.91994380950928,0.1435523823098519,1739502698.6644175,58.91994380950928,97.14328572978724,1739502698.6644204,58.91994380950928,9.689123559403365,1739502698.6644218,58.91994380950928,-0.01,1739502698.6644235,58.91994380950928,-3.1154698930388767,1739502698.664425,58.91994380950928,0.08481519252113719,1739502698.6644266,58.91994380950928,0.018847571103134994,1739502698.6644278,58.91994380950928,2.3359965261165776,1739502698.6644294,58.91994380950928,0.0,1739502698.6644306,58.91994380950928,0.0890976027760208,1739502698.6644318,58.91994380950928,3.1532875569249996,1739502698.664434,58.91994380950928,2.247663176319603 +1739502698.684191,58.93994379043579,15.56589345298601,1739502698.6841931,58.93994379043579,0.1435523823098519,1739502698.6841958,58.93994379043579,97.14328572978724,1739502698.6841984,58.93994379043579,9.689123559403365,1739502698.6842,58.93994379043579,-0.01,1739502698.6842015,58.93994379043579,-3.1154698930388767,1739502698.6842027,58.93994379043579,0.08481519252113719,1739502698.684204,58.93994379043579,0.018847571103134994,1739502698.6842053,58.93994379043579,2.3359965261165776,1739502698.684207,58.93994379043579,0.0,1739502698.6842082,58.93994379043579,0.08833334979697449,1739502698.6842093,58.93994379043579,3.1532875569249996,1739502698.684211,58.93994379043579,2.247663176319603 +1739502698.7041903,58.959943771362305,15.56589345298601,1739502698.7041924,58.959943771362305,0.1435523823098519,1739502698.7041953,58.959943771362305,97.14328572978724,1739502698.7041981,58.959943771362305,9.689123559403365,1739502698.7041993,58.959943771362305,-0.01,1739502698.7042012,58.959943771362305,-3.1154698930388767,1739502698.7042024,58.959943771362305,0.08481519252113719,1739502698.704204,58.959943771362305,0.018847571103134994,1739502698.704205,58.959943771362305,2.3359965261165776,1739502698.7042067,58.959943771362305,0.0,1739502698.704208,58.959943771362305,0.08833334979697449,1739502698.704209,58.959943771362305,3.1532875569249996,1739502698.7042108,58.959943771362305,2.247663176319603 +1739502698.7243228,58.97994375228882,15.56589345298601,1739502698.724326,58.97994375228882,0.1435523823098519,1739502698.7243295,58.97994375228882,97.14328572978724,1739502698.7243326,58.97994375228882,9.689123559403365,1739502698.7243338,58.97994375228882,-0.01,1739502698.7243357,58.97994375228882,-3.1154698930388767,1739502698.7243369,58.97994375228882,0.08481519252113719,1739502698.7243385,58.97994375228882,0.018847571103134994,1739502698.7243397,58.97994375228882,2.3359965261165776,1739502698.7243412,58.97994375228882,0.0,1739502698.7243426,58.97994375228882,0.08833334979697449,1739502698.724344,58.97994375228882,3.1532875569249996,1739502698.7243454,58.97994375228882,2.247663176319603 +1739502698.746029,58.99994373321533,15.56589345298601,1739502698.7460322,58.99994373321533,0.1435523823098519,1739502698.7460365,58.99994373321533,97.14328572978724,1739502698.7460415,58.99994373321533,9.689123559403365,1739502698.7460442,58.99994373321533,-0.01,1739502698.7460477,58.99994373321533,-3.1154698930388767,1739502698.746051,58.99994373321533,0.08481519252113719,1739502698.7460544,58.99994373321533,0.018847571103134994,1739502698.7460575,58.99994373321533,2.3359965261165776,1739502698.7460608,58.99994373321533,0.0,1739502698.7460642,58.99994373321533,0.08833334979697449,1739502698.7460675,58.99994373321533,3.1532875569249996,1739502698.746071,58.99994373321533,2.247663176319603 +1739502698.7643933,59.019943714141846,15.56589345298601,1739502698.7643957,59.019943714141846,0.1435523823098519,1739502698.7643988,59.019943714141846,97.14328572978724,1739502698.7644017,59.019943714141846,9.689123559403365,1739502698.7644029,59.019943714141846,-0.01,1739502698.7644048,59.019943714141846,-3.1154698930388767,1739502698.764406,59.019943714141846,0.08481519252113719,1739502698.7644076,59.019943714141846,0.018847571103134994,1739502698.7644086,59.019943714141846,2.3359965261165776,1739502698.76441,59.019943714141846,0.0,1739502698.7644117,59.019943714141846,0.08833334979697449,1739502698.7644129,59.019943714141846,3.1532875569249996,1739502698.7644145,59.019943714141846,2.247663176319603 +1739502698.784257,59.03994369506836,15.318182838286564,1739502698.7842593,59.03994369506836,0.14054765109588896,1739502698.7842622,59.03994369506836,97.1549251239469,1739502698.7842648,59.03994369506836,9.658112593293462,1739502698.784266,59.03994369506836,-0.01,1739502698.7842674,59.03994369506836,-3.115000728525754,1739502698.7842693,59.03994369506836,0.07893721165996737,1739502698.7842705,59.03994369506836,0.01890977966858178,1739502698.7842717,59.03994369506836,2.3470071482154964,1739502698.7842731,59.03994369506836,0.0,1739502698.784274,59.03994369506836,0.09026038473315898,1739502698.7842758,59.03994369506836,3.154242726904926,1739502698.784277,59.03994369506836,2.2573489622947274 +1739502698.8041742,59.05994367599487,15.318182838286564,1739502698.804176,59.05994367599487,0.14054765109588896,1739502698.8041787,59.05994367599487,97.1549251239469,1739502698.8041816,59.05994367599487,9.658112593293462,1739502698.8041828,59.05994367599487,-0.01,1739502698.8041844,59.05994367599487,-3.115000728525754,1739502698.8041856,59.05994367599487,0.07893721165996737,1739502698.8041873,59.05994367599487,0.01890977966858178,1739502698.8041885,59.05994367599487,2.3470071482154964,1739502698.80419,59.05994367599487,0.0,1739502698.8041909,59.05994367599487,0.08965818592076902,1739502698.8041925,59.05994367599487,3.154242726904926,1739502698.8041937,59.05994367599487,2.2573489622947274 +1739502698.824353,59.07994365692139,15.318182838286564,1739502698.8243563,59.07994365692139,0.14054765109588896,1739502698.8243597,59.07994365692139,97.1549251239469,1739502698.8243625,59.07994365692139,9.658112593293462,1739502698.8243642,59.07994365692139,-0.01,1739502698.8243663,59.07994365692139,-3.115000728525754,1739502698.8243678,59.07994365692139,0.07893721165996737,1739502698.8243692,59.07994365692139,0.01890977966858178,1739502698.8243709,59.07994365692139,2.3470071482154964,1739502698.8243728,59.07994365692139,0.0,1739502698.824374,59.07994365692139,0.08965818592076902,1739502698.8243756,59.07994365692139,3.154242726904926,1739502698.8243768,59.07994365692139,2.2573489622947274 +1739502698.844192,59.0999436378479,15.318182838286564,1739502698.8441944,59.0999436378479,0.14054765109588896,1739502698.8441968,59.0999436378479,97.1549251239469,1739502698.8441997,59.0999436378479,9.658112593293462,1739502698.8442008,59.0999436378479,-0.01,1739502698.8442025,59.0999436378479,-3.115000728525754,1739502698.8442037,59.0999436378479,0.07893721165996737,1739502698.8442051,59.0999436378479,0.01890977966858178,1739502698.8442063,59.0999436378479,2.3470071482154964,1739502698.8442078,59.0999436378479,0.0,1739502698.8442092,59.0999436378479,0.08965818592076902,1739502698.8442104,59.0999436378479,3.154242726904926,1739502698.8442118,59.0999436378479,2.2573489622947274 +1739502698.8667307,59.119943618774414,15.318182838286564,1739502698.8667347,59.119943618774414,0.14054765109588896,1739502698.8667395,59.119943618774414,97.1549251239469,1739502698.8667448,59.119943618774414,9.658112593293462,1739502698.8667476,59.119943618774414,-0.01,1739502698.8667512,59.119943618774414,-3.115000728525754,1739502698.8667545,59.119943618774414,0.07893721165996737,1739502698.8667583,59.119943618774414,0.01890977966858178,1739502698.8667614,59.119943618774414,2.3470071482154964,1739502698.866765,59.119943618774414,0.0,1739502698.8667684,59.119943618774414,0.08965818592076902,1739502698.8667717,59.119943618774414,3.154242726904926,1739502698.8667753,59.119943618774414,2.2573489622947274 +1739502698.884278,59.13994359970093,15.069405260810598,1739502698.8842802,59.13994359970093,0.13729231413636267,1739502698.884283,59.13994359970093,97.45432068358875,1739502698.8842857,59.13994359970093,9.33910645443878,1739502698.884287,59.13994359970093,-0.01,1739502698.8842888,59.13994359970093,-3.1158941877349986,1739502698.88429,59.13994359970093,0.06931897797727038,1739502698.8842914,59.13994359970093,0.016201967863562348,1739502698.8842926,59.13994359970093,2.3651360565655293,1739502698.884294,59.13994359970093,0.0,1739502698.8842955,59.13994359970093,0.10176527133786159,1739502698.884297,59.13994359970093,3.1551978968848524,1739502698.8842983,59.13994359970093,2.267154251901143 +1739502698.9042394,59.15994358062744,15.069405260810598,1739502698.904242,59.15994358062744,0.13729231413636267,1739502698.9042447,59.15994358062744,97.45432068358875,1739502698.9042475,59.15994358062744,9.33910645443878,1739502698.9042487,59.15994358062744,-0.01,1739502698.9042506,59.15994358062744,-3.1158941877349986,1739502698.9042518,59.15994358062744,0.06931897797727038,1739502698.9042532,59.15994358062744,0.016201967863562348,1739502698.9042544,59.15994358062744,2.3651360565655293,1739502698.904256,59.15994358062744,0.0,1739502698.904257,59.15994358062744,0.09798180466438611,1739502698.9042585,59.15994358062744,3.1551978968848524,1739502698.90426,59.15994358062744,2.267154251901143 +1739502698.924322,59.179943561553955,15.069405260810598,1739502698.9243248,59.179943561553955,0.13729231413636267,1739502698.9243279,59.179943561553955,97.45432068358875,1739502698.924331,59.179943561553955,9.33910645443878,1739502698.9243324,59.179943561553955,-0.01,1739502698.924334,59.179943561553955,-3.1158941877349986,1739502698.9243352,59.179943561553955,0.06931897797727038,1739502698.924337,59.179943561553955,0.016201967863562348,1739502698.924338,59.179943561553955,2.3651360565655293,1739502698.92434,59.179943561553955,0.0,1739502698.924342,59.179943561553955,0.09798180466438611,1739502698.9243464,59.179943561553955,3.1551978968848524,1739502698.9243507,59.179943561553955,2.267154251901143 +1739502698.9489799,59.19994354248047,15.069405260810598,1739502698.9489894,59.19994354248047,0.13729231413636267,1739502698.9490001,59.19994354248047,97.45432068358875,1739502698.9490104,59.19994354248047,9.33910645443878,1739502698.9490151,59.19994354248047,-0.01,1739502698.9490209,59.19994354248047,-3.1158941877349986,1739502698.9490263,59.19994354248047,0.06931897797727038,1739502698.949031,59.19994354248047,0.016201967863562348,1739502698.949036,59.19994354248047,2.3651360565655293,1739502698.9490414,59.19994354248047,0.0,1739502698.9490464,59.19994354248047,0.09798180466438611,1739502698.9490516,59.19994354248047,3.1551978968848524,1739502698.9490569,59.19994354248047,2.267154251901143 +1739502698.968194,59.21994352340698,15.069405260810598,1739502698.9681985,59.21994352340698,0.13729231413636267,1739502698.9682047,59.21994352340698,97.45432068358875,1739502698.968212,59.21994352340698,9.33910645443878,1739502698.9682162,59.21994352340698,-0.01,1739502698.9682212,59.21994352340698,-3.1158941877349986,1739502698.9682257,59.21994352340698,0.06931897797727038,1739502698.9682305,59.21994352340698,0.016201967863562348,1739502698.968235,59.21994352340698,2.3651360565655293,1739502698.9682395,59.21994352340698,0.0,1739502698.9682446,59.21994352340698,0.09798180466438611,1739502698.968249,59.21994352340698,3.1551978968848524,1739502698.9682536,59.21994352340698,2.267154251901143 +1739502698.986134,59.239943504333496,15.069405260810598,1739502698.9861374,59.239943504333496,0.13729231413636267,1739502698.9861417,59.239943504333496,97.45432068358875,1739502698.9861465,59.239943504333496,9.33910645443878,1739502698.986149,59.239943504333496,-0.01,1739502698.9861526,59.239943504333496,-3.1158941877349986,1739502698.9861557,59.239943504333496,0.06931897797727038,1739502698.9861588,59.239943504333496,0.016201967863562348,1739502698.986162,59.239943504333496,2.3651360565655293,1739502698.9861653,59.239943504333496,0.0,1739502698.9861684,59.239943504333496,0.09798180466438611,1739502698.9861717,59.239943504333496,3.1551978968848524,1739502698.9861748,59.239943504333496,2.267154251901143 +1739502699.0061574,59.25994348526001,14.819498414738941,1739502699.006161,59.25994348526001,0.13378344490892502,1739502699.006165,59.25994348526001,97.64744119118393,1739502699.00617,59.25994348526001,9.124386792079884,1739502699.0061727,59.25994348526001,-0.011,1739502699.0061765,59.25994348526001,-3.116175721408548,1739502699.0061796,59.25994348526001,0.061847848853042064,1739502699.006183,59.25994348526001,0.014635154086961755,1739502699.006186,59.25994348526001,2.379314575675644,1739502699.0061893,59.25994348526001,0.0,1739502699.0061927,59.25994348526001,0.10289352251384241,1739502699.006196,59.25994348526001,3.156153066864779,1739502699.0061994,59.25994348526001,2.277955965996124 +1739502699.0258696,59.27994346618652,14.819498414738941,1739502699.0258727,59.27994346618652,0.13378344490892502,1739502699.0258768,59.27994346618652,97.64744119118393,1739502699.0258813,59.27994346618652,9.124386792079884,1739502699.025884,59.27994346618652,-0.011,1739502699.0258873,59.27994346618652,-3.116175721408548,1739502699.0258904,59.27994346618652,0.061847848853042064,1739502699.0258934,59.27994346618652,0.014635154086961755,1739502699.0258965,59.27994346618652,2.379314575675644,1739502699.0259,59.27994346618652,0.0,1739502699.0259027,59.27994346618652,0.10135860967952004,1739502699.0259058,59.27994346618652,3.156153066864779,1739502699.025909,59.27994346618652,2.277955965996124 +1739502699.0463095,59.29994344711304,14.819498414738941,1739502699.0463128,59.29994344711304,0.13378344490892502,1739502699.046317,59.29994344711304,97.64744119118393,1739502699.0463216,59.29994344711304,9.124386792079884,1739502699.0463243,59.29994344711304,-0.011,1739502699.0463278,59.29994344711304,-3.116175721408548,1739502699.046331,59.29994344711304,0.061847848853042064,1739502699.046334,59.29994344711304,0.014635154086961755,1739502699.0463371,59.29994344711304,2.379314575675644,1739502699.0463405,59.29994344711304,0.0,1739502699.0463433,59.29994344711304,0.10135860967952004,1739502699.0463464,59.29994344711304,3.156153066864779,1739502699.0463495,59.29994344711304,2.277955965996124 +1739502699.0655549,59.31994342803955,14.819498414738941,1739502699.0655575,59.31994342803955,0.13378344490892502,1739502699.06556,59.31994342803955,97.64744119118393,1739502699.0655627,59.31994342803955,9.124386792079884,1739502699.0655642,59.31994342803955,-0.011,1739502699.0655656,59.31994342803955,-3.116175721408548,1739502699.065567,59.31994342803955,0.061847848853042064,1739502699.0655682,59.31994342803955,0.014635154086961755,1739502699.0655696,59.31994342803955,2.379314575675644,1739502699.0655708,59.31994342803955,0.0,1739502699.065572,59.31994342803955,0.10135860967952004,1739502699.0655735,59.31994342803955,3.156153066864779,1739502699.0655746,59.31994342803955,2.277955965996124 +1739502699.084195,59.339943408966064,14.819498414738941,1739502699.084197,59.339943408966064,0.13378344490892502,1739502699.0841997,59.339943408966064,97.64744119118393,1739502699.0842025,59.339943408966064,9.124386792079884,1739502699.0842037,59.339943408966064,-0.011,1739502699.0842054,59.339943408966064,-3.116175721408548,1739502699.0842068,59.339943408966064,0.061847848853042064,1739502699.084208,59.339943408966064,0.014635154086961755,1739502699.0842094,59.339943408966064,2.379314575675644,1739502699.0842109,59.339943408966064,0.0,1739502699.0842123,59.339943408966064,0.10135860967952004,1739502699.0842135,59.339943408966064,3.156153066864779,1739502699.0842147,59.339943408966064,2.277955965996124 +1739502699.1042552,59.35994338989258,14.56839741302652,1739502699.1042576,59.35994338989258,0.1300179117791842,1739502699.1042604,59.35994338989258,97.92876518547853,1739502699.1042628,59.35994338989258,8.820899439925661,1739502699.1042643,59.35994338989258,-0.0103556473037014,1739502699.104266,59.35994338989258,-3.117174087698996,1739502699.1042674,59.35994338989258,0.05118445770341723,1739502699.1042688,59.35994338989258,0.011892698716967036,1739502699.1042697,59.35994338989258,2.399698646979144,1739502699.1042714,59.35994338989258,0.0,1739502699.1042726,59.35994338989258,0.11488732881457336,1739502699.1042743,59.35994338989258,3.157108236844705,1739502699.1042755,59.35994338989258,2.289039045666189 +1739502699.1243234,59.37994337081909,14.56839741302652,1739502699.124326,59.37994337081909,0.1300179117791842,1739502699.1243293,59.37994337081909,97.92876518547853,1739502699.1243317,59.37994337081909,8.820899439925661,1739502699.1243331,59.37994337081909,-0.0103556473037014,1739502699.1243348,59.37994337081909,-3.117174087698996,1739502699.1243365,59.37994337081909,0.05118445770341723,1739502699.1243377,59.37994337081909,0.011892698716967036,1739502699.1243389,59.37994337081909,2.399698646979144,1739502699.1243405,59.37994337081909,0.0,1739502699.124342,59.37994337081909,0.11065960131295505,1739502699.1243436,59.37994337081909,3.157108236844705,1739502699.1243448,59.37994337081909,2.289039045666189 +1739502699.1443834,59.399943351745605,14.56839741302652,1739502699.1443865,59.399943351745605,0.1300179117791842,1739502699.1443894,59.399943351745605,97.92876518547853,1739502699.1443923,59.399943351745605,8.820899439925661,1739502699.1443934,59.399943351745605,-0.0103556473037014,1739502699.1443954,59.399943351745605,-3.117174087698996,1739502699.1443965,59.399943351745605,0.05118445770341723,1739502699.144398,59.399943351745605,0.011892698716967036,1739502699.1443994,59.399943351745605,2.399698646979144,1739502699.1444008,59.399943351745605,0.0,1739502699.1444025,59.399943351745605,0.11065960131295505,1739502699.1444037,59.399943351745605,3.157108236844705,1739502699.144405,59.399943351745605,2.289039045666189 +1739502699.1643283,59.41994333267212,14.56839741302652,1739502699.164331,59.41994333267212,0.1300179117791842,1739502699.1643345,59.41994333267212,97.92876518547853,1739502699.1643376,59.41994333267212,8.820899439925661,1739502699.1643388,59.41994333267212,-0.0103556473037014,1739502699.1643407,59.41994333267212,-3.117174087698996,1739502699.1643422,59.41994333267212,0.05118445770341723,1739502699.1643438,59.41994333267212,0.011892698716967036,1739502699.1643453,59.41994333267212,2.399698646979144,1739502699.1643472,59.41994333267212,0.0,1739502699.1643486,59.41994333267212,0.11065960131295505,1739502699.1643503,59.41994333267212,3.157108236844705,1739502699.1643517,59.41994333267212,2.289039045666189 +1739502699.1842542,59.43994331359863,14.56839741302652,1739502699.1842568,59.43994331359863,0.1300179117791842,1739502699.18426,59.43994331359863,97.92876518547853,1739502699.1842625,59.43994331359863,8.820899439925661,1739502699.1842637,59.43994331359863,-0.0103556473037014,1739502699.1842654,59.43994331359863,-3.117174087698996,1739502699.184267,59.43994331359863,0.05118445770341723,1739502699.1842685,59.43994331359863,0.011892698716967036,1739502699.1842697,59.43994331359863,2.399698646979144,1739502699.184271,59.43994331359863,0.0,1739502699.1842723,59.43994331359863,0.11065960131295505,1739502699.1842737,59.43994331359863,3.157108236844705,1739502699.184275,59.43994331359863,2.289039045666189 +1739502699.2046688,59.45994329452515,14.56839741302652,1739502699.2046885,59.45994329452515,0.1300179117791842,1739502699.2046962,59.45994329452515,97.92876518547853,1739502699.2047045,59.45994329452515,8.820899439925661,1739502699.204707,59.45994329452515,-0.0103556473037014,1739502699.204709,59.45994329452515,-3.117174087698996,1739502699.204711,59.45994329452515,0.05118445770341723,1739502699.2047124,59.45994329452515,0.011892698716967036,1739502699.204714,59.45994329452515,2.399698646979144,1739502699.2047157,59.45994329452515,0.0,1739502699.2047174,59.45994329452515,0.11065960131295505,1739502699.204719,59.45994329452515,3.157108236844705,1739502699.2047207,59.45994329452515,2.289039045666189 +1739502699.2252533,59.47994327545166,14.316020353051027,1739502699.2252579,59.47994327545166,0.1259921132650499,1739502699.2252622,59.47994327545166,98.16581567855565,1739502699.2252655,59.47994327545166,8.559454155042316,1739502699.225267,59.47994327545166,-0.01,1739502699.2252693,59.47994327545166,-3.1179732216811415,1739502699.2252707,59.47994327545166,0.04116297292947738,1739502699.225273,59.47994327545166,0.009534483666961822,1739502699.2252743,59.47994327545166,2.4190148089279195,1739502699.2252765,59.47994327545166,0.0,1739502699.225278,59.47994327545166,0.12101304863701981,1739502699.2252803,59.47994327545166,3.1580634068246316,1739502699.225282,59.47994327545166,2.301237214700999 +1739502699.2475398,59.499943256378174,14.316020353051027,1739502699.247544,59.499943256378174,0.1259921132650499,1739502699.2475498,59.499943256378174,98.16581567855565,1739502699.2475555,59.499943256378174,8.559454155042316,1739502699.247559,59.499943256378174,-0.01,1739502699.2475638,59.499943256378174,-3.1179732216811415,1739502699.2475677,59.499943256378174,0.04116297292947738,1739502699.2475717,59.499943256378174,0.009534483666961822,1739502699.2475755,59.499943256378174,2.4190148089279195,1739502699.2475796,59.499943256378174,0.0,1739502699.2475836,59.499943256378174,0.11777759422692036,1739502699.247588,59.499943256378174,3.1580634068246316,1739502699.2475917,59.499943256378174,2.301237214700999 +1739502699.2647915,59.51994323730469,14.316020353051027,1739502699.264794,59.51994323730469,0.1259921132650499,1739502699.2647977,59.51994323730469,98.16581567855565,1739502699.264801,59.51994323730469,8.559454155042316,1739502699.2648025,59.51994323730469,-0.01,1739502699.2648046,59.51994323730469,-3.1179732216811415,1739502699.264806,59.51994323730469,0.04116297292947738,1739502699.2648077,59.51994323730469,0.009534483666961822,1739502699.2648091,59.51994323730469,2.4190148089279195,1739502699.264811,59.51994323730469,0.0,1739502699.2648125,59.51994323730469,0.11777759422692036,1739502699.2648141,59.51994323730469,3.1580634068246316,1739502699.2648158,59.51994323730469,2.301237214700999 +1739502699.284714,59.5399432182312,14.316020353051027,1739502699.2847173,59.5399432182312,0.1259921132650499,1739502699.2847211,59.5399432182312,98.16581567855565,1739502699.2847247,59.5399432182312,8.559454155042316,1739502699.2847264,59.5399432182312,-0.01,1739502699.2847283,59.5399432182312,-3.1179732216811415,1739502699.2847302,59.5399432182312,0.04116297292947738,1739502699.2847316,59.5399432182312,0.009534483666961822,1739502699.2847338,59.5399432182312,2.4190148089279195,1739502699.2847354,59.5399432182312,0.0,1739502699.284737,59.5399432182312,0.11777759422692036,1739502699.2847385,59.5399432182312,3.1580634068246316,1739502699.2847404,59.5399432182312,2.301237214700999 +1739502699.3046992,59.559943199157715,14.316020353051027,1739502699.304702,59.559943199157715,0.1259921132650499,1739502699.3047056,59.559943199157715,98.16581567855565,1739502699.304709,59.559943199157715,8.559454155042316,1739502699.3047104,59.559943199157715,-0.01,1739502699.3047128,59.559943199157715,-3.1179732216811415,1739502699.3047147,59.559943199157715,0.04116297292947738,1739502699.304717,59.559943199157715,0.009534483666961822,1739502699.3047185,59.559943199157715,2.4190148089279195,1739502699.3047204,59.559943199157715,0.0,1739502699.3047216,59.559943199157715,0.11777759422692036,1739502699.3047235,59.559943199157715,3.1580634068246316,1739502699.304725,59.559943199157715,2.301237214700999 +1739502699.324518,59.57994318008423,14.062277390625983,1739502699.3245203,59.57994318008423,0.12170208750692257,1739502699.3245237,59.57994318008423,98.33553876546561,1739502699.3245268,59.57994318008423,8.36398191974298,1739502699.3245285,59.57994318008423,-0.0108049662451562,1739502699.3245304,59.57994318008423,-3.1183430382892214,1739502699.324532,59.57994318008423,0.03319390164387667,1739502699.3245335,59.57994318008423,0.007846822455825575,1739502699.3245351,59.57994318008423,2.434485913825182,1739502699.3245368,59.57994318008423,0.0,1739502699.3245382,59.57994318008423,0.12155293941353978,1739502699.32454,59.57994318008423,3.159018576804558,1739502699.3245413,59.57994318008423,2.3141127705559956 +1739502699.3446925,59.59994316101074,14.062277390625983,1739502699.3446999,59.59994316101074,0.12170208750692257,1739502699.3447075,59.59994316101074,98.33553876546561,1739502699.344712,59.59994316101074,8.36398191974298,1739502699.344714,59.59994316101074,-0.0108049662451562,1739502699.3447163,59.59994316101074,-3.1183430382892214,1739502699.344719,59.59994316101074,0.03319390164387667,1739502699.3447208,59.59994316101074,0.007846822455825575,1739502699.344723,59.59994316101074,2.434485913825182,1739502699.3447251,59.59994316101074,0.0,1739502699.344727,59.59994316101074,0.12037314326918658,1739502699.3447292,59.59994316101074,3.159018576804558,1739502699.344731,59.59994316101074,2.3141127705559956 +1739502699.3645382,59.619943141937256,14.062277390625983,1739502699.3645406,59.619943141937256,0.12170208750692257,1739502699.364544,59.619943141937256,98.33553876546561,1739502699.3645473,59.619943141937256,8.36398191974298,1739502699.364549,59.619943141937256,-0.0108049662451562,1739502699.3645508,59.619943141937256,-3.1183430382892214,1739502699.3645525,59.619943141937256,0.03319390164387667,1739502699.3645544,59.619943141937256,0.007846822455825575,1739502699.3645558,59.619943141937256,2.434485913825182,1739502699.3645577,59.619943141937256,0.0,1739502699.3645594,59.619943141937256,0.12037314326918658,1739502699.3645608,59.619943141937256,3.159018576804558,1739502699.3645625,59.619943141937256,2.3141127705559956 +1739502699.3847358,59.63994312286377,14.062277390625983,1739502699.3847408,59.63994312286377,0.12170208750692257,1739502699.384745,59.63994312286377,98.33553876546561,1739502699.3847482,59.63994312286377,8.36398191974298,1739502699.38475,59.63994312286377,-0.0108049662451562,1739502699.3847518,59.63994312286377,-3.1183430382892214,1739502699.3847535,59.63994312286377,0.03319390164387667,1739502699.384755,59.63994312286377,0.007846822455825575,1739502699.3847566,59.63994312286377,2.434485913825182,1739502699.3847585,59.63994312286377,0.0,1739502699.3847601,59.63994312286377,0.12037314326918658,1739502699.3847618,59.63994312286377,3.159018576804558,1739502699.3847635,59.63994312286377,2.3141127705559956 +1739502699.404712,59.65994310379028,14.062277390625983,1739502699.4047153,59.65994310379028,0.12170208750692257,1739502699.4047189,59.65994310379028,98.33553876546561,1739502699.4047222,59.65994310379028,8.36398191974298,1739502699.4047236,59.65994310379028,-0.0108049662451562,1739502699.4047258,59.65994310379028,-3.1183430382892214,1739502699.4047275,59.65994310379028,0.03319390164387667,1739502699.4047291,59.65994310379028,0.007846822455825575,1739502699.4047306,59.65994310379028,2.434485913825182,1739502699.4047325,59.65994310379028,0.0,1739502699.404734,59.65994310379028,0.12037314326918658,1739502699.4047358,59.65994310379028,3.159018576804558,1739502699.4047372,59.65994310379028,2.3141127705559956 +1739502699.424588,59.6799430847168,14.062277390625983,1739502699.4245906,59.6799430847168,0.12170208750692257,1739502699.4245937,59.6799430847168,98.33553876546561,1739502699.4245968,59.6799430847168,8.36398191974298,1739502699.4245982,59.6799430847168,-0.0108049662451562,1739502699.4246001,59.6799430847168,-3.1183430382892214,1739502699.4246018,59.6799430847168,0.03319390164387667,1739502699.4246035,59.6799430847168,0.007846822455825575,1739502699.4246047,59.6799430847168,2.434485913825182,1739502699.4246068,59.6799430847168,0.0,1739502699.424608,59.6799430847168,0.12037314326918658,1739502699.42461,59.6799430847168,3.159018576804558,1739502699.4246113,59.6799430847168,2.3141127705559956 +1739502699.444832,59.69994306564331,13.807103326135024,1739502699.4448357,59.69994306564331,0.11714405611348067,1739502699.4448395,59.69994306564331,98.64305388773174,1739502699.444843,59.69994306564331,8.03006565114845,1739502699.4448447,59.69994306564331,-0.011,1739502699.4448469,59.69994306564331,-3.1194146701904097,1739502699.4448483,59.69994306564331,0.021940120602032563,1739502699.4448502,59.69994306564331,0.005046331662182824,1739502699.4448516,59.69994306564331,2.456502610685976,1739502699.4448538,59.69994306564331,0.0,1739502699.4448552,59.69994306564331,0.13319625378453903,1739502699.444857,59.69994306564331,3.1599737467844844,1739502699.4448586,59.69994306564331,2.327313581564826 +1739502699.465069,59.719943046569824,13.807103326135024,1739502699.4650722,59.719943046569824,0.11714405611348067,1739502699.4650767,59.719943046569824,98.64305388773174,1739502699.4650798,59.719943046569824,8.03006565114845,1739502699.4650817,59.719943046569824,-0.011,1739502699.4650836,59.719943046569824,-3.1194146701904097,1739502699.4650853,59.719943046569824,0.021940120602032563,1739502699.4650867,59.719943046569824,0.005046331662182824,1739502699.4650884,59.719943046569824,2.456502610685976,1739502699.46509,59.719943046569824,0.0,1739502699.4650915,59.719943046569824,0.12918902912115016,1739502699.4650934,59.719943046569824,3.1599737467844844,1739502699.4650953,59.719943046569824,2.327313581564826 +1739502699.4847653,59.73994302749634,13.807103326135024,1739502699.4847686,59.73994302749634,0.11714405611348067,1739502699.4847724,59.73994302749634,98.64305388773174,1739502699.4847753,59.73994302749634,8.03006565114845,1739502699.484777,59.73994302749634,-0.011,1739502699.4847796,59.73994302749634,-3.1194146701904097,1739502699.484781,59.73994302749634,0.021940120602032563,1739502699.4847827,59.73994302749634,0.005046331662182824,1739502699.4847841,59.73994302749634,2.456502610685976,1739502699.484786,59.73994302749634,0.0,1739502699.4847875,59.73994302749634,0.12918902912115016,1739502699.484789,59.73994302749634,3.1599737467844844,1739502699.4847908,59.73994302749634,2.327313581564826 +1739502699.5047593,59.75994300842285,13.807103326135024,1739502699.5047624,59.75994300842285,0.11714405611348067,1739502699.504766,59.75994300842285,98.64305388773174,1739502699.5047693,59.75994300842285,8.03006565114845,1739502699.5047708,59.75994300842285,-0.011,1739502699.504773,59.75994300842285,-3.1194146701904097,1739502699.5047746,59.75994300842285,0.021940120602032563,1739502699.5047762,59.75994300842285,0.005046331662182824,1739502699.5047777,59.75994300842285,2.456502610685976,1739502699.5047793,59.75994300842285,0.0,1739502699.5047808,59.75994300842285,0.12918902912115016,1739502699.5047827,59.75994300842285,3.1599737467844844,1739502699.5047843,59.75994300842285,2.327313581564826 +1739502699.5245013,59.779942989349365,13.807103326135024,1739502699.5245037,59.779942989349365,0.11714405611348067,1739502699.524507,59.779942989349365,98.64305388773174,1739502699.5245101,59.779942989349365,8.03006565114845,1739502699.5245118,59.779942989349365,-0.011,1739502699.5245135,59.779942989349365,-3.1194146701904097,1739502699.5245152,59.779942989349365,0.021940120602032563,1739502699.5245168,59.779942989349365,0.005046331662182824,1739502699.5245183,59.779942989349365,2.456502610685976,1739502699.52452,59.779942989349365,0.0,1739502699.5245216,59.779942989349365,0.12918902912115016,1739502699.5245233,59.779942989349365,3.1599737467844844,1739502699.5245247,59.779942989349365,2.327313581564826 +1739502699.544794,59.79994297027588,13.55043905530778,1739502699.5447974,59.79994297027588,0.11231415764510011,1739502699.5448008,59.79994297027588,98.98556827168933,1739502699.544804,59.79994297027588,7.659315832647607,1739502699.5448055,59.79994297027588,-0.012891010330552151,1739502699.5448077,59.79994297027588,-3.1203426615755876,1739502699.5448096,59.79994297027588,0.01127655146335862,1739502699.5448112,59.79994297027588,0.0024942793248694368,1739502699.544813,59.79994297027588,2.4775483203465285,1739502699.5448148,59.79994297027588,0.0,1739502699.5448167,59.79994297027588,0.139260026769323,1739502699.5448182,59.79994297027588,3.160928916764411,1739502699.54482,59.79994297027588,2.3414354824057173 +1739502699.565021,59.81994295120239,13.55043905530778,1739502699.5650246,59.81994295120239,0.11231415764510011,1739502699.5650282,59.81994295120239,98.98556827168933,1739502699.5650315,59.81994295120239,7.659315832647607,1739502699.565033,59.81994295120239,-0.012891010330552151,1739502699.565035,59.81994295120239,-3.1203426615755876,1739502699.5650368,59.81994295120239,0.01127655146335862,1739502699.5650384,59.81994295120239,0.0024942793248694368,1739502699.5650399,59.81994295120239,2.4775483203465285,1739502699.5650418,59.81994295120239,0.0,1739502699.5650432,59.81994295120239,0.1361128379408112,1739502699.5650449,59.81994295120239,3.160928916764411,1739502699.5650468,59.81994295120239,2.3414354824057173 +1739502699.5846882,59.839942932128906,13.55043905530778,1739502699.5846915,59.839942932128906,0.11231415764510011,1739502699.584695,59.839942932128906,98.98556827168933,1739502699.5846984,59.839942932128906,7.659315832647607,1739502699.5846999,59.839942932128906,-0.012891010330552151,1739502699.5847025,59.839942932128906,-3.1203426615755876,1739502699.584704,59.839942932128906,0.01127655146335862,1739502699.5847058,59.839942932128906,0.0024942793248694368,1739502699.5847073,59.839942932128906,2.4775483203465285,1739502699.5847092,59.839942932128906,0.0,1739502699.5847106,59.839942932128906,0.1361128379408112,1739502699.5847123,59.839942932128906,3.160928916764411,1739502699.584714,59.839942932128906,2.3414354824057173 +1739502699.6047,59.85994291305542,13.55043905530778,1739502699.6047032,59.85994291305542,0.11231415764510011,1739502699.6047065,59.85994291305542,98.98556827168933,1739502699.6047099,59.85994291305542,7.659315832647607,1739502699.6047118,59.85994291305542,-0.012891010330552151,1739502699.6047137,59.85994291305542,-3.1203426615755876,1739502699.6047158,59.85994291305542,0.01127655146335862,1739502699.6047173,59.85994291305542,0.0024942793248694368,1739502699.6047187,59.85994291305542,2.4775483203465285,1739502699.6047206,59.85994291305542,0.0,1739502699.6047223,59.85994291305542,0.1361128379408112,1739502699.6047237,59.85994291305542,3.160928916764411,1739502699.6047254,59.85994291305542,2.3414354824057173 +1739502699.6248825,59.879942893981934,13.55043905530778,1739502699.6248856,59.879942893981934,0.11231415764510011,1739502699.6248891,59.879942893981934,98.98556827168933,1739502699.6248922,59.879942893981934,7.659315832647607,1739502699.6248937,59.879942893981934,-0.012891010330552151,1739502699.6248958,59.879942893981934,-3.1203426615755876,1739502699.6248972,59.879942893981934,0.01127655146335862,1739502699.6248991,59.879942893981934,0.0024942793248694368,1739502699.6249006,59.879942893981934,2.4775483203465285,1739502699.6249027,59.879942893981934,0.0,1739502699.6249042,59.879942893981934,0.1361128379408112,1739502699.624906,59.879942893981934,3.160928916764411,1739502699.6249075,59.879942893981934,2.3414354824057173 +1739502699.645195,59.89994287490845,13.55043905530778,1739502699.6451979,59.89994287490845,0.11231415764510011,1739502699.645201,59.89994287490845,98.98556827168933,1739502699.6452038,59.89994287490845,7.659315832647607,1739502699.645205,59.89994287490845,-0.012891010330552151,1739502699.645207,59.89994287490845,-3.1203426615755876,1739502699.6452084,59.89994287490845,0.01127655146335862,1739502699.6452098,59.89994287490845,0.0024942793248694368,1739502699.6452112,59.89994287490845,2.4775483203465285,1739502699.6452127,59.89994287490845,0.0,1739502699.6452143,59.89994287490845,0.1361128379408112,1739502699.6452155,59.89994287490845,3.160928916764411,1739502699.645217,59.89994287490845,2.3414354824057173 +1739502699.6654525,59.91994285583496,13.292179242106776,1739502699.6654587,59.91994285583496,0.10720745453783032,1739502699.6654623,59.91994285583496,99.22507692964703,1739502699.6654654,59.91994285583496,7.389889887108681,1739502699.665483,59.91994285583496,-0.014411269499188953,1739502699.6654875,59.91994285583496,-3.1209902214147833,1739502699.6654897,59.91994285583496,0.0018359958181210852,1739502699.6655028,59.91994285583496,0.00040458293261129105,1739502699.6655042,59.91994285583496,2.496330703748454,1739502699.6655064,59.91994285583496,0.0,1739502699.6655097,59.91994285583496,0.14166913561598063,1739502699.6655111,59.91994285583496,3.161884086744337,1739502699.6655142,59.91994285583496,2.3563979122944 +1739502699.6861448,59.939942836761475,13.292179242106776,1739502699.6861486,59.939942836761475,0.10720745453783032,1739502699.6861532,59.939942836761475,99.22507692964703,1739502699.6861584,59.939942836761475,7.389889887108681,1739502699.686161,59.939942836761475,-0.014411269499188953,1739502699.6861653,59.939942836761475,-3.1209902214147833,1739502699.686169,59.939942836761475,0.0018359958181210852,1739502699.6861725,59.939942836761475,0.00040458293261129105,1739502699.686176,59.939942836761475,2.496330703748454,1739502699.6861796,59.939942836761475,0.0,1739502699.686183,59.939942836761475,0.13993279145405424,1739502699.6861866,59.939942836761475,3.161884086744337,1739502699.68619,59.939942836761475,2.3563979122944 +1739502699.704311,59.95994281768799,13.292179242106776,1739502699.7043138,59.95994281768799,0.10720745453783032,1739502699.704317,59.95994281768799,99.22507692964703,1739502699.7043202,59.95994281768799,7.389889887108681,1739502699.7043219,59.95994281768799,-0.014411269499188953,1739502699.7043238,59.95994281768799,-3.1209902214147833,1739502699.704326,59.95994281768799,0.0018359958181210852,1739502699.7043276,59.95994281768799,0.00040458293261129105,1739502699.704329,59.95994281768799,2.496330703748454,1739502699.704331,59.95994281768799,0.0,1739502699.704332,59.95994281768799,0.13993279145405424,1739502699.7043335,59.95994281768799,3.161884086744337,1739502699.7043352,59.95994281768799,2.3563979122944 +1739502699.7251303,59.9799427986145,13.292179242106776,1739502699.7251334,59.9799427986145,0.10720745453783032,1739502699.7251377,59.9799427986145,99.22507692964703,1739502699.7251427,59.9799427986145,7.389889887108681,1739502699.7251453,59.9799427986145,-0.014411269499188953,1739502699.7251482,59.9799427986145,-3.1209902214147833,1739502699.7251508,59.9799427986145,0.0018359958181210852,1739502699.725153,59.9799427986145,0.00040458293261129105,1739502699.725155,59.9799427986145,2.496330703748454,1739502699.725158,59.9799427986145,0.0,1739502699.7251606,59.9799427986145,0.13993279145405424,1739502699.7251632,59.9799427986145,3.161884086744337,1739502699.725166,59.9799427986145,2.3563979122944 +1739502699.745576,59.999942779541016,13.292179242106776,1739502699.7455797,59.999942779541016,0.10720745453783032,1739502699.745584,59.999942779541016,99.22507692964703,1739502699.7455885,59.999942779541016,7.389889887108681,1739502699.7455907,59.999942779541016,-0.014411269499188953,1739502699.7455938,59.999942779541016,-3.1209902214147833,1739502699.7455962,59.999942779541016,0.0018359958181210852,1739502699.7455986,59.999942779541016,0.00040458293261129105,1739502699.7456005,59.999942779541016,2.496330703748454,1739502699.7456028,59.999942779541016,0.0,1739502699.7456048,59.999942779541016,0.13993279145405424,1739502699.7456079,59.999942779541016,3.161884086744337,1739502699.7456105,59.999942779541016,2.3563979122944 +1739502699.7656267,60.01994276046753,13.032266233659133,1739502699.7656305,60.01994276046753,0.1018196965091338,1739502699.7656345,60.01994276046753,99.46390290185593,1739502699.7656388,60.01994276046753,7.120468821450745,1739502699.7656415,60.01994276046753,-0.015707488095038337,1739502699.7656446,60.01994276046753,-3.1217151616702887,1739502699.7656472,60.01994276046753,-0.008095504882811322,1739502699.7656493,60.01994276046753,-0.001778256540267089,1739502699.765652,60.01994276046753,2.483861306991412,1739502699.7656546,60.01994276046753,0.0,1739502699.7656572,60.01994276046753,0.09954058268403863,1739502699.7656596,60.01994276046753,3.1628392567242636,1739502699.7656622,60.01994276046753,2.3716981507907393 +1739502699.784108,60.03994274139404,13.032266233659133,1739502699.7841108,60.03994274139404,0.1018196965091338,1739502699.7841136,60.03994274139404,99.46390290185593,1739502699.7841165,60.03994274139404,7.120468821450745,1739502699.7841177,60.03994274139404,-0.015707488095038337,1739502699.7841196,60.03994274139404,-3.1217151616702887,1739502699.7841208,60.03994274139404,-0.008095504882811322,1739502699.7841225,60.03994274139404,-0.001778256540267089,1739502699.7841237,60.03994274139404,2.483861306991412,1739502699.7841253,60.03994274139404,0.0,1739502699.7841268,60.03994274139404,0.11216315620067263,1739502699.7841282,60.03994274139404,3.1628392567242636,1739502699.7841296,60.03994274139404,2.3716981507907393 +1739502699.8040504,60.05994272232056,13.032266233659133,1739502699.8040526,60.05994272232056,0.1018196965091338,1739502699.804055,60.05994272232056,99.46390290185593,1739502699.8040576,60.05994272232056,7.120468821450745,1739502699.8040586,60.05994272232056,-0.015707488095038337,1739502699.8040605,60.05994272232056,-3.1217151616702887,1739502699.8040617,60.05994272232056,-0.008095504882811322,1739502699.8040626,60.05994272232056,-0.001778256540267089,1739502699.804064,60.05994272232056,2.483861306991412,1739502699.8040652,60.05994272232056,0.0,1739502699.8040667,60.05994272232056,0.11216315620067263,1739502699.8040679,60.05994272232056,3.1628392567242636,1739502699.804069,60.05994272232056,2.3716981507907393 +1739502699.8241465,60.07994270324707,13.032266233659133,1739502699.824149,60.07994270324707,0.1018196965091338,1739502699.8241518,60.07994270324707,99.46390290185593,1739502699.8241546,60.07994270324707,7.120468821450745,1739502699.8241558,60.07994270324707,-0.015707488095038337,1739502699.8241575,60.07994270324707,-3.1217151616702887,1739502699.8241587,60.07994270324707,-0.008095504882811322,1739502699.82416,60.07994270324707,-0.001778256540267089,1739502699.8241613,60.07994270324707,2.483861306991412,1739502699.8241627,60.07994270324707,0.0,1739502699.8241642,60.07994270324707,0.11216315620067263,1739502699.8241653,60.07994270324707,3.1628392567242636,1739502699.8241668,60.07994270324707,2.3716981507907393 +1739502699.8443623,60.099942684173584,13.032266233659133,1739502699.8443654,60.099942684173584,0.1018196965091338,1739502699.8443685,60.099942684173584,99.46390290185593,1739502699.8443713,60.099942684173584,7.120468821450745,1739502699.8443725,60.099942684173584,-0.015707488095038337,1739502699.844374,60.099942684173584,-3.1217151616702887,1739502699.8443756,60.099942684173584,-0.008095504882811322,1739502699.8443768,60.099942684173584,-0.001778256540267089,1739502699.844378,60.099942684173584,2.483861306991412,1739502699.84438,60.099942684173584,0.0,1739502699.844381,60.099942684173584,0.11216315620067263,1739502699.8443828,60.099942684173584,3.1628392567242636,1739502699.844384,60.099942684173584,2.3716981507907393 +1739502699.8642347,60.1199426651001,13.032266233659133,1739502699.8642373,60.1199426651001,0.1018196965091338,1739502699.864241,60.1199426651001,99.46390290185593,1739502699.864244,60.1199426651001,7.120468821450745,1739502699.8642452,60.1199426651001,-0.015707488095038337,1739502699.8642473,60.1199426651001,-3.1217151616702887,1739502699.8642485,60.1199426651001,-0.008095504882811322,1739502699.8642507,60.1199426651001,-0.001778256540267089,1739502699.864252,60.1199426651001,2.483861306991412,1739502699.8642538,60.1199426651001,0.0,1739502699.864255,60.1199426651001,0.11216315620067263,1739502699.864257,60.1199426651001,3.1628392567242636,1739502699.8642583,60.1199426651001,2.3716981507907393 +1739502699.8841434,60.13994264602661,12.770849688226065,1739502699.8841455,60.13994264602661,0.09615099078000888,1739502699.8841486,60.13994264602661,99.89258072016068,1739502699.8841512,60.13994264602661,6.667745718750699,1739502699.8841527,60.13994264602661,-0.018,1739502699.8841543,60.13994264602661,-3.122891074365007,1739502699.8841558,60.13994264602661,-0.021365739817502914,1739502699.8841572,60.13994264602661,-0.004403777859854703,1739502699.8841584,60.13994264602661,2.4576316443815935,1739502699.88416,60.13994264602661,0.0,1739502699.8841612,60.13994264602661,0.05651585384870689,1739502699.884163,60.13994264602661,3.16379442670419,1739502699.884164,60.13994264602661,2.3837259971462603 +1739502699.9040778,60.159942626953125,12.770849688226065,1739502699.9040804,60.159942626953125,0.09615099078000888,1739502699.9040833,60.159942626953125,99.89258072016068,1739502699.9040859,60.159942626953125,6.667745718750699,1739502699.9040873,60.159942626953125,-0.018,1739502699.9040887,60.159942626953125,-3.122891074365007,1739502699.9040902,60.159942626953125,-0.021365739817502914,1739502699.9040914,60.159942626953125,-0.004403777859854703,1739502699.9040928,60.159942626953125,2.4576316443815935,1739502699.9040942,60.159942626953125,0.0,1739502699.9040954,60.159942626953125,0.07390564723533322,1739502699.904097,60.159942626953125,3.16379442670419,1739502699.9040983,60.159942626953125,2.3837259971462603 +1739502699.9241967,60.17994260787964,12.770849688226065,1739502699.9241993,60.17994260787964,0.09615099078000888,1739502699.9242022,60.17994260787964,99.89258072016068,1739502699.924205,60.17994260787964,6.667745718750699,1739502699.9242063,60.17994260787964,-0.018,1739502699.9242082,60.17994260787964,-3.122891074365007,1739502699.9242094,60.17994260787964,-0.021365739817502914,1739502699.9242108,60.17994260787964,-0.004403777859854703,1739502699.9242125,60.17994260787964,2.4576316443815935,1739502699.9242141,60.17994260787964,0.0,1739502699.9242153,60.17994260787964,0.07390564723533322,1739502699.9242167,60.17994260787964,3.16379442670419,1739502699.9242182,60.17994260787964,2.3837259971462603 +1739502699.9441595,60.19994258880615,12.770849688226065,1739502699.9441621,60.19994258880615,0.09615099078000888,1739502699.9441648,60.19994258880615,99.89258072016068,1739502699.9441679,60.19994258880615,6.667745718750699,1739502699.9441695,60.19994258880615,-0.018,1739502699.944171,60.19994258880615,-3.122891074365007,1739502699.9441726,60.19994258880615,-0.021365739817502914,1739502699.9441738,60.19994258880615,-0.004403777859854703,1739502699.944175,60.19994258880615,2.4576316443815935,1739502699.9441767,60.19994258880615,0.0,1739502699.944178,60.19994258880615,0.07390564723533322,1739502699.9441795,60.19994258880615,3.16379442670419,1739502699.9441807,60.19994258880615,2.3837259971462603 +1739502699.9641778,60.219942569732666,12.770849688226065,1739502699.9641807,60.219942569732666,0.09615099078000888,1739502699.9641836,60.219942569732666,99.89258072016068,1739502699.964187,60.219942569732666,6.667745718750699,1739502699.964188,60.219942569732666,-0.018,1739502699.9641902,60.219942569732666,-3.122891074365007,1739502699.9641914,60.219942569732666,-0.021365739817502914,1739502699.964193,60.219942569732666,-0.004403777859854703,1739502699.9641943,60.219942569732666,2.4576316443815935,1739502699.9641962,60.219942569732666,0.0,1739502699.9641974,60.219942569732666,0.07390564723533322,1739502699.9641986,60.219942569732666,3.16379442670419,1739502699.9642003,60.219942569732666,2.3837259971462603 +1739502699.9841256,60.23994255065918,12.508294359948373,1739502699.9841285,60.23994255065918,0.09020671977515615,1739502699.9841313,60.23994255065918,99.9172609210188,1739502699.9841342,60.23994255065918,6.626846321444638,1739502699.9841352,60.23994255065918,-0.018480765421712786,1739502699.984137,60.23994255065918,-3.1231150414837954,1739502699.9841383,60.23994255065918,-0.027525840460198767,1739502699.9841397,60.23994255065918,-0.006109200701590046,1739502699.984141,60.23994255065918,2.445550031794864,1739502699.9841425,60.23994255065918,0.0,1739502699.9841442,60.23994255065918,0.04453263182001264,1739502699.9841454,60.23994255065918,3.1647495966841164,1739502699.9841468,60.23994255065918,2.391838326639294 +1739502700.0041714,60.25994253158569,12.508294359948373,1739502700.0041735,60.25994253158569,0.09020671977515615,1739502700.0041764,60.25994253158569,99.9172609210188,1739502700.004179,60.25994253158569,6.626846321444638,1739502700.0041804,60.25994253158569,-0.018480765421712786,1739502700.004182,60.25994253158569,-3.1231150414837954,1739502700.0041833,60.25994253158569,-0.027525840460198767,1739502700.0041845,60.25994253158569,-0.006109200701590046,1739502700.0041864,60.25994253158569,2.445550031794864,1739502700.0041878,60.25994253158569,0.0,1739502700.0041893,60.25994253158569,0.05371170515556978,1739502700.0041904,60.25994253158569,3.1647495966841164,1739502700.0041916,60.25994253158569,2.391838326639294 +1739502700.0241888,60.27994251251221,12.508294359948373,1739502700.0241914,60.27994251251221,0.09020671977515615,1739502700.0241947,60.27994251251221,99.9172609210188,1739502700.0241978,60.27994251251221,6.626846321444638,1739502700.0241995,60.27994251251221,-0.018480765421712786,1739502700.0242014,60.27994251251221,-3.1231150414837954,1739502700.0242028,60.27994251251221,-0.027525840460198767,1739502700.0242043,60.27994251251221,-0.006109200701590046,1739502700.024206,60.27994251251221,2.445550031794864,1739502700.0242078,60.27994251251221,0.0,1739502700.0242095,60.27994251251221,0.05371170515556978,1739502700.024211,60.27994251251221,3.1647495966841164,1739502700.0242128,60.27994251251221,2.391838326639294 +1739502700.044161,60.29994249343872,12.508294359948373,1739502700.0441635,60.29994249343872,0.09020671977515615,1739502700.0441666,60.29994249343872,99.9172609210188,1739502700.0441697,60.29994249343872,6.626846321444638,1739502700.0441713,60.29994249343872,-0.018480765421712786,1739502700.044173,60.29994249343872,-3.1231150414837954,1739502700.0441747,60.29994249343872,-0.027525840460198767,1739502700.044176,60.29994249343872,-0.006109200701590046,1739502700.0441773,60.29994249343872,2.445550031794864,1739502700.0441792,60.29994249343872,0.0,1739502700.0441806,60.29994249343872,0.05371170515556978,1739502700.0441825,60.29994249343872,3.1647495966841164,1739502700.044184,60.29994249343872,2.391838326639294 +1739502700.0666747,60.319942474365234,12.508294359948373,1739502700.0666783,60.319942474365234,0.09020671977515615,1739502700.066683,60.319942474365234,99.9172609210188,1739502700.0666888,60.319942474365234,6.626846321444638,1739502700.0666916,60.319942474365234,-0.018480765421712786,1739502700.0666957,60.319942474365234,-3.1231150414837954,1739502700.0666993,60.319942474365234,-0.027525840460198767,1739502700.0667028,60.319942474365234,-0.006109200701590046,1739502700.0667064,60.319942474365234,2.445550031794864,1739502700.06671,60.319942474365234,0.0,1739502700.0667136,60.319942474365234,0.05371170515556978,1739502700.0667174,60.319942474365234,3.1647495966841164,1739502700.066721,60.319942474365234,2.391838326639294 +1739502700.0842612,60.33994245529175,12.508294359948373,1739502700.084264,60.33994245529175,0.09020671977515615,1739502700.084267,60.33994245529175,99.9172609210188,1739502700.0842698,60.33994245529175,6.626846321444638,1739502700.0842714,60.33994245529175,-0.018480765421712786,1739502700.0842733,60.33994245529175,-3.1231150414837954,1739502700.084275,60.33994245529175,-0.027525840460198767,1739502700.0842762,60.33994245529175,-0.006109200701590046,1739502700.0842779,60.33994245529175,2.445550031794864,1739502700.0842793,60.33994245529175,0.0,1739502700.0842807,60.33994245529175,0.05371170515556978,1739502700.0842824,60.33994245529175,3.1647495966841164,1739502700.0842838,60.33994245529175,2.391838326639294 +1739502700.1043282,60.35994243621826,12.244988261261025,1739502700.1043313,60.35994243621826,0.08399383370388325,1739502700.1043346,60.35994243621826,100.28357824945135,1739502700.104338,60.35994243621826,6.249147432840361,1739502700.1043391,60.35994243621826,-0.020668372175776512,1739502700.104341,60.35994243621826,-3.1241386249636616,1739502700.1043425,60.35994243621826,-0.03992660115256156,1739502700.1043441,60.35994243621826,-0.008526874876184148,1739502700.1043453,60.35994243621826,2.4214086339059766,1739502700.1043472,60.35994243621826,0.0,1739502700.1043484,60.35994243621826,0.010309546057800364,1739502700.10435,60.35994243621826,3.1657047666640428,1739502700.1043518,60.35994243621826,2.397535904237407 +1739502700.1247442,60.379942417144775,12.244988261261025,1739502700.1247468,60.379942417144775,0.08399383370388325,1739502700.1247504,60.379942417144775,100.28357824945135,1739502700.1247535,60.379942417144775,6.249147432840361,1739502700.1247551,60.379942417144775,-0.020668372175776512,1739502700.124757,60.379942417144775,-3.1241386249636616,1739502700.1247585,60.379942417144775,-0.03992660115256156,1739502700.1247602,60.379942417144775,-0.008526874876184148,1739502700.1247616,60.379942417144775,2.4214086339059766,1739502700.1247635,60.379942417144775,0.0,1739502700.124765,60.379942417144775,0.02387272966856946,1739502700.1247663,60.379942417144775,3.1657047666640428,1739502700.124768,60.379942417144775,2.397535904237407 +1739502700.1447368,60.39994239807129,12.244988261261025,1739502700.1447399,60.39994239807129,0.08399383370388325,1739502700.144744,60.39994239807129,100.28357824945135,1739502700.1447473,60.39994239807129,6.249147432840361,1739502700.1447487,60.39994239807129,-0.020668372175776512,1739502700.144751,60.39994239807129,-3.1241386249636616,1739502700.1447527,60.39994239807129,-0.03992660115256156,1739502700.1447544,60.39994239807129,-0.008526874876184148,1739502700.1447556,60.39994239807129,2.4214086339059766,1739502700.1447575,60.39994239807129,0.0,1739502700.1447597,60.39994239807129,0.02387272966856946,1739502700.1447613,60.39994239807129,3.1657047666640428,1739502700.144763,60.39994239807129,2.397535904237407 +1739502700.1649227,60.4199423789978,12.244988261261025,1739502700.1649265,60.4199423789978,0.08399383370388325,1739502700.16493,60.4199423789978,100.28357824945135,1739502700.1649334,60.4199423789978,6.249147432840361,1739502700.1649349,60.4199423789978,-0.020668372175776512,1739502700.164937,60.4199423789978,-3.1241386249636616,1739502700.1649387,60.4199423789978,-0.03992660115256156,1739502700.1649404,60.4199423789978,-0.008526874876184148,1739502700.164942,60.4199423789978,2.4214086339059766,1739502700.1649442,60.4199423789978,0.0,1739502700.1649456,60.4199423789978,0.02387272966856946,1739502700.1649475,60.4199423789978,3.1657047666640428,1739502700.1649492,60.4199423789978,2.397535904237407 +1739502700.1844833,60.439942359924316,12.244988261261025,1739502700.1844866,60.439942359924316,0.08399383370388325,1739502700.1844897,60.439942359924316,100.28357824945135,1739502700.184493,60.439942359924316,6.249147432840361,1739502700.1844945,60.439942359924316,-0.020668372175776512,1739502700.1844966,60.439942359924316,-3.1241386249636616,1739502700.184498,60.439942359924316,-0.03992660115256156,1739502700.1844997,60.439942359924316,-0.008526874876184148,1739502700.1845012,60.439942359924316,2.4214086339059766,1739502700.184503,60.439942359924316,0.0,1739502700.1845047,60.439942359924316,0.02387272966856946,1739502700.1845064,60.439942359924316,3.1657047666640428,1739502700.1845078,60.439942359924316,2.397535904237407 +1739502700.2045648,60.45994234085083,11.98120171574094,1739502700.204568,60.45994234085083,0.07751753271893502,1739502700.2045715,60.45994234085083,100.5228570618227,1739502700.2045743,60.45994234085083,6.004606209213242,1739502700.2045763,60.45994234085083,-0.021929572136914426,1739502700.2045784,60.45994234085083,-3.124954765299653,1739502700.2045798,60.45994234085083,-0.05038545993354473,1739502700.2045813,60.45994234085083,-0.010830203224755112,1739502700.204583,60.45994234085083,2.401233020405122,1739502700.2045846,60.45994234085083,0.0,1739502700.2045863,60.45994234085083,-0.009305071445733925,1739502700.204588,60.45994234085083,3.166659936643969,1739502700.2045896,60.45994234085083,2.4001700222048 +1739502700.224465,60.479942321777344,11.98120171574094,1739502700.2244675,60.479942321777344,0.07751753271893502,1739502700.2244709,60.479942321777344,100.5228570618227,1739502700.2244742,60.479942321777344,6.004606209213242,1739502700.2244756,60.479942321777344,-0.021929572136914426,1739502700.2244778,60.479942321777344,-3.124954765299653,1739502700.2244792,60.479942321777344,-0.05038545993354473,1739502700.2244809,60.479942321777344,-0.010830203224755112,1739502700.2244823,60.479942321777344,2.401233020405122,1739502700.2244842,60.479942321777344,0.0,1739502700.2244856,60.479942321777344,0.001062998200322074,1739502700.224487,60.479942321777344,3.166659936643969,1739502700.224489,60.479942321777344,2.4001700222048 +1739502700.2443173,60.49994230270386,11.98120171574094,1739502700.24432,60.49994230270386,0.07751753271893502,1739502700.244323,60.49994230270386,100.5228570618227,1739502700.2443264,60.49994230270386,6.004606209213242,1739502700.244328,60.49994230270386,-0.021929572136914426,1739502700.24433,60.49994230270386,-3.124954765299653,1739502700.2443316,60.49994230270386,-0.05038545993354473,1739502700.244333,60.49994230270386,-0.010830203224755112,1739502700.2443347,60.49994230270386,2.401233020405122,1739502700.2443364,60.49994230270386,0.0,1739502700.244338,60.49994230270386,0.001062998200322074,1739502700.2443397,60.49994230270386,3.166659936643969,1739502700.2443411,60.49994230270386,2.4001700222048 +1739502700.2651584,60.51994228363037,11.98120171574094,1739502700.2651618,60.51994228363037,0.07751753271893502,1739502700.2651658,60.51994228363037,100.5228570618227,1739502700.2651694,60.51994228363037,6.004606209213242,1739502700.2651715,60.51994228363037,-0.021929572136914426,1739502700.2651737,60.51994228363037,-3.124954765299653,1739502700.2651756,60.51994228363037,-0.05038545993354473,1739502700.2651772,60.51994228363037,-0.010830203224755112,1739502700.265179,60.51994228363037,2.401233020405122,1739502700.2651813,60.51994228363037,0.0,1739502700.2651827,60.51994228363037,0.001062998200322074,1739502700.2651842,60.51994228363037,3.166659936643969,1739502700.265186,60.51994228363037,2.4001700222048 +1739502700.2845328,60.539942264556885,11.98120171574094,1739502700.284536,60.539942264556885,0.07751753271893502,1739502700.2845395,60.539942264556885,100.5228570618227,1739502700.2845428,60.539942264556885,6.004606209213242,1739502700.2845442,60.539942264556885,-0.021929572136914426,1739502700.2845464,60.539942264556885,-3.124954765299653,1739502700.2845478,60.539942264556885,-0.05038545993354473,1739502700.2845495,60.539942264556885,-0.010830203224755112,1739502700.284551,60.539942264556885,2.401233020405122,1739502700.284553,60.539942264556885,0.0,1739502700.2845545,60.539942264556885,0.001062998200322074,1739502700.2845562,60.539942264556885,3.166659936643969,1739502700.2845576,60.539942264556885,2.4001700222048 +1739502700.3045008,60.5599422454834,11.98120171574094,1739502700.3045034,60.5599422454834,0.07751753271893502,1739502700.3045068,60.5599422454834,100.5228570618227,1739502700.30451,60.5599422454834,6.004606209213242,1739502700.3045118,60.5599422454834,-0.021929572136914426,1739502700.3045137,60.5599422454834,-3.124954765299653,1739502700.304516,60.5599422454834,-0.05038545993354473,1739502700.3045177,60.5599422454834,-0.010830203224755112,1739502700.3045192,60.5599422454834,2.401233020405122,1739502700.3045208,60.5599422454834,0.0,1739502700.3045225,60.5599422454834,0.001062998200322074,1739502700.304524,60.5599422454834,3.166659936643969,1739502700.3045256,60.5599422454834,2.4001700222048 +1739502700.324791,60.57994222640991,11.717282650855442,1739502700.3247936,60.57994222640991,0.07078575444751056,1739502700.3247972,60.57994222640991,100.67079260052253,1739502700.3248,60.57994222640991,5.85684915726137,1739502700.3248017,60.57994222640991,-0.022,1739502700.3248036,60.57994222640991,-3.1257614010326567,1739502700.324805,60.57994222640991,-0.0597313038065891,1739502700.3248067,60.57994222640991,-0.013353404712924885,1739502700.3248081,60.57994222640991,2.383346729589716,1739502700.32481,60.57994222640991,0.0,1739502700.3248115,60.57994222640991,-0.024823861100592426,1739502700.3248134,60.57994222640991,3.1676151066238956,1739502700.3248148,60.57994222640991,2.4000809418547857 +1739502700.344627,60.599942207336426,11.717282650855442,1739502700.3446295,60.599942207336426,0.07078575444751056,1739502700.3446333,60.599942207336426,100.67079260052253,1739502700.3446364,60.599942207336426,5.85684915726137,1739502700.344638,60.599942207336426,-0.022,1739502700.3446403,60.599942207336426,-3.1257614010326567,1739502700.3446417,60.599942207336426,-0.0597313038065891,1739502700.3446434,60.599942207336426,-0.013353404712924885,1739502700.3446448,60.599942207336426,2.383346729589716,1739502700.3446467,60.599942207336426,0.0,1739502700.3446481,60.599942207336426,-0.016734212265069548,1739502700.34465,60.599942207336426,3.1676151066238956,1739502700.3446515,60.599942207336426,2.4000809418547857 +1739502700.3649287,60.61994218826294,11.717282650855442,1739502700.3649318,60.61994218826294,0.07078575444751056,1739502700.3649354,60.61994218826294,100.67079260052253,1739502700.3649387,60.61994218826294,5.85684915726137,1739502700.3649404,60.61994218826294,-0.022,1739502700.3649426,60.61994218826294,-3.1257614010326567,1739502700.3649445,60.61994218826294,-0.0597313038065891,1739502700.364946,60.61994218826294,-0.013353404712924885,1739502700.3649476,60.61994218826294,2.383346729589716,1739502700.3649492,60.61994218826294,0.0,1739502700.3649511,60.61994218826294,-0.016734212265069548,1739502700.3649528,60.61994218826294,3.1676151066238956,1739502700.3649547,60.61994218826294,2.4000809418547857 +1739502700.3889248,60.63994216918945,11.717282650855442,1739502700.3889332,60.63994216918945,0.07078575444751056,1739502700.3889434,60.63994216918945,100.67079260052253,1739502700.3889534,60.63994216918945,5.85684915726137,1739502700.388958,60.63994216918945,-0.022,1739502700.3889644,60.63994216918945,-3.1257614010326567,1739502700.3889692,60.63994216918945,-0.0597313038065891,1739502700.3889744,60.63994216918945,-0.013353404712924885,1739502700.388979,60.63994216918945,2.383346729589716,1739502700.3889847,60.63994216918945,0.0,1739502700.3889894,60.63994216918945,-0.016734212265069548,1739502700.3889945,60.63994216918945,3.1676151066238956,1739502700.3889997,60.63994216918945,2.4000809418547857 +1739502700.4089696,60.65994215011597,11.717282650855442,1739502700.4089777,60.65994215011597,0.07078575444751056,1739502700.408987,60.65994215011597,100.67079260052253,1739502700.4089968,60.65994215011597,5.85684915726137,1739502700.4090016,60.65994215011597,-0.022,1739502700.4090073,60.65994215011597,-3.1257614010326567,1739502700.4090126,60.65994215011597,-0.0597313038065891,1739502700.4090173,60.65994215011597,-0.013353404712924885,1739502700.4090219,60.65994215011597,2.383346729589716,1739502700.4090276,60.65994215011597,0.0,1739502700.4090323,60.65994215011597,-0.016734212265069548,1739502700.4090378,60.65994215011597,3.1676151066238956,1739502700.4090426,60.65994215011597,2.4000809418547857 +1739502700.4319165,60.67994213104248,11.45345385982394,1739502700.4319248,60.67994213104248,0.06380412366758303,1739502700.4319353,60.67994213104248,101.00232154603299,1739502700.4319453,60.67994213104248,5.528956726767972,1739502700.43195,60.67994213104248,-0.023,1739502700.431956,60.67994213104248,-3.1269419733694623,1739502700.4319613,60.67994213104248,-0.07303692597481282,1739502700.4319663,60.67994213104248,-0.015977300053280543,1739502700.4319708,60.67994213104248,2.3581117458605183,1739502700.431976,60.67994213104248,0.0,1739502700.4319813,60.67994213104248,-0.05079834555700273,1739502700.4319863,60.67994213104248,3.168570276603822,1739502700.4319918,60.67994213104248,2.398265042784354 +1739502700.454317,60.699942111968994,11.45345385982394,1739502700.4543257,60.699942111968994,0.06380412366758303,1739502700.4543357,60.699942111968994,101.00232154603299,1739502700.454346,60.699942111968994,5.528956726767972,1739502700.4543512,60.699942111968994,-0.023,1739502700.4543571,60.699942111968994,-3.1269419733694623,1739502700.4543624,60.699942111968994,-0.07303692597481282,1739502700.4543672,60.699942111968994,-0.015977300053280543,1739502700.454372,60.699942111968994,2.3581117458605183,1739502700.4543774,60.699942111968994,0.0,1739502700.4543824,60.699942111968994,-0.040153296923835846,1739502700.4543874,60.699942111968994,3.168570276603822,1739502700.4543927,60.699942111968994,2.398265042784354 +1739502700.4817638,60.71994209289551,11.45345385982394,1739502700.4817712,60.71994209289551,0.06380412366758303,1739502700.4817805,60.71994209289551,101.00232154603299,1739502700.4817896,60.71994209289551,5.528956726767972,1739502700.4817944,60.71994209289551,-0.023,1739502700.4817996,60.71994209289551,-3.1269419733694623,1739502700.4818044,60.71994209289551,-0.07303692597481282,1739502700.4818084,60.71994209289551,-0.015977300053280543,1739502700.4818127,60.71994209289551,2.3581117458605183,1739502700.481818,60.71994209289551,0.0,1739502700.481822,60.71994209289551,-0.040153296923835846,1739502700.4818265,60.71994209289551,3.168570276603822,1739502700.4818308,60.71994209289551,2.398265042784354 +1739502700.4995384,60.74994206428528,11.45345385982394,1739502700.499542,60.74994206428528,0.06380412366758303,1739502700.4995465,60.74994206428528,101.00232154603299,1739502700.499551,60.74994206428528,5.528956726767972,1739502700.4995532,60.74994206428528,-0.023,1739502700.4995558,60.74994206428528,-3.1269419733694623,1739502700.499558,60.74994206428528,-0.07303692597481282,1739502700.49956,60.74994206428528,-0.015977300053280543,1739502700.4995623,60.74994206428528,2.3581117458605183,1739502700.499565,60.74994206428528,0.0,1739502700.4995668,60.74994206428528,-0.040153296923835846,1739502700.499569,60.74994206428528,3.168570276603822,1739502700.499571,60.74994206428528,2.398265042784354 +1739502700.5168912,60.76994204521179,11.45345385982394,1739502700.5168934,60.76994204521179,0.06380412366758303,1739502700.516897,60.76994204521179,101.00232154603299,1739502700.5168998,60.76994204521179,5.528956726767972,1739502700.5169015,60.76994204521179,-0.023,1739502700.5169032,60.76994204521179,-3.1269419733694623,1739502700.5169046,60.76994204521179,-0.07303692597481282,1739502700.516906,60.76994204521179,-0.015977300053280543,1739502700.5169075,60.76994204521179,2.3581117458605183,1739502700.5169091,60.76994204521179,0.0,1739502700.5169106,60.76994204521179,-0.040153296923835846,1739502700.516912,60.76994204521179,3.168570276603822,1739502700.5169134,60.76994204521179,2.398265042784354 +1739502700.53802,60.789942026138306,11.189984068248583,1739502700.538022,60.789942026138306,0.05658017475817889,1739502700.538025,60.789942026138306,101.4513854975948,1739502700.5380275,60.789942026138306,5.089111251272517,1739502700.5380287,60.789942026138306,-0.024,1739502700.5380304,60.789942026138306,-3.1283854467011167,1739502700.5380316,60.789942026138306,-0.08984351679937971,1739502700.538033,60.789942026138306,-0.018534579540481606,1739502700.5380342,60.789942026138306,2.326618482663202,1739502700.5380356,60.789942026138306,0.0,1739502700.5380368,60.789942026138306,-0.07926172618346299,1739502700.538038,60.789942026138306,3.1695254465837484,1739502700.5380394,60.789942026138306,2.3936588166900625 +1739502700.5567398,60.80994200706482,11.189984068248583,1739502700.5567422,60.80994200706482,0.05658017475817889,1739502700.556745,60.80994200706482,101.4513854975948,1739502700.5567477,60.80994200706482,5.089111251272517,1739502700.556749,60.80994200706482,-0.024,1739502700.5567508,60.80994200706482,-3.1283854467011167,1739502700.5567522,60.80994200706482,-0.08984351679937971,1739502700.5567536,60.80994200706482,-0.018534579540481606,1739502700.5567546,60.80994200706482,2.326618482663202,1739502700.5567563,60.80994200706482,0.0,1739502700.5567575,60.80994200706482,-0.06704033402686038,1739502700.556759,60.80994200706482,3.1695254465837484,1739502700.5567603,60.80994200706482,2.3936588166900625 +1739502700.5770512,60.82994198799133,11.189984068248583,1739502700.5770535,60.82994198799133,0.05658017475817889,1739502700.5770564,60.82994198799133,101.4513854975948,1739502700.577059,60.82994198799133,5.089111251272517,1739502700.5770605,60.82994198799133,-0.024,1739502700.5770624,60.82994198799133,-3.1283854467011167,1739502700.5770638,60.82994198799133,-0.08984351679937971,1739502700.577065,60.82994198799133,-0.018534579540481606,1739502700.5770662,60.82994198799133,2.326618482663202,1739502700.5770679,60.82994198799133,0.0,1739502700.577069,60.82994198799133,-0.06704033402686038,1739502700.5770702,60.82994198799133,3.1695254465837484,1739502700.5770717,60.82994198799133,2.3936588166900625 +1739502700.5965626,60.84994196891785,11.189984068248583,1739502700.5965648,60.84994196891785,0.05658017475817889,1739502700.5965676,60.84994196891785,101.4513854975948,1739502700.59657,60.84994196891785,5.089111251272517,1739502700.5965717,60.84994196891785,-0.024,1739502700.596573,60.84994196891785,-3.1283854467011167,1739502700.5965748,60.84994196891785,-0.08984351679937971,1739502700.596576,60.84994196891785,-0.018534579540481606,1739502700.5965772,60.84994196891785,2.326618482663202,1739502700.596579,60.84994196891785,0.0,1739502700.5965803,60.84994196891785,-0.06704033402686038,1739502700.596582,60.84994196891785,3.1695254465837484,1739502700.5965831,60.84994196891785,2.3936588166900625 +1739502700.6168778,60.86994194984436,11.189984068248583,1739502700.61688,60.86994194984436,0.05658017475817889,1739502700.6168828,60.86994194984436,101.4513854975948,1739502700.6168852,60.86994194984436,5.089111251272517,1739502700.6168866,60.86994194984436,-0.024,1739502700.6168883,60.86994194984436,-3.1283854467011167,1739502700.6168897,60.86994194984436,-0.08984351679937971,1739502700.6168911,60.86994194984436,-0.018534579540481606,1739502700.6168926,60.86994194984436,2.326618482663202,1739502700.6168942,60.86994194984436,0.0,1739502700.6168954,60.86994194984436,-0.06704033402686038,1739502700.616897,60.86994194984436,3.1695254465837484,1739502700.6168983,60.86994194984436,2.3936588166900625 +1739502700.6372528,60.889941930770874,11.189984068248583,1739502700.6372554,60.889941930770874,0.05658017475817889,1739502700.637259,60.889941930770874,101.4513854975948,1739502700.6372616,60.889941930770874,5.089111251272517,1739502700.637263,60.889941930770874,-0.024,1739502700.637265,60.889941930770874,-3.1283854467011167,1739502700.6372666,60.889941930770874,-0.08984351679937971,1739502700.637268,60.889941930770874,-0.018534579540481606,1739502700.6372695,60.889941930770874,2.326618482663202,1739502700.637271,60.889941930770874,0.0,1739502700.6372724,60.889941930770874,-0.06704033402686038,1739502700.6372738,60.889941930770874,3.1695254465837484,1739502700.637275,60.889941930770874,2.3936588166900625 +1739502700.657186,60.90994191169739,10.927177923122116,1739502700.6571894,60.90994191169739,0.049131025558600605,1739502700.6571925,60.90994191169739,101.79718483207785,1739502700.6571953,60.90994191169739,4.758478047276896,1739502700.6571968,60.90994191169739,-0.025,1739502700.6571987,60.90994191169739,-3.1295759468586892,1739502700.6571999,60.90994191169739,-0.10362898554056067,1739502700.657201,60.90994191169739,-0.020911512044356383,1739502700.6572025,60.90994191169739,2.3011006304262756,1739502700.657204,60.90994191169739,0.0,1739502700.6572056,60.90994191169739,-0.09313083506859844,1739502700.6572068,60.90994191169739,3.1704080990216457,1739502700.6572082,60.90994191169739,2.3860781785736194 +1739502700.6772764,60.9299418926239,10.927177923122116,1739502700.6772795,60.9299418926239,0.049131025558600605,1739502700.6772826,60.9299418926239,101.79718483207785,1739502700.6772854,60.9299418926239,4.758478047276896,1739502700.677287,60.9299418926239,-0.025,1739502700.6772888,60.9299418926239,-3.1295759468586892,1739502700.6772907,60.9299418926239,-0.10362898554056067,1739502700.677292,60.9299418926239,-0.020911512044356383,1739502700.6772933,60.9299418926239,2.3011006304262756,1739502700.6772952,60.9299418926239,0.0,1739502700.6772964,60.9299418926239,-0.08497754814734382,1739502700.6772978,60.9299418926239,3.1704080990216457,1739502700.6772995,60.9299418926239,2.3860781785736194 +1739502700.696938,60.949941873550415,10.927177923122116,1739502700.6969402,60.949941873550415,0.049131025558600605,1739502700.696943,60.949941873550415,101.79718483207785,1739502700.6969457,60.949941873550415,4.758478047276896,1739502700.696947,60.949941873550415,-0.025,1739502700.6969488,60.949941873550415,-3.1295759468586892,1739502700.6969502,60.949941873550415,-0.10362898554056067,1739502700.696952,60.949941873550415,-0.020911512044356383,1739502700.6969533,60.949941873550415,2.3011006304262756,1739502700.696955,60.949941873550415,0.0,1739502700.6969562,60.949941873550415,-0.08497754814734382,1739502700.6969573,60.949941873550415,3.1704080990216457,1739502700.696959,60.949941873550415,2.3860781785736194 +1739502700.717334,60.96994185447693,10.927177923122116,1739502700.7173362,60.96994185447693,0.049131025558600605,1739502700.7173388,60.96994185447693,101.79718483207785,1739502700.7173417,60.96994185447693,4.758478047276896,1739502700.717343,60.96994185447693,-0.025,1739502700.7173448,60.96994185447693,-3.1295759468586892,1739502700.7173457,60.96994185447693,-0.10362898554056067,1739502700.7173474,60.96994185447693,-0.020911512044356383,1739502700.7173486,60.96994185447693,2.3011006304262756,1739502700.7173502,60.96994185447693,0.0,1739502700.7173514,60.96994185447693,-0.08497754814734382,1739502700.7173526,60.96994185447693,3.1704080990216457,1739502700.717354,60.96994185447693,2.3860781785736194 +1739502700.741153,60.98994183540344,10.927177923122116,1739502700.7411618,60.98994183540344,0.049131025558600605,1739502700.7411726,60.98994183540344,101.79718483207785,1739502700.7411828,60.98994183540344,4.758478047276896,1739502700.7411876,60.98994183540344,-0.025,1739502700.7411938,60.98994183540344,-3.1295759468586892,1739502700.7411985,60.98994183540344,-0.10362898554056067,1739502700.7412035,60.98994183540344,-0.020911512044356383,1739502700.741208,60.98994183540344,2.3011006304262756,1739502700.7412133,60.98994183540344,0.0,1739502700.7412186,60.98994183540344,-0.08497754814734382,1739502700.7412236,60.98994183540344,3.1704080990216457,1739502700.7412288,60.98994183540344,2.3860781785736194 +1739502700.7619507,61.009941816329956,10.665282162575256,1739502700.7619588,61.009941816329956,0.041484292270824064,1739502700.761969,61.009941816329956,101.82835042758292,1739502700.7619793,61.009941816329956,4.745869984131076,1739502700.7619843,61.009941816329956,-0.025,1739502700.7619905,61.009941816329956,-3.130361555829668,1739502700.761996,61.009941816329956,-0.10888475082861918,1739502700.7620008,61.009941816329956,-0.023862018466605878,1739502700.7620056,61.009941816329956,2.291445706401838,1739502700.7620108,61.009941816329956,0.0,1739502700.7620158,61.009941816329956,-0.0855246869937631,1739502700.7620208,61.009941816329956,3.1712181493928826,1739502700.762026,61.009941816329956,2.376799412393991 +1739502700.7924173,61.02994179725647,10.665282162575256,1739502700.7924256,61.02994179725647,0.041484292270824064,1739502700.7924364,61.02994179725647,101.82835042758292,1739502700.7924466,61.02994179725647,4.745869984131076,1739502700.7924516,61.02994179725647,-0.025,1739502700.7924578,61.02994179725647,-3.130361555829668,1739502700.7924626,61.02994179725647,-0.10888475082861918,1739502700.7924674,61.02994179725647,-0.023862018466605878,1739502700.7924721,61.02994179725647,2.291445706401838,1739502700.7924776,61.02994179725647,0.0,1739502700.7924826,61.02994179725647,-0.0853537059921532,1739502700.7924879,61.02994179725647,3.1712181493928826,1739502700.7924929,61.02994179725647,2.376799412393991 +1739502700.8133056,61.05994176864624,10.665282162575256,1739502700.813314,61.05994176864624,0.041484292270824064,1739502700.8133247,61.05994176864624,101.82835042758292,1739502700.8133352,61.05994176864624,4.745869984131076,1739502700.8133402,61.05994176864624,-0.025,1739502700.8133469,61.05994176864624,-3.130361555829668,1739502700.813352,61.05994176864624,-0.10888475082861918,1739502700.813357,61.05994176864624,-0.023862018466605878,1739502700.8133616,61.05994176864624,2.291445706401838,1739502700.8133674,61.05994176864624,0.0,1739502700.813372,61.05994176864624,-0.0853537059921532,1739502700.8133776,61.05994176864624,3.1712181493928826,1739502700.8133826,61.05994176864624,2.376799412393991 +1739502700.8623586,61.09994173049927,10.665282162575256,1739502700.8623638,61.09994173049927,0.041484292270824064,1739502700.8623698,61.09994173049927,101.82835042758292,1739502700.8623753,61.09994173049927,4.745869984131076,1739502700.862378,61.09994173049927,-0.025,1739502700.8623812,61.09994173049927,-3.130361555829668,1739502700.862384,61.09994173049927,-0.10888475082861918,1739502700.8623867,61.09994173049927,-0.023862018466605878,1739502700.8623893,61.09994173049927,2.291445706401838,1739502700.8623927,61.09994173049927,0.0,1739502700.862395,61.09994173049927,-0.0853537059921532,1739502700.862398,61.09994173049927,3.1712181493928826,1739502700.8624008,61.09994173049927,2.376799412393991 +1739502700.8821187,61.11994171142578,10.404419540983893,1739502700.8821237,61.11994171142578,0.033673471421997725,1739502700.8821301,61.11994171142578,102.15350549412622,1739502700.8821359,61.11994171142578,4.439412591434963,1739502700.8821387,61.11994171142578,-0.025910356272047966,1739502700.882142,61.11994171142578,-3.1316040908609,1739502700.8821447,61.11994171142578,-0.1210532374258982,1739502700.8821473,61.11994171142578,-0.026125307513570874,1739502700.88215,61.11994171142578,2.2692471895556685,1739502700.8821533,61.11994171142578,0.0,1739502700.8821557,61.11994171142578,-0.10404730776454085,1739502700.8821585,61.11994171142578,3.17187549411445,1739502700.8821616,61.11994171142578,2.3674527429361856 +1739502700.9020333,61.14994168281555,10.404419540983893,1739502700.9020383,61.14994168281555,0.033673471421997725,1739502700.902044,61.14994168281555,102.15350549412622,1739502700.9020493,61.14994168281555,4.439412591434963,1739502700.9020522,61.14994168281555,-0.025910356272047966,1739502700.9020555,61.14994168281555,-3.1316040908609,1739502700.9020581,61.14994168281555,-0.1210532374258982,1739502700.9020607,61.14994168281555,-0.026125307513570874,1739502700.9020634,61.14994168281555,2.2692471895556685,1739502700.9020665,61.14994168281555,0.0,1739502700.902069,61.14994168281555,-0.09820555338051706,1739502700.9020717,61.14994168281555,3.17187549411445,1739502700.9020748,61.14994168281555,2.3674527429361856 +1739502700.9242573,61.169941663742065,10.404419540983893,1739502700.9242623,61.169941663742065,0.033673471421997725,1739502700.9242685,61.169941663742065,102.15350549412622,1739502700.924274,61.169941663742065,4.439412591434963,1739502700.924276,61.169941663742065,-0.025910356272047966,1739502700.9242797,61.169941663742065,-3.1316040908609,1739502700.9242823,61.169941663742065,-0.1210532374258982,1739502700.9242852,61.169941663742065,-0.026125307513570874,1739502700.9242878,61.169941663742065,2.2692471895556685,1739502700.9242911,61.169941663742065,0.0,1739502700.9242935,61.169941663742065,-0.09820555338051706,1739502700.9242964,61.169941663742065,3.17187549411445,1739502700.9242995,61.169941663742065,2.3674527429361856 +1739502700.9414723,61.18994164466858,10.404419540983893,1739502700.9414775,61.18994164466858,0.033673471421997725,1739502700.9414833,61.18994164466858,102.15350549412622,1739502700.941489,61.18994164466858,4.439412591434963,1739502700.9414914,61.18994164466858,-0.025910356272047966,1739502700.9414947,61.18994164466858,-3.1316040908609,1739502700.9414976,61.18994164466858,-0.1210532374258982,1739502700.9415007,61.18994164466858,-0.026125307513570874,1739502700.9415033,61.18994164466858,2.2692471895556685,1739502700.9415069,61.18994164466858,0.0,1739502700.9415095,61.18994164466858,-0.09820555338051706,1739502700.9415128,61.18994164466858,3.17187549411445,1739502700.9415164,61.18994164466858,2.3674527429361856 +1739502700.9606621,61.20994162559509,10.404419540983893,1739502700.9606657,61.20994162559509,0.033673471421997725,1739502700.9606698,61.20994162559509,102.15350549412622,1739502700.9606833,61.20994162559509,4.439412591434963,1739502700.960685,61.20994162559509,-0.025910356272047966,1739502700.9606879,61.20994162559509,-3.1316040908609,1739502700.96069,61.20994162559509,-0.1210532374258982,1739502700.9606917,61.20994162559509,-0.026125307513570874,1739502700.960694,61.20994162559509,2.2692471895556685,1739502700.9606962,61.20994162559509,0.0,1739502700.9606981,61.20994162559509,-0.09820555338051706,1739502700.9607003,61.20994162559509,3.17187549411445,1739502700.960702,61.20994162559509,2.3674527429361856 +1739502700.9802406,61.229941606521606,10.14467520191236,1739502700.980243,61.229941606521606,0.0257379665017492,1739502700.980246,61.229941606521606,103.02852885236695,1739502700.980249,61.229941606521606,3.5862671148040484,1739502700.9802504,61.229941606521606,-0.02648630087082637,1739502700.9802518,61.229941606521606,-3.1336298731560035,1739502700.9802532,61.229941606521606,-0.15006620290899422,1739502700.9802547,61.229941606521606,-0.026792186483575606,1739502700.980256,61.229941606521606,2.2171836614766987,1739502700.9802577,61.229941606521606,0.0,1739502700.9802592,61.229941606521606,-0.15804496509107224,1739502700.9802604,61.229941606521606,3.172438203758676,1739502700.9802618,61.229941606521606,2.3565287981476595 +1739502701.000042,61.24994158744812,10.14467520191236,1739502701.0000443,61.24994158744812,0.0257379665017492,1739502701.0000467,61.24994158744812,103.02852885236695,1739502701.000049,61.24994158744812,3.5862671148040484,1739502701.0000505,61.24994158744812,-0.02648630087082637,1739502701.000052,61.24994158744812,-3.1336298731560035,1739502701.0000532,61.24994158744812,-0.15006620290899422,1739502701.0000546,61.24994158744812,-0.026792186483575606,1739502701.0000556,61.24994158744812,2.2171836614766987,1739502701.000057,61.24994158744812,0.0,1739502701.0000582,61.24994158744812,-0.13934513667096082,1739502701.0000594,61.24994158744812,3.172438203758676,1739502701.0000606,61.24994158744812,2.3565287981476595 +1739502701.02053,61.269941568374634,10.14467520191236,1739502701.0205321,61.269941568374634,0.0257379665017492,1739502701.0205352,61.269941568374634,103.02852885236695,1739502701.0205376,61.269941568374634,3.5862671148040484,1739502701.0205388,61.269941568374634,-0.02648630087082637,1739502701.0205405,61.269941568374634,-3.1336298731560035,1739502701.0205417,61.269941568374634,-0.15006620290899422,1739502701.0205433,61.269941568374634,-0.026792186483575606,1739502701.0205443,61.269941568374634,2.2171836614766987,1739502701.0205457,61.269941568374634,0.0,1739502701.0205472,61.269941568374634,-0.13934513667096082,1739502701.0205483,61.269941568374634,3.172438203758676,1739502701.0205495,61.269941568374634,2.3565287981476595 +1739502701.0411117,61.28994154930115,10.14467520191236,1739502701.0411158,61.28994154930115,0.0257379665017492,1739502701.0411186,61.28994154930115,103.02852885236695,1739502701.0411217,61.28994154930115,3.5862671148040484,1739502701.0411232,61.28994154930115,-0.02648630087082637,1739502701.041125,61.28994154930115,-3.1336298731560035,1739502701.0411265,61.28994154930115,-0.15006620290899422,1739502701.0411282,61.28994154930115,-0.026792186483575606,1739502701.04113,61.28994154930115,2.2171836614766987,1739502701.0411315,61.28994154930115,0.0,1739502701.0411332,61.28994154930115,-0.13934513667096082,1739502701.0411346,61.28994154930115,3.172438203758676,1739502701.041136,61.28994154930115,2.3565287981476595 +1739502701.0806382,61.329941511154175,10.14467520191236,1739502701.0806417,61.329941511154175,0.0257379665017492,1739502701.0806448,61.329941511154175,103.02852885236695,1739502701.0806482,61.329941511154175,3.5862671148040484,1739502701.0806494,61.329941511154175,-0.02648630087082637,1739502701.0806515,61.329941511154175,-3.1336298731560035,1739502701.080653,61.329941511154175,-0.15006620290899422,1739502701.0806546,61.329941511154175,-0.026792186483575606,1739502701.080656,61.329941511154175,2.2171836614766987,1739502701.0806582,61.329941511154175,0.0,1739502701.0806594,61.329941511154175,-0.13934513667096082,1739502701.0806613,61.329941511154175,3.172438203758676,1739502701.080663,61.329941511154175,2.3565287981476595 +1739502701.1000218,61.34994149208069,9.886381535540163,1739502701.1000242,61.34994149208069,0.01770303361464798,1739502701.1000273,61.34994149208069,103.03472790035987,1739502701.10003,61.34994149208069,3.6113009637772526,1739502701.1000314,61.34994149208069,-0.02715826178424517,1739502701.1000333,61.34994149208069,-3.1344436567563823,1739502701.1000347,61.34994149208069,-0.15217210767934816,1739502701.1000361,61.34994149208069,-0.029677089052725106,1739502701.1000376,61.34994149208069,2.2134514641007943,1739502701.1000392,61.34994149208069,0.0,1739502701.1000404,61.34994149208069,-0.12204741063736417,1739502701.1000423,61.34994149208069,3.1729936317115612,1739502701.1000438,61.34994149208069,2.3409044176678075 +1739502701.1212947,61.3699414730072,9.886381535540163,1739502701.1212978,61.3699414730072,0.01770303361464798,1739502701.121301,61.3699414730072,103.03472790035987,1739502701.121304,61.3699414730072,3.6113009637772526,1739502701.1213057,61.3699414730072,-0.02715826178424517,1739502701.1213074,61.3699414730072,-3.1344436567563823,1739502701.1213093,61.3699414730072,-0.15217210767934816,1739502701.1213105,61.3699414730072,-0.029677089052725106,1739502701.1213117,61.3699414730072,2.2134514641007943,1739502701.1213136,61.3699414730072,0.0,1739502701.1213145,61.3699414730072,-0.12745295356701325,1739502701.1213162,61.3699414730072,3.1729936317115612,1739502701.1213176,61.3699414730072,2.3409044176678075 +1739502701.1416483,61.389941453933716,9.886381535540163,1739502701.141651,61.389941453933716,0.01770303361464798,1739502701.1416543,61.389941453933716,103.03472790035987,1739502701.1416569,61.389941453933716,3.6113009637772526,1739502701.1416583,61.389941453933716,-0.02715826178424517,1739502701.14166,61.389941453933716,-3.1344436567563823,1739502701.1416616,61.389941453933716,-0.15217210767934816,1739502701.1416633,61.389941453933716,-0.029677089052725106,1739502701.1416645,61.389941453933716,2.2134514641007943,1739502701.1416664,61.389941453933716,0.0,1739502701.1416676,61.389941453933716,-0.12745295356701325,1739502701.1416688,61.389941453933716,3.1729936317115612,1739502701.1416705,61.389941453933716,2.3409044176678075 +1739502701.1603968,61.40994143486023,9.886381535540163,1739502701.1603997,61.40994143486023,0.01770303361464798,1739502701.1604028,61.40994143486023,103.03472790035987,1739502701.1604054,61.40994143486023,3.6113009637772526,1739502701.160407,61.40994143486023,-0.02715826178424517,1739502701.1604087,61.40994143486023,-3.1344436567563823,1739502701.1604104,61.40994143486023,-0.15217210767934816,1739502701.1604118,61.40994143486023,-0.029677089052725106,1739502701.1604133,61.40994143486023,2.2134514641007943,1739502701.1604147,61.40994143486023,0.0,1739502701.1604164,61.40994143486023,-0.12745295356701325,1739502701.1604178,61.40994143486023,3.1729936317115612,1739502701.1604192,61.40994143486023,2.3409044176678075 +1739502701.1802843,61.42994141578674,9.886381535540163,1739502701.180287,61.42994141578674,0.01770303361464798,1739502701.18029,61.42994141578674,103.03472790035987,1739502701.1802926,61.42994141578674,3.6113009637772526,1739502701.180294,61.42994141578674,-0.02715826178424517,1739502701.180296,61.42994141578674,-3.1344436567563823,1739502701.1802971,61.42994141578674,-0.15217210767934816,1739502701.1802988,61.42994141578674,-0.029677089052725106,1739502701.1803,61.42994141578674,2.2134514641007943,1739502701.1803017,61.42994141578674,0.0,1739502701.1803029,61.42994141578674,-0.12745295356701325,1739502701.180304,61.42994141578674,3.1729936317115612,1739502701.1803057,61.42994141578674,2.3409044176678075 +1739502701.2001793,61.44994139671326,9.629710479534776,1739502701.200182,61.44994139671326,0.009586756207608182,1739502701.2001848,61.44994139671326,103.040888005704,1739502701.2001877,61.44994139671326,3.6330353550819114,1739502701.200189,61.44994139671326,-0.027369275292057394,1739502701.200191,61.44994139671326,-3.135429977959421,1739502701.2001927,61.44994139671326,-0.15391884093791575,1739502701.2001944,61.44994139671326,-0.032869877751817406,1739502701.2001956,61.44994139671326,2.21036057675519,1739502701.2001972,61.44994139671326,0.0,1739502701.2001987,61.44994139671326,-0.11166113339096377,1739502701.2002,61.44994139671326,3.1734250244478277,1739502701.2002017,61.44994139671326,2.3269566571867726 +1739502701.2199357,61.46994137763977,9.629710479534776,1739502701.2199383,61.46994137763977,0.009586756207608182,1739502701.2199416,61.46994137763977,103.040888005704,1739502701.2199442,61.46994137763977,3.6330353550819114,1739502701.2199454,61.46994137763977,-0.027369275292057394,1739502701.2199476,61.46994137763977,-3.135429977959421,1739502701.2199488,61.46994137763977,-0.15391884093791575,1739502701.2199504,61.46994137763977,-0.032869877751817406,1739502701.2199516,61.46994137763977,2.21036057675519,1739502701.2199533,61.46994137763977,0.0,1739502701.2199547,61.46994137763977,-0.11659608043158265,1739502701.2199562,61.46994137763977,3.1734250244478277,1739502701.2199578,61.46994137763977,2.3269566571867726 +1739502701.2414048,61.489941358566284,9.629710479534776,1739502701.2414074,61.489941358566284,0.009586756207608182,1739502701.2414105,61.489941358566284,103.040888005704,1739502701.2414136,61.489941358566284,3.6330353550819114,1739502701.2414153,61.489941358566284,-0.027369275292057394,1739502701.241417,61.489941358566284,-3.135429977959421,1739502701.2414186,61.489941358566284,-0.15391884093791575,1739502701.24142,61.489941358566284,-0.032869877751817406,1739502701.2414212,61.489941358566284,2.21036057675519,1739502701.2414234,61.489941358566284,0.0,1739502701.2414248,61.489941358566284,-0.11659608043158265,1739502701.2414265,61.489941358566284,3.1734250244478277,1739502701.241428,61.489941358566284,2.3269566571867726 +1739502701.262578,61.5099413394928,9.629710479534776,1739502701.262583,61.5099413394928,0.009586756207608182,1739502701.2625878,61.5099413394928,103.040888005704,1739502701.2625937,61.5099413394928,3.6330353550819114,1739502701.2625976,61.5099413394928,-0.027369275292057394,1739502701.262602,61.5099413394928,-3.135429977959421,1739502701.2626054,61.5099413394928,-0.15391884093791575,1739502701.262609,61.5099413394928,-0.032869877751817406,1739502701.2626128,61.5099413394928,2.21036057675519,1739502701.2626164,61.5099413394928,0.0,1739502701.26262,61.5099413394928,-0.11659608043158265,1739502701.262624,61.5099413394928,3.1734250244478277,1739502701.2626278,61.5099413394928,2.3269566571867726 +1739502701.2822456,61.52994132041931,9.629710479534776,1739502701.2822504,61.52994132041931,0.009586756207608182,1739502701.282256,61.52994132041931,103.040888005704,1739502701.282261,61.52994132041931,3.6330353550819114,1739502701.2822645,61.52994132041931,-0.027369275292057394,1739502701.2822685,61.52994132041931,-3.135429977959421,1739502701.2822714,61.52994132041931,-0.15391884093791575,1739502701.2822745,61.52994132041931,-0.032869877751817406,1739502701.282279,61.52994132041931,2.21036057675519,1739502701.2822824,61.52994132041931,0.0,1739502701.282286,61.52994132041931,-0.11659608043158265,1739502701.2822895,61.52994132041931,3.1734250244478277,1739502701.2822933,61.52994132041931,2.3269566571867726 +1739502701.2999656,61.549941301345825,9.629710479534776,1739502701.2999685,61.549941301345825,0.009586756207608182,1739502701.2999713,61.549941301345825,103.040888005704,1739502701.2999742,61.549941301345825,3.6330353550819114,1739502701.2999754,61.549941301345825,-0.027369275292057394,1739502701.2999773,61.549941301345825,-3.135429977959421,1739502701.2999787,61.549941301345825,-0.15391884093791575,1739502701.29998,61.549941301345825,-0.032869877751817406,1739502701.2999814,61.549941301345825,2.21036057675519,1739502701.299983,61.549941301345825,0.0,1739502701.2999845,61.549941301345825,-0.11659608043158265,1739502701.299986,61.549941301345825,3.1734250244478277,1739502701.2999873,61.549941301345825,2.3269566571867726 +1739502701.3205235,61.56994128227234,9.374505712917289,1739502701.3205264,61.56994128227234,0.0014281594606737613,1739502701.3205295,61.56994128227234,103.04701292010283,1739502701.320532,61.56994128227234,3.652241720556503,1739502701.3205335,61.56994128227234,-0.027555744859771872,1739502701.320535,61.56994128227234,-3.13652758555049,1739502701.3205366,61.56994128227234,-0.15461784762539457,1739502701.3205378,61.56994128227234,-0.03626208490863744,1739502701.3205392,61.56994128227234,2.209124876832482,1739502701.3205407,61.56994128227234,0.0,1739502701.3205419,61.56994128227234,-0.09997004987754195,1739502701.3205435,61.56994128227234,3.173681061413053,1739502701.320545,61.56994128227234,2.314290564664687 +1739502701.3401496,61.58994126319885,9.374505712917289,1739502701.3401525,61.58994126319885,0.0014281594606737613,1739502701.3401554,61.58994126319885,103.04701292010283,1739502701.3401585,61.58994126319885,3.652241720556503,1739502701.3401597,61.58994126319885,-0.027555744859771872,1739502701.3401618,61.58994126319885,-3.13652758555049,1739502701.3401632,61.58994126319885,-0.15461784762539457,1739502701.3401647,61.58994126319885,-0.03626208490863744,1739502701.3401659,61.58994126319885,2.209124876832482,1739502701.3401678,61.58994126319885,0.0,1739502701.340169,61.58994126319885,-0.10516568783220537,1739502701.3401701,61.58994126319885,3.173681061413053,1739502701.3401718,61.58994126319885,2.314290564664687 +1739502701.3613017,61.609941244125366,9.374505712917289,1739502701.3613043,61.609941244125366,0.0014281594606737613,1739502701.3613071,61.609941244125366,103.04701292010283,1739502701.36131,61.609941244125366,3.652241720556503,1739502701.3613112,61.609941244125366,-0.027555744859771872,1739502701.361313,61.609941244125366,-3.13652758555049,1739502701.3613145,61.609941244125366,-0.15461784762539457,1739502701.3613157,61.609941244125366,-0.03626208490863744,1739502701.3613172,61.609941244125366,2.209124876832482,1739502701.361319,61.609941244125366,0.0,1739502701.3613205,61.609941244125366,-0.10516568783220537,1739502701.361322,61.609941244125366,3.173681061413053,1739502701.3613234,61.609941244125366,2.314290564664687 +1739502701.3800433,61.62994122505188,9.374505712917289,1739502701.3800461,61.62994122505188,0.0014281594606737613,1739502701.380049,61.62994122505188,103.04701292010283,1739502701.3800523,61.62994122505188,3.652241720556503,1739502701.3800535,61.62994122505188,-0.027555744859771872,1739502701.3800552,61.62994122505188,-3.13652758555049,1739502701.3800569,61.62994122505188,-0.15461784762539457,1739502701.3800583,61.62994122505188,-0.03626208490863744,1739502701.3800597,61.62994122505188,2.209124876832482,1739502701.3800611,61.62994122505188,0.0,1739502701.3800626,61.62994122505188,-0.10516568783220537,1739502701.3800642,61.62994122505188,3.173681061413053,1739502701.3800654,61.62994122505188,2.314290564664687 +1739502701.4004653,61.649941205978394,9.374505712917289,1739502701.4004674,61.649941205978394,0.0014281594606737613,1739502701.4004703,61.649941205978394,103.04701292010283,1739502701.400473,61.649941205978394,3.652241720556503,1739502701.4004748,61.649941205978394,-0.027555744859771872,1739502701.4004765,61.649941205978394,-3.13652758555049,1739502701.400478,61.649941205978394,-0.15461784762539457,1739502701.4004793,61.649941205978394,-0.03626208490863744,1739502701.4004805,61.649941205978394,2.209124876832482,1739502701.400482,61.649941205978394,0.0,1739502701.4004838,61.649941205978394,-0.10516568783220537,1739502701.4004853,61.649941205978394,3.173681061413053,1739502701.400487,61.649941205978394,2.314290564664687 +1739502701.420704,61.66994118690491,9.120643285517101,1739502701.4207067,61.66994118690491,-0.0067416131660067435,1739502701.42071,61.66994118690491,103.32885173134603,1739502701.4207127,61.66994118690491,3.3937226989825455,1739502701.420714,61.66994118690491,-0.016133465636399294,1739502701.420716,61.66994118690491,-3.1399527069712017,1739502701.4207175,61.66994118690491,-0.175312025366504,1739502701.4207187,61.66994118690491,-0.04104897646177483,1739502701.4207199,61.66994118690491,2.1728531325597893,1739502701.4207218,61.66994118690491,0.0,1739502701.420723,61.66994118690491,-0.14118164113590503,1739502701.4207244,61.66994118690491,3.1738492604057638,1739502701.420726,61.66994118690491,2.30277978090894 +1739502701.4422975,61.68994116783142,9.120643285517101,1739502701.4423,61.68994116783142,-0.0067416131660067435,1739502701.442303,61.68994116783142,103.32885173134603,1739502701.4423058,61.68994116783142,3.3937226989825455,1739502701.4423072,61.68994116783142,-0.016133465636399294,1739502701.4423094,61.68994116783142,-3.1399527069712017,1739502701.4423106,61.68994116783142,-0.175312025366504,1739502701.4423122,61.68994116783142,-0.04104897646177483,1739502701.4423134,61.68994116783142,2.1728531325597893,1739502701.4423153,61.68994116783142,0.0,1739502701.4423165,61.68994116783142,-0.12992664834915058,1739502701.442318,61.68994116783142,3.1738492604057638,1739502701.4423196,61.68994116783142,2.30277978090894 +1739502701.4617782,61.709941148757935,9.120643285517101,1739502701.4617822,61.709941148757935,-0.0067416131660067435,1739502701.4617875,61.709941148757935,103.32885173134603,1739502701.4617927,61.709941148757935,3.3937226989825455,1739502701.4617956,61.709941148757935,-0.016133465636399294,1739502701.4617994,61.709941148757935,-3.1399527069712017,1739502701.461803,61.709941148757935,-0.175312025366504,1739502701.4618063,61.709941148757935,-0.04104897646177483,1739502701.4618104,61.709941148757935,2.1728531325597893,1739502701.461814,61.709941148757935,0.0,1739502701.4618175,61.709941148757935,-0.12992664834915058,1739502701.4618208,61.709941148757935,3.1738492604057638,1739502701.4618244,61.709941148757935,2.30277978090894 +1739502701.4826205,61.72994112968445,9.120643285517101,1739502701.4826248,61.72994112968445,-0.0067416131660067435,1739502701.4826295,61.72994112968445,103.32885173134603,1739502701.4826355,61.72994112968445,3.3937226989825455,1739502701.4826386,61.72994112968445,-0.016133465636399294,1739502701.4826424,61.72994112968445,-3.1399527069712017,1739502701.482646,61.72994112968445,-0.175312025366504,1739502701.4826496,61.72994112968445,-0.04104897646177483,1739502701.482653,61.72994112968445,2.1728531325597893,1739502701.4826565,61.72994112968445,0.0,1739502701.48266,61.72994112968445,-0.12992664834915058,1739502701.4826636,61.72994112968445,3.1738492604057638,1739502701.4826674,61.72994112968445,2.30277978090894 +1739502701.501946,61.74994111061096,9.120643285517101,1739502701.5019488,61.74994111061096,-0.0067416131660067435,1739502701.501952,61.74994111061096,103.32885173134603,1739502701.5019546,61.74994111061096,3.3937226989825455,1739502701.501956,61.74994111061096,-0.016133465636399294,1739502701.501958,61.74994111061096,-3.1399527069712017,1739502701.5019593,61.74994111061096,-0.175312025366504,1739502701.5019608,61.74994111061096,-0.04104897646177483,1739502701.5019622,61.74994111061096,2.1728531325597893,1739502701.501964,61.74994111061096,0.0,1739502701.5019655,61.74994111061096,-0.12992664834915058,1739502701.5019674,61.74994111061096,3.1738492604057638,1739502701.5019686,61.74994111061096,2.30277978090894 +1739502701.5202477,61.769941091537476,9.120643285517101,1739502701.52025,61.769941091537476,-0.0067416131660067435,1739502701.520253,61.769941091537476,103.32885173134603,1739502701.5202558,61.769941091537476,3.3937226989825455,1739502701.5202572,61.769941091537476,-0.016133465636399294,1739502701.520259,61.769941091537476,-3.1399527069712017,1739502701.52026,61.769941091537476,-0.175312025366504,1739502701.5202613,61.769941091537476,-0.04104897646177483,1739502701.5202627,61.769941091537476,2.1728531325597893,1739502701.5202641,61.769941091537476,0.0,1739502701.5202656,61.769941091537476,-0.12992664834915058,1739502701.5202668,61.769941091537476,3.1738492604057638,1739502701.520268,61.769941091537476,2.30277978090894 +1739502701.5405056,61.78994107246399,8.868202713299336,1739502701.5405083,61.78994107246399,-0.014886570745307637,1739502701.540511,61.78994107246399,104.12859181094454,1739502701.5405138,61.78994107246399,2.623895685164623,1739502701.5405152,61.78994107246399,0.022616502646341925,1739502701.5405169,61.78994107246399,3.1355867633764083,1739502701.540518,61.78994107246399,-0.23858969725259252,1739502701.5405197,61.78994107246399,-0.046988677976556426,1739502701.540521,61.78994107246399,2.065596350009202,1739502701.5405226,61.78994107246399,0.0,1739502701.5405238,61.78994107246399,-0.2649233038989893,1739502701.5405252,61.78994107246399,3.1738045323924147,1739502701.5405269,61.78994107246399,2.288333171389253 +1739502701.560215,61.8099410533905,8.868202713299336,1739502701.5602174,61.8099410533905,-0.014886570745307637,1739502701.5602202,61.8099410533905,104.12859181094454,1739502701.5602226,61.8099410533905,2.623895685164623,1739502701.560224,61.8099410533905,0.022616502646341925,1739502701.5602257,61.8099410533905,3.1355867633764083,1739502701.5602272,61.8099410533905,-0.23858969725259252,1739502701.5602283,61.8099410533905,-0.046988677976556426,1739502701.5602295,61.8099410533905,2.065596350009202,1739502701.5602312,61.8099410533905,0.0,1739502701.5602324,61.8099410533905,-0.22273682138005135,1739502701.560234,61.8099410533905,3.1738045323924147,1739502701.5602355,61.8099410533905,2.288333171389253 +1739502701.5814455,61.82994103431702,8.868202713299336,1739502701.5814486,61.82994103431702,-0.014886570745307637,1739502701.581452,61.82994103431702,104.12859181094454,1739502701.5814543,61.82994103431702,2.623895685164623,1739502701.5814557,61.82994103431702,0.022616502646341925,1739502701.5814574,61.82994103431702,3.1355867633764083,1739502701.5814593,61.82994103431702,-0.23858969725259252,1739502701.581461,61.82994103431702,-0.046988677976556426,1739502701.5814626,61.82994103431702,2.065596350009202,1739502701.5814643,61.82994103431702,0.0,1739502701.5814655,61.82994103431702,-0.22273682138005135,1739502701.5814672,61.82994103431702,3.1738045323924147,1739502701.5814693,61.82994103431702,2.288333171389253 +1739502701.60046,61.84994101524353,8.868202713299336,1739502701.600465,61.84994101524353,-0.014886570745307637,1739502701.6004715,61.84994101524353,104.12859181094454,1739502701.6004772,61.84994101524353,2.623895685164623,1739502701.6004803,61.84994101524353,0.022616502646341925,1739502701.6004848,61.84994101524353,3.1355867633764083,1739502701.6004913,61.84994101524353,-0.23858969725259252,1739502701.6004963,61.84994101524353,-0.046988677976556426,1739502701.6004994,61.84994101524353,2.065596350009202,1739502701.6005025,61.84994101524353,0.0,1739502701.600505,61.84994101524353,-0.22273682138005135,1739502701.6005085,61.84994101524353,3.1738045323924147,1739502701.6005123,61.84994101524353,2.288333171389253 +1739502701.620772,61.869940996170044,8.868202713299336,1739502701.620775,61.869940996170044,-0.014886570745307637,1739502701.620778,61.869940996170044,104.12859181094454,1739502701.620781,61.869940996170044,2.623895685164623,1739502701.6207829,61.869940996170044,0.022616502646341925,1739502701.6207845,61.869940996170044,3.1355867633764083,1739502701.6207867,61.869940996170044,-0.23858969725259252,1739502701.6207883,61.869940996170044,-0.046988677976556426,1739502701.6207895,61.869940996170044,2.065596350009202,1739502701.620791,61.869940996170044,0.0,1739502701.6207926,61.869940996170044,-0.22273682138005135,1739502701.6207943,61.869940996170044,3.1738045323924147,1739502701.620796,61.869940996170044,2.288333171389253 +1739502701.6417458,61.88994097709656,8.617814452929174,1739502701.6417496,61.88994097709656,-0.022930510227708645,1739502701.6417522,61.88994097709656,104.15789528134735,1739502701.641755,61.88994097709656,2.6431525100232665,1739502701.6417568,61.88994097709656,0.02183050979496872,1739502701.6417587,61.88994097709656,3.1341009857696056,1739502701.6417603,61.88994097709656,-0.2355735983270846,1739502701.6417615,61.88994097709656,-0.05067520074821536,1739502701.6417627,61.88994097709656,2.0705864021299734,1739502701.6417644,61.88994097709656,0.0,1739502701.641766,61.88994097709656,-0.18015031159870168,1739502701.6417675,61.88994097709656,3.173538876254534,1739502701.641769,61.88994097709656,2.2640450067609437 +1739502701.660251,61.90994095802307,8.617814452929174,1739502701.6602535,61.90994095802307,-0.022930510227708645,1739502701.6602566,61.90994095802307,104.15789528134735,1739502701.6602592,61.90994095802307,2.6431525100232665,1739502701.660261,61.90994095802307,0.02183050979496872,1739502701.6602628,61.90994095802307,3.1341009857696056,1739502701.6602643,61.90994095802307,-0.2355735983270846,1739502701.6602654,61.90994095802307,-0.05067520074821536,1739502701.6602666,61.90994095802307,2.0705864021299734,1739502701.6602683,61.90994095802307,0.0,1739502701.6602697,61.90994095802307,-0.1934586046309703,1739502701.6602712,61.90994095802307,3.173538876254534,1739502701.6602726,61.90994095802307,2.2640450067609437 +1739502701.6805248,61.929940938949585,8.617814452929174,1739502701.6805277,61.929940938949585,-0.022930510227708645,1739502701.6805308,61.929940938949585,104.15789528134735,1739502701.6805336,61.929940938949585,2.6431525100232665,1739502701.680535,61.929940938949585,0.02183050979496872,1739502701.6805367,61.929940938949585,3.1341009857696056,1739502701.6805382,61.929940938949585,-0.2355735983270846,1739502701.6805394,61.929940938949585,-0.05067520074821536,1739502701.680541,61.929940938949585,2.0705864021299734,1739502701.6805425,61.929940938949585,0.0,1739502701.6805437,61.929940938949585,-0.1934586046309703,1739502701.6805456,61.929940938949585,3.173538876254534,1739502701.680547,61.929940938949585,2.2640450067609437 +1739502701.7025757,61.9499409198761,8.617814452929174,1739502701.7025797,61.9499409198761,-0.022930510227708645,1739502701.7025845,61.9499409198761,104.15789528134735,1739502701.7025902,61.9499409198761,2.6431525100232665,1739502701.702593,61.9499409198761,0.02183050979496872,1739502701.7025971,61.9499409198761,3.1341009857696056,1739502701.7026005,61.9499409198761,-0.2355735983270846,1739502701.702604,61.9499409198761,-0.05067520074821536,1739502701.7026076,61.9499409198761,2.0705864021299734,1739502701.7026114,61.9499409198761,0.0,1739502701.7026148,61.9499409198761,-0.1934586046309703,1739502701.7026184,61.9499409198761,3.173538876254534,1739502701.702622,61.9499409198761,2.2640450067609437 +1739502701.7206032,61.96994090080261,8.617814452929174,1739502701.7206056,61.96994090080261,-0.022930510227708645,1739502701.7206087,61.96994090080261,104.15789528134735,1739502701.7206113,61.96994090080261,2.6431525100232665,1739502701.7206128,61.96994090080261,0.02183050979496872,1739502701.7206147,61.96994090080261,3.1341009857696056,1739502701.7206163,61.96994090080261,-0.2355735983270846,1739502701.7206178,61.96994090080261,-0.05067520074821536,1739502701.720619,61.96994090080261,2.0705864021299734,1739502701.7206206,61.96994090080261,0.0,1739502701.7206218,61.96994090080261,-0.1934586046309703,1739502701.7206233,61.96994090080261,3.173538876254534,1739502701.720625,61.96994090080261,2.2640450067609437 +1739502701.7402809,61.989940881729126,8.617814452929174,1739502701.7402835,61.989940881729126,-0.022930510227708645,1739502701.7402868,61.989940881729126,104.15789528134735,1739502701.7402894,61.989940881729126,2.6431525100232665,1739502701.7402909,61.989940881729126,0.02183050979496872,1739502701.7402925,61.989940881729126,3.1341009857696056,1739502701.7402942,61.989940881729126,-0.2355735983270846,1739502701.7402954,61.989940881729126,-0.05067520074821536,1739502701.7402966,61.989940881729126,2.0705864021299734,1739502701.7402985,61.989940881729126,0.0,1739502701.7402997,61.989940881729126,-0.1934586046309703,1739502701.7403014,61.989940881729126,3.173538876254534,1739502701.740303,61.989940881729126,2.2640450067609437 +1739502701.7623854,62.00994086265564,8.369930236266711,1739502701.7623904,62.00994086265564,-0.030801322357739913,1739502701.7623951,62.00994086265564,104.18690560550898,1739502701.7624006,62.00994086265564,2.6559629708534813,1739502701.7624032,62.00994086265564,0.02130763384271505,1739502701.7624075,62.00994086265564,3.132473330836227,1739502701.7624106,62.00994086265564,-0.23189435084697807,1739502701.7624142,62.00994086265564,-0.05453708615722465,1739502701.7624176,62.00994086265564,2.0766899401360623,1739502701.7624216,62.00994086265564,0.0,1739502701.7624252,62.00994086265564,-0.1541578456448642,1739502701.7624288,62.00994086265564,3.1730665638141184,1739502701.7624323,62.00994086265564,2.2431292810164605 +1739502701.781255,62.02994084358215,8.369930236266711,1739502701.7812576,62.02994084358215,-0.030801322357739913,1739502701.7812612,62.02994084358215,104.18690560550898,1739502701.781264,62.02994084358215,2.6559629708534813,1739502701.7812655,62.02994084358215,0.02130763384271505,1739502701.7812674,62.02994084358215,3.132473330836227,1739502701.7812693,62.02994084358215,-0.23189435084697807,1739502701.7812705,62.02994084358215,-0.05453708615722465,1739502701.7812722,62.02994084358215,2.0766899401360623,1739502701.7812736,62.02994084358215,0.0,1739502701.7812748,62.02994084358215,-0.16643934088039813,1739502701.7812767,62.02994084358215,3.1730665638141184,1739502701.7812784,62.02994084358215,2.2431292810164605 +1739502701.800722,62.04994082450867,8.369930236266711,1739502701.8007245,62.04994082450867,-0.030801322357739913,1739502701.8007278,62.04994082450867,104.18690560550898,1739502701.8007305,62.04994082450867,2.6559629708534813,1739502701.8007317,62.04994082450867,0.02130763384271505,1739502701.8007333,62.04994082450867,3.132473330836227,1739502701.800735,62.04994082450867,-0.23189435084697807,1739502701.8007362,62.04994082450867,-0.05453708615722465,1739502701.8007379,62.04994082450867,2.0766899401360623,1739502701.8007393,62.04994082450867,0.0,1739502701.800741,62.04994082450867,-0.16643934088039813,1739502701.8007424,62.04994082450867,3.1730665638141184,1739502701.8007438,62.04994082450867,2.2431292810164605 +1739502701.822531,62.06994080543518,8.369930236266711,1739502701.8225348,62.06994080543518,-0.030801322357739913,1739502701.8225396,62.06994080543518,104.18690560550898,1739502701.8225446,62.06994080543518,2.6559629708534813,1739502701.8225477,62.06994080543518,0.02130763384271505,1739502701.8225513,62.06994080543518,3.132473330836227,1739502701.8225548,62.06994080543518,-0.23189435084697807,1739502701.8225582,62.06994080543518,-0.05453708615722465,1739502701.8225615,62.06994080543518,2.0766899401360623,1739502701.822565,62.06994080543518,0.0,1739502701.8225684,62.06994080543518,-0.16643934088039813,1739502701.822572,62.06994080543518,3.1730665638141184,1739502701.8225753,62.06994080543518,2.2431292810164605 +1739502701.8417106,62.089940786361694,8.369930236266711,1739502701.8417132,62.089940786361694,-0.030801322357739913,1739502701.8417163,62.089940786361694,104.18690560550898,1739502701.8417192,62.089940786361694,2.6559629708534813,1739502701.8417206,62.089940786361694,0.02130763384271505,1739502701.841722,62.089940786361694,3.132473330836227,1739502701.8417237,62.089940786361694,-0.23189435084697807,1739502701.8417249,62.089940786361694,-0.05453708615722465,1739502701.8417263,62.089940786361694,2.0766899401360623,1739502701.8417277,62.089940786361694,0.0,1739502701.8417299,62.089940786361694,-0.16643934088039813,1739502701.841731,62.089940786361694,3.1730665638141184,1739502701.8417323,62.089940786361694,2.2431292810164605 +1739502701.8620374,62.10994076728821,8.124222647036099,1739502701.862041,62.10994076728821,-0.03847148568167569,1739502701.862044,62.10994076728821,104.88175209184325,1739502701.8620467,62.10994076728821,1.9977105984038859,1739502701.862048,62.10994076728821,0.03377930458172987,1739502701.8620503,62.10994076728821,3.129800064189902,1739502701.8620515,62.10994076728821,-0.2612112719813868,1739502701.862053,62.10994076728821,-0.053434312234036344,1739502701.862054,62.10994076728821,2.028550937541699,1739502701.8620558,62.10994076728821,0.0,1739502701.8620572,62.10994076728821,-0.2099489891247374,1739502701.8620584,62.10994076728821,3.1724462380719687,1739502701.8620598,62.10994076728821,2.2249031526753407 +1739502701.8798704,62.12994074821472,8.124222647036099,1739502701.8798728,62.12994074821472,-0.03847148568167569,1739502701.8798761,62.12994074821472,104.88175209184325,1739502701.8798792,62.12994074821472,1.9977105984038859,1739502701.8798807,62.12994074821472,0.03377930458172987,1739502701.8798826,62.12994074821472,3.129800064189902,1739502701.8798838,62.12994074821472,-0.2612112719813868,1739502701.8798852,62.12994074821472,-0.053434312234036344,1739502701.8798866,62.12994074821472,2.028550937541699,1739502701.879888,62.12994074821472,0.0,1739502701.8798897,62.12994074821472,-0.19635221513364165,1739502701.8798912,62.12994074821472,3.1724462380719687,1739502701.8798926,62.12994074821472,2.2249031526753407 +1739502701.9008117,62.149940729141235,8.124222647036099,1739502701.9008143,62.149940729141235,-0.03847148568167569,1739502701.9008174,62.149940729141235,104.88175209184325,1739502701.9008203,62.149940729141235,1.9977105984038859,1739502701.9008214,62.149940729141235,0.03377930458172987,1739502701.9008234,62.149940729141235,3.129800064189902,1739502701.9008245,62.149940729141235,-0.2612112719813868,1739502701.9008257,62.149940729141235,-0.053434312234036344,1739502701.9008272,62.149940729141235,2.028550937541699,1739502701.9008286,62.149940729141235,0.0,1739502701.90083,62.149940729141235,-0.19635221513364165,1739502701.9008315,62.149940729141235,3.1724462380719687,1739502701.9008331,62.149940729141235,2.2249031526753407 +1739502701.9198618,62.16994071006775,8.124222647036099,1739502701.9198642,62.16994071006775,-0.03847148568167569,1739502701.919867,62.16994071006775,104.88175209184325,1739502701.91987,62.16994071006775,1.9977105984038859,1739502701.9198713,62.16994071006775,0.03377930458172987,1739502701.919873,62.16994071006775,3.129800064189902,1739502701.9198747,62.16994071006775,-0.2612112719813868,1739502701.9198759,62.16994071006775,-0.053434312234036344,1739502701.919877,62.16994071006775,2.028550937541699,1739502701.919879,62.16994071006775,0.0,1739502701.91988,62.16994071006775,-0.19635221513364165,1739502701.9198818,62.16994071006775,3.1724462380719687,1739502701.919883,62.16994071006775,2.2249031526753407 +1739502701.9470763,62.18994069099426,8.124222647036099,1739502701.9470842,62.18994069099426,-0.03847148568167569,1739502701.9470944,62.18994069099426,104.88175209184325,1739502701.9471045,62.18994069099426,1.9977105984038859,1739502701.9471097,62.18994069099426,0.03377930458172987,1739502701.9471161,62.18994069099426,3.129800064189902,1739502701.947121,62.18994069099426,-0.2612112719813868,1739502701.947126,62.18994069099426,-0.053434312234036344,1739502701.9471307,62.18994069099426,2.028550937541699,1739502701.9471362,62.18994069099426,0.0,1739502701.9471412,62.18994069099426,-0.19635221513364165,1739502701.9471464,62.18994069099426,3.1724462380719687,1739502701.9471517,62.18994069099426,2.2249031526753407 +1739502701.9662058,62.209940671920776,8.124222647036099,1739502701.9662142,62.209940671920776,-0.03847148568167569,1739502701.9662247,62.209940671920776,104.88175209184325,1739502701.9662352,62.209940671920776,1.9977105984038859,1739502701.96624,62.209940671920776,0.03377930458172987,1739502701.966246,62.209940671920776,3.129800064189902,1739502701.9662514,62.209940671920776,-0.2612112719813868,1739502701.9662561,62.209940671920776,-0.053434312234036344,1739502701.9662607,62.209940671920776,2.028550937541699,1739502701.9662664,62.209940671920776,0.0,1739502701.9662714,62.209940671920776,-0.19635221513364165,1739502701.9662766,62.209940671920776,3.1724462380719687,1739502701.9662817,62.209940671920776,2.2249031526753407 +1739502701.9938786,62.22994065284729,7.88069964354294,1739502701.9938872,62.22994065284729,-0.04591472666055818,1739502701.9938977,62.22994065284729,104.93168175080034,1739502701.9939077,62.22994065284729,1.9913158657676577,1739502701.9939125,62.22994065284729,0.03392463941437142,1739502701.9939187,62.22994065284729,3.1280369950167093,1739502701.993924,62.22994065284729,-0.25761320371896773,1739502701.9939287,62.22994065284729,-0.05702397820558603,1739502701.9939332,62.22994065284729,2.0343984411888116,1739502701.993939,62.22994065284729,0.0,1739502701.9939435,62.22994065284729,-0.1561861796751485,1739502701.9939487,62.22994065284729,3.1717888957377065,1739502701.9939537,62.22994065284729,2.2031365151744025 +1739502702.0123026,62.249940633773804,7.88069964354294,1739502702.0123107,62.249940633773804,-0.04591472666055818,1739502702.012321,62.249940633773804,104.93168175080034,1739502702.0123312,62.249940633773804,1.9913158657676577,1739502702.0123367,62.249940633773804,0.03392463941437142,1739502702.0123427,62.249940633773804,3.1280369950167093,1739502702.012348,62.249940633773804,-0.25761320371896773,1739502702.012353,62.249940633773804,-0.05702397820558603,1739502702.012358,62.249940633773804,2.0343984411888116,1739502702.0123637,62.249940633773804,0.0,1739502702.012369,62.249940633773804,-0.16873807398559082,1739502702.0123742,62.249940633773804,3.1717888957377065,1739502702.0123796,62.249940633773804,2.2031365151744025 +1739502702.0420244,62.279940605163574,7.88069964354294,1739502702.0420387,62.279940605163574,-0.04591472666055818,1739502702.0420582,62.279940605163574,104.93168175080034,1739502702.0420809,62.279940605163574,1.9913158657676577,1739502702.042089,62.279940605163574,0.03392463941437142,1739502702.0420995,62.279940605163574,3.1280369950167093,1739502702.0421152,62.279940605163574,-0.25761320371896773,1739502702.0421238,62.279940605163574,-0.05702397820558603,1739502702.042131,62.279940605163574,2.0343984411888116,1739502702.042139,62.279940605163574,0.0,1739502702.042155,62.279940605163574,-0.16873807398559082,1739502702.042165,62.279940605163574,3.1717888957377065,1739502702.0421789,62.279940605163574,2.2031365151744025 +1739502702.0607698,62.29994058609009,7.88069964354294,1739502702.0607738,62.29994058609009,-0.04591472666055818,1739502702.0607789,62.29994058609009,104.93168175080034,1739502702.0607834,62.29994058609009,1.9913158657676577,1739502702.0607858,62.29994058609009,0.03392463941437142,1739502702.0607884,62.29994058609009,3.1280369950167093,1739502702.0607908,62.29994058609009,-0.25761320371896773,1739502702.0607932,62.29994058609009,-0.05702397820558603,1739502702.060795,62.29994058609009,2.0343984411888116,1739502702.0607977,62.29994058609009,0.0,1739502702.0608,62.29994058609009,-0.16873807398559082,1739502702.0608022,62.29994058609009,3.1717888957377065,1739502702.0608046,62.29994058609009,2.2031365151744025 +1739502702.079037,62.3199405670166,7.88069964354294,1739502702.0790403,62.3199405670166,-0.04591472666055818,1739502702.0790448,62.3199405670166,104.93168175080034,1739502702.0790486,62.3199405670166,1.9913158657676577,1739502702.0790508,62.3199405670166,0.03392463941437142,1739502702.0790532,62.3199405670166,3.1280369950167093,1739502702.0790548,62.3199405670166,-0.25761320371896773,1739502702.079057,62.3199405670166,-0.05702397820558603,1739502702.0790586,62.3199405670166,2.0343984411888116,1739502702.0790608,62.3199405670166,0.0,1739502702.0790625,62.3199405670166,-0.16873807398559082,1739502702.0790646,62.3199405670166,3.1717888957377065,1739502702.0790663,62.3199405670166,2.2031365151744025 +1739502702.0986505,62.339940547943115,7.639391987222988,1739502702.0986543,62.339940547943115,-0.053125621285348146,1739502702.0986583,62.339940547943115,104.98115703124053,1739502702.098662,62.339940547943115,1.9788006866893846,1739502702.0986636,62.339940547943115,0.034209075302513985,1739502702.098666,62.339940547943115,3.1261653310323982,1739502702.0986679,62.339940547943115,-0.25410251173669934,1739502702.0986698,62.339940547943115,-0.060881253616648354,1739502702.0986717,62.339940547943115,2.0401201893829097,1739502702.0986736,62.339940547943115,0.0,1739502702.0986755,62.339940547943115,-0.13353779735589125,1739502702.0986772,62.339940547943115,3.171064820715189,1739502702.098679,62.339940547943115,2.1846580803978055 +1739502702.1186018,62.35994052886963,7.639391987222988,1739502702.1186051,62.35994052886963,-0.053125621285348146,1739502702.1186094,62.35994052886963,104.98115703124053,1739502702.1186135,62.35994052886963,1.9788006866893846,1739502702.1186154,62.35994052886963,0.034209075302513985,1739502702.1186178,62.35994052886963,3.1261653310323982,1739502702.1186197,62.35994052886963,-0.25410251173669934,1739502702.118622,62.35994052886963,-0.060881253616648354,1739502702.1186237,62.35994052886963,2.0401201893829097,1739502702.1186264,62.35994052886963,0.0,1739502702.118628,62.35994052886963,-0.14453789101489578,1739502702.11863,62.35994052886963,3.171064820715189,1739502702.1186318,62.35994052886963,2.1846580803978055 +1739502702.1390553,62.37994050979614,7.639391987222988,1739502702.1390595,62.37994050979614,-0.053125621285348146,1739502702.139064,62.37994050979614,104.98115703124053,1739502702.139068,62.37994050979614,1.9788006866893846,1739502702.1390698,62.37994050979614,0.034209075302513985,1739502702.1390724,62.37994050979614,3.1261653310323982,1739502702.1390743,62.37994050979614,-0.25410251173669934,1739502702.1390762,62.37994050979614,-0.060881253616648354,1739502702.1390781,62.37994050979614,2.0401201893829097,1739502702.139081,62.37994050979614,0.0,1739502702.139083,62.37994050979614,-0.14453789101489578,1739502702.1390848,62.37994050979614,3.171064820715189,1739502702.139087,62.37994050979614,2.1846580803978055 +1739502702.1584942,62.399940490722656,7.639391987222988,1739502702.158497,62.399940490722656,-0.053125621285348146,1739502702.1585002,62.399940490722656,104.98115703124053,1739502702.1585028,62.399940490722656,1.9788006866893846,1739502702.1585045,62.399940490722656,0.034209075302513985,1739502702.1585062,62.399940490722656,3.1261653310323982,1739502702.1585078,62.399940490722656,-0.25410251173669934,1739502702.1585093,62.399940490722656,-0.060881253616648354,1739502702.1585107,62.399940490722656,2.0401201893829097,1739502702.158512,62.399940490722656,0.0,1739502702.1585133,62.399940490722656,-0.14453789101489578,1739502702.158515,62.399940490722656,3.171064820715189,1739502702.1585164,62.399940490722656,2.1846580803978055 +1739502702.1778953,62.41994047164917,7.639391987222988,1739502702.1778977,62.41994047164917,-0.053125621285348146,1739502702.1779006,62.41994047164917,104.98115703124053,1739502702.1779032,62.41994047164917,1.9788006866893846,1739502702.1779044,62.41994047164917,0.034209075302513985,1739502702.177906,62.41994047164917,3.1261653310323982,1739502702.1779075,62.41994047164917,-0.25410251173669934,1739502702.177909,62.41994047164917,-0.060881253616648354,1739502702.1779103,62.41994047164917,2.0401201893829097,1739502702.1779118,62.41994047164917,0.0,1739502702.1779132,62.41994047164917,-0.14453789101489578,1739502702.1779146,62.41994047164917,3.171064820715189,1739502702.1779158,62.41994047164917,2.1846580803978055 +1739502702.1984634,62.439940452575684,7.399969757476075,1739502702.1984668,62.439940452575684,-0.06009323565458935,1739502702.1984713,62.439940452575684,105.60848263734283,1739502702.1984766,62.439940452575684,1.382987817387169,1739502702.1984794,62.439940452575684,0.042896262111854946,1739502702.198483,62.439940452575684,3.1244778537075066,1739502702.1984863,62.439940452575684,-0.27505115890360066,1739502702.1984897,62.439940452575684,-0.05832239463120391,1739502702.198493,62.439940452575684,2.006214884622831,1739502702.1984963,62.439940452575684,0.0,1739502702.1984997,62.439940452575684,-0.1709892594311843,1739502702.1985033,62.439940452575684,3.1701995659764735,1739502702.1985066,62.439940452575684,2.168938086004275 +1739502702.2184827,62.4599404335022,7.399969757476075,1739502702.2184868,62.4599404335022,-0.06009323565458935,1739502702.2184918,62.4599404335022,105.60848263734283,1739502702.2184975,62.4599404335022,1.382987817387169,1739502702.2185004,62.4599404335022,0.042896262111854946,1739502702.2185044,62.4599404335022,3.1244778537075066,1739502702.218508,62.4599404335022,-0.27505115890360066,1739502702.2185118,62.4599404335022,-0.05832239463120391,1739502702.2185154,62.4599404335022,2.006214884622831,1739502702.218519,62.4599404335022,0.0,1739502702.2185225,62.4599404335022,-0.16272320138144414,1739502702.2185264,62.4599404335022,3.1701995659764735,1739502702.21853,62.4599404335022,2.168938086004275 +1739502702.2402046,62.47994041442871,7.399969757476075,1739502702.2402086,62.47994041442871,-0.06009323565458935,1739502702.2402143,62.47994041442871,105.60848263734283,1739502702.2402203,62.47994041442871,1.382987817387169,1739502702.240224,62.47994041442871,0.042896262111854946,1739502702.2402284,62.47994041442871,3.1244778537075066,1739502702.2402325,62.47994041442871,-0.27505115890360066,1739502702.2402365,62.47994041442871,-0.05832239463120391,1739502702.2402403,62.47994041442871,2.006214884622831,1739502702.2402446,62.47994041442871,0.0,1739502702.240249,62.47994041442871,-0.16272320138144414,1739502702.240253,62.47994041442871,3.1701995659764735,1739502702.240257,62.47994041442871,2.168938086004275 +1739502702.2600567,62.499940395355225,7.399969757476075,1739502702.260061,62.499940395355225,-0.06009323565458935,1739502702.2600667,62.499940395355225,105.60848263734283,1739502702.260073,62.499940395355225,1.382987817387169,1739502702.2600763,62.499940395355225,0.042896262111854946,1739502702.2600808,62.499940395355225,3.1244778537075066,1739502702.2600846,62.499940395355225,-0.27505115890360066,1739502702.260089,62.499940395355225,-0.05832239463120391,1739502702.2600927,62.499940395355225,2.006214884622831,1739502702.260097,62.499940395355225,0.0,1739502702.2601008,62.499940395355225,-0.16272320138144414,1739502702.2601054,62.499940395355225,3.1701995659764735,1739502702.2601097,62.499940395355225,2.168938086004275 +1739502702.280319,62.51994037628174,7.399969757476075,1739502702.280323,62.51994037628174,-0.06009323565458935,1739502702.2803288,62.51994037628174,105.60848263734283,1739502702.280335,62.51994037628174,1.382987817387169,1739502702.2803385,62.51994037628174,0.042896262111854946,1739502702.2803428,62.51994037628174,3.1244778537075066,1739502702.2803469,62.51994037628174,-0.27505115890360066,1739502702.2803507,62.51994037628174,-0.05832239463120391,1739502702.2803547,62.51994037628174,2.006214884622831,1739502702.280359,62.51994037628174,0.0,1739502702.280363,62.51994037628174,-0.16272320138144414,1739502702.2803671,62.51994037628174,3.1701995659764735,1739502702.2803712,62.51994037628174,2.168938086004275 +1739502702.2996683,62.53994035720825,7.399969757476075,1739502702.2996724,62.53994035720825,-0.06009323565458935,1739502702.2996778,62.53994035720825,105.60848263734283,1739502702.299684,62.53994035720825,1.382987817387169,1739502702.2996874,62.53994035720825,0.042896262111854946,1739502702.2996917,62.53994035720825,3.1244778537075066,1739502702.299696,62.53994035720825,-0.27505115890360066,1739502702.2997,62.53994035720825,-0.05832239463120391,1739502702.2997038,62.53994035720825,2.006214884622831,1739502702.299708,62.53994035720825,0.0,1739502702.2997117,62.53994035720825,-0.16272320138144414,1739502702.2997158,62.53994035720825,3.1701995659764735,1739502702.2997203,62.53994035720825,2.168938086004275 +1739502702.3200004,62.559940338134766,7.162389176817541,1739502702.3200047,62.559940338134766,-0.06679415259418686,1739502702.32001,62.559940338134766,105.63533594387417,1739502702.3200161,62.559940338134766,1.3920940996861644,1739502702.3200197,62.559940338134766,0.042777998705374486,1739502702.320024,62.559940338134766,3.12260593232862,1739502702.3200278,62.559940338134766,-0.2693727679260539,1739502702.320032,62.559940338134766,-0.06210123751056454,1739502702.320036,62.559940338134766,2.0153492743689663,1739502702.32004,62.559940338134766,0.0,1739502702.320044,62.559940338134766,-0.12328381782073357,1739502702.320048,62.559940338134766,3.1692971490560304,1739502702.3200521,62.559940338134766,2.1509579076332006 +1739502702.346449,62.57994031906128,7.162389176817541,1739502702.346457,62.57994031906128,-0.06679415259418686,1739502702.3464675,62.57994031906128,105.63533594387417,1739502702.346478,62.57994031906128,1.3920940996861644,1739502702.3464835,62.57994031906128,0.042777998705374486,1739502702.3464897,62.57994031906128,3.12260593232862,1739502702.3464952,62.57994031906128,-0.2693727679260539,1739502702.3465002,62.57994031906128,-0.06210123751056454,1739502702.346505,62.57994031906128,2.0153492743689663,1739502702.3465106,62.57994031906128,0.0,1739502702.3465157,62.57994031906128,-0.13560863326423434,1739502702.3465211,62.57994031906128,3.1692971490560304,1739502702.3465266,62.57994031906128,2.1509579076332006 +1739502702.3658764,62.59994029998779,7.162389176817541,1739502702.3658843,62.59994029998779,-0.06679415259418686,1739502702.3658946,62.59994029998779,105.63533594387417,1739502702.3659048,62.59994029998779,1.3920940996861644,1739502702.36591,62.59994029998779,0.042777998705374486,1739502702.365916,62.59994029998779,3.12260593232862,1739502702.365921,62.59994029998779,-0.2693727679260539,1739502702.365926,62.59994029998779,-0.06210123751056454,1739502702.3659306,62.59994029998779,2.0153492743689663,1739502702.3659368,62.59994029998779,0.0,1739502702.3659415,62.59994029998779,-0.13560863326423434,1739502702.3659468,62.59994029998779,3.1692971490560304,1739502702.365952,62.59994029998779,2.1509579076332006 +1739502702.394523,62.62994027137756,7.162389176817541,1739502702.3945274,62.62994027137756,-0.06679415259418686,1739502702.394533,62.62994027137756,105.63533594387417,1739502702.3945382,62.62994027137756,1.3920940996861644,1739502702.394541,62.62994027137756,0.042777998705374486,1739502702.3945444,62.62994027137756,3.12260593232862,1739502702.394547,62.62994027137756,-0.2693727679260539,1739502702.3945498,62.62994027137756,-0.06210123751056454,1739502702.3945522,62.62994027137756,2.0153492743689663,1739502702.3945553,62.62994027137756,0.0,1739502702.3945644,62.62994027137756,-0.13560863326423434,1739502702.3945675,62.62994027137756,3.1692971490560304,1739502702.3945699,62.62994027137756,2.1509579076332006 +1739502702.4139044,62.64994025230408,7.162389176817541,1739502702.413909,62.64994025230408,-0.06679415259418686,1739502702.4139147,62.64994025230408,105.63533594387417,1739502702.41392,62.64994025230408,1.3920940996861644,1739502702.4139228,62.64994025230408,0.042777998705374486,1739502702.4139261,62.64994025230408,3.12260593232862,1739502702.4139287,62.64994025230408,-0.2693727679260539,1739502702.4139316,62.64994025230408,-0.06210123751056454,1739502702.4139338,62.64994025230408,2.0153492743689663,1739502702.4139369,62.64994025230408,0.0,1739502702.4139395,62.64994025230408,-0.13560863326423434,1739502702.4139423,62.64994025230408,3.1692971490560304,1739502702.4139447,62.64994025230408,2.1509579076332006 +1739502702.4335752,62.67994022369385,6.92661973719601,1739502702.4335804,62.67994022369385,-0.07322530072694189,1739502702.433586,62.67994022369385,105.84757000034718,1739502702.4335914,62.67994022369385,1.2095789597532118,1739502702.4335942,62.67994022369385,0.044,1739502702.4335973,62.67994022369385,3.1210909848340447,1739502702.4336002,62.67994022369385,-0.27001103604155907,1739502702.433603,62.67994022369385,-0.06340929440008587,1739502702.4336057,62.67994022369385,2.014320470505652,1739502702.4336085,62.67994022369385,0.0,1739502702.4336116,62.67994022369385,-0.11549734122435515,1739502702.4336143,62.67994022369385,3.168327784703925,1739502702.4336176,62.67994022369385,2.136102594613094 +1739502702.4564655,62.69994020462036,6.92661973719601,1739502702.4564707,62.69994020462036,-0.07322530072694189,1739502702.4564779,62.69994020462036,105.84757000034718,1739502702.456485,62.69994020462036,1.2095789597532118,1739502702.4564893,62.69994020462036,0.044,1739502702.456494,62.69994020462036,3.1210909848340447,1739502702.4564984,62.69994020462036,-0.27001103604155907,1739502702.4565027,62.69994020462036,-0.06340929440008587,1739502702.4565072,62.69994020462036,2.014320470505652,1739502702.4565115,62.69994020462036,0.0,1739502702.4565158,62.69994020462036,-0.12178212410744216,1739502702.4565208,62.69994020462036,3.168327784703925,1739502702.4565248,62.69994020462036,2.136102594613094 +1739502702.4923506,62.719940185546875,6.92661973719601,1739502702.4923546,62.719940185546875,-0.07322530072694189,1739502702.4923596,62.719940185546875,105.84757000034718,1739502702.4923656,62.719940185546875,1.2095789597532118,1739502702.4923687,62.719940185546875,0.044,1739502702.4923725,62.719940185546875,3.1210909848340447,1739502702.4923759,62.719940185546875,-0.27001103604155907,1739502702.4923792,62.719940185546875,-0.06340929440008587,1739502702.4923823,62.719940185546875,2.014320470505652,1739502702.4923859,62.719940185546875,0.0,1739502702.4923892,62.719940185546875,-0.12178212410744216,1739502702.4923925,62.719940185546875,3.168327784703925,1739502702.492396,62.719940185546875,2.136102594613094 +1739502702.4954998,62.73994016647339,6.92661973719601,1739502702.4955022,62.73994016647339,-0.07322530072694189,1739502702.4955053,62.73994016647339,105.84757000034718,1739502702.495508,62.73994016647339,1.2095789597532118,1739502702.4955091,62.73994016647339,0.044,1739502702.495511,62.73994016647339,3.1210909848340447,1739502702.4955125,62.73994016647339,-0.27001103604155907,1739502702.4955142,62.73994016647339,-0.06340929440008587,1739502702.4955153,62.73994016647339,2.014320470505652,1739502702.4955173,62.73994016647339,0.0,1739502702.4955184,62.73994016647339,-0.12178212410744216,1739502702.49552,62.73994016647339,3.168327784703925,1739502702.4955215,62.73994016647339,2.136102594613094 +1739502702.5158255,62.7599401473999,6.92661973719601,1739502702.5158281,62.7599401473999,-0.07322530072694189,1739502702.5158308,62.7599401473999,105.84757000034718,1739502702.5158334,62.7599401473999,1.2095789597532118,1739502702.5158346,62.7599401473999,0.044,1739502702.5158362,62.7599401473999,3.1210909848340447,1739502702.5158372,62.7599401473999,-0.27001103604155907,1739502702.5158384,62.7599401473999,-0.06340929440008587,1739502702.5158398,62.7599401473999,2.014320470505652,1739502702.5158412,62.7599401473999,0.0,1739502702.5158427,62.7599401473999,-0.12178212410744216,1739502702.5158439,62.7599401473999,3.168327784703925,1739502702.5158453,62.7599401473999,2.136102594613094 +1739502702.5357773,62.779940128326416,6.692411397076601,1739502702.5357802,62.779940128326416,-0.07937921482429289,1739502702.5357828,62.779940128326416,105.86865490487203,1739502702.5357854,62.779940128326416,1.2154062322127388,1739502702.535787,62.779940128326416,0.044,1739502702.535789,62.779940128326416,3.119069696671695,1739502702.5357904,62.779940128326416,-0.2640345648112698,1739502702.5357916,62.779940128326416,-0.06755258366940706,1739502702.5357928,62.779940128326416,2.023974353248729,1739502702.5357945,62.779940128326416,0.0,1739502702.5357957,62.779940128326416,-0.08816761047459648,1739502702.5357974,62.779940128326416,3.167283983101646,1739502702.5357985,62.779940128326416,2.1226465061209043 +1739502702.5565364,62.79994010925293,6.692411397076601,1739502702.556539,62.79994010925293,-0.07937921482429289,1739502702.5565422,62.79994010925293,105.86865490487203,1739502702.556545,62.79994010925293,1.2154062322127388,1739502702.5565462,62.79994010925293,0.044,1739502702.556548,62.79994010925293,3.119069696671695,1739502702.5565493,62.79994010925293,-0.2640345648112698,1739502702.556551,62.79994010925293,-0.06755258366940706,1739502702.556552,62.79994010925293,2.023974353248729,1739502702.5565538,62.79994010925293,0.0,1739502702.556555,62.79994010925293,-0.09867215287217546,1739502702.5565565,62.79994010925293,3.167283983101646,1739502702.5565581,62.79994010925293,2.1226465061209043 +1739502702.57519,62.81994009017944,6.692411397076601,1739502702.575193,62.81994009017944,-0.07937921482429289,1739502702.5751963,62.81994009017944,105.86865490487203,1739502702.5751984,62.81994009017944,1.2154062322127388,1739502702.5751998,62.81994009017944,0.044,1739502702.5752015,62.81994009017944,3.119069696671695,1739502702.5752032,62.81994009017944,-0.2640345648112698,1739502702.5752046,62.81994009017944,-0.06755258366940706,1739502702.5752058,62.81994009017944,2.023974353248729,1739502702.5752075,62.81994009017944,0.0,1739502702.5752087,62.81994009017944,-0.09867215287217546,1739502702.5752103,62.81994009017944,3.167283983101646,1739502702.5752118,62.81994009017944,2.1226465061209043 +1739502702.5956662,62.83994007110596,6.692411397076601,1739502702.5956688,62.83994007110596,-0.07937921482429289,1739502702.5956721,62.83994007110596,105.86865490487203,1739502702.5956745,62.83994007110596,1.2154062322127388,1739502702.595676,62.83994007110596,0.044,1739502702.5956776,62.83994007110596,3.119069696671695,1739502702.5956793,62.83994007110596,-0.2640345648112698,1739502702.5956807,62.83994007110596,-0.06755258366940706,1739502702.5956821,62.83994007110596,2.023974353248729,1739502702.5956836,62.83994007110596,0.0,1739502702.5956848,62.83994007110596,-0.09867215287217546,1739502702.5956864,62.83994007110596,3.167283983101646,1739502702.5956879,62.83994007110596,2.1226465061209043 +1739502702.615163,62.85994005203247,6.692411397076601,1739502702.615166,62.85994005203247,-0.07937921482429289,1739502702.6151693,62.85994005203247,105.86865490487203,1739502702.6151724,62.85994005203247,1.2154062322127388,1739502702.615174,62.85994005203247,0.044,1739502702.6151762,62.85994005203247,3.119069696671695,1739502702.6151776,62.85994005203247,-0.2640345648112698,1739502702.6151793,62.85994005203247,-0.06755258366940706,1739502702.6151807,62.85994005203247,2.023974353248729,1739502702.6151826,62.85994005203247,0.0,1739502702.615184,62.85994005203247,-0.09867215287217546,1739502702.6151857,62.85994005203247,3.167283983101646,1739502702.6151872,62.85994005203247,2.1226465061209043 +1739502702.6387904,62.879940032958984,6.459539216885268,1739502702.6387956,62.879940032958984,-0.08524039965441776,1739502702.6388013,62.879940032958984,106.6881379480606,1739502702.6388083,62.879940032958984,0.4182084410417777,1739502702.638812,62.879940032958984,0.065,1739502702.638817,62.879940032958984,3.1167290193347026,1739502702.6388214,62.879940032958984,-0.2981828405590059,1739502702.6388257,62.879940032958984,-0.06269701924051282,1739502702.6388304,62.879940032958984,1.9694305881614935,1739502702.638835,62.879940032958984,0.0,1739502702.6388392,62.879940032958984,-0.16228183505351718,1739502702.638844,62.879940032958984,3.16609095250424,1739502702.6388483,62.879940032958984,2.1118343845002836 +1739502702.6574032,62.8999400138855,6.459539216885268,1739502702.657408,62.8999400138855,-0.08524039965441776,1739502702.6574144,62.8999400138855,106.6881379480606,1739502702.657421,62.8999400138855,0.4182084410417777,1739502702.657425,62.8999400138855,0.065,1739502702.6574297,62.8999400138855,3.1167290193347026,1739502702.6574342,62.8999400138855,-0.2981828405590059,1739502702.6574388,62.8999400138855,-0.06269701924051282,1739502702.657443,62.8999400138855,1.9694305881614935,1739502702.6574476,62.8999400138855,0.0,1739502702.6574523,62.8999400138855,-0.14240379633879008,1739502702.6574566,62.8999400138855,3.16609095250424,1739502702.6574612,62.8999400138855,2.1118343845002836 +1739502702.683098,62.91993999481201,6.459539216885268,1739502702.6831071,62.91993999481201,-0.08524039965441776,1739502702.6831179,62.91993999481201,106.6881379480606,1739502702.6831279,62.91993999481201,0.4182084410417777,1739502702.6831326,62.91993999481201,0.065,1739502702.683139,62.91993999481201,3.1167290193347026,1739502702.683144,62.91993999481201,-0.2981828405590059,1739502702.683149,62.91993999481201,-0.06269701924051282,1739502702.6831539,62.91993999481201,1.9694305881614935,1739502702.6831596,62.91993999481201,0.0,1739502702.6831644,62.91993999481201,-0.14240379633879008,1739502702.6831696,62.91993999481201,3.16609095250424,1739502702.6831748,62.91993999481201,2.1118343845002836 +1739502702.7029936,62.939939975738525,6.459539216885268,1739502702.703003,62.939939975738525,-0.08524039965441776,1739502702.703013,62.939939975738525,106.6881379480606,1739502702.7030232,62.939939975738525,0.4182084410417777,1739502702.703028,62.939939975738525,0.065,1739502702.7030344,62.939939975738525,3.1167290193347026,1739502702.7030396,62.939939975738525,-0.2981828405590059,1739502702.703045,62.939939975738525,-0.06269701924051282,1739502702.7030494,62.939939975738525,1.9694305881614935,1739502702.7030554,62.939939975738525,0.0,1739502702.70306,62.939939975738525,-0.14240379633879008,1739502702.7030654,62.939939975738525,3.16609095250424,1739502702.7030702,62.939939975738525,2.1118343845002836 +1739502702.7203732,62.95993995666504,6.459539216885268,1739502702.7203822,62.95993995666504,-0.08524039965441776,1739502702.7203932,62.95993995666504,106.6881379480606,1739502702.7204037,62.95993995666504,0.4182084410417777,1739502702.7204087,62.95993995666504,0.065,1739502702.7204146,62.95993995666504,3.1167290193347026,1739502702.72042,62.95993995666504,-0.2981828405590059,1739502702.7204247,62.95993995666504,-0.06269701924051282,1739502702.7204294,62.95993995666504,1.9694305881614935,1739502702.7204351,62.95993995666504,0.0,1739502702.72044,62.95993995666504,-0.14240379633879008,1739502702.720445,62.95993995666504,3.16609095250424,1739502702.7204497,62.95993995666504,2.1118343845002836 +1739502702.746284,62.97993993759155,6.459539216885268,1739502702.74629,62.97993993759155,-0.08524039965441776,1739502702.7462974,62.97993993759155,106.6881379480606,1739502702.7463043,62.97993993759155,0.4182084410417777,1739502702.7463078,62.97993993759155,0.065,1739502702.746312,62.97993993759155,3.1167290193347026,1739502702.7463155,62.97993993759155,-0.2981828405590059,1739502702.746319,62.97993993759155,-0.06269701924051282,1739502702.7463222,62.97993993759155,1.9694305881614935,1739502702.746326,62.97993993759155,0.0,1739502702.7463293,62.97993993759155,-0.14240379633879008,1739502702.746333,62.97993993759155,3.16609095250424,1739502702.7463365,62.97993993759155,2.1118343845002836 +1739502702.7646575,62.999939918518066,6.228122458662758,1739502702.7646632,62.999939918518066,-0.09078153256094268,1739502702.764691,62.999939918518066,106.69832582655529,1739502702.7647002,62.999939918518066,0.4399936624039431,1739502702.7647038,62.999939918518066,0.065,1739502702.7647083,62.999939918518066,3.1146851779070968,1739502702.7647116,62.999939918518066,-0.29040508122020314,1739502702.7647152,62.999939918518066,-0.06651252251924519,1739502702.7647185,62.999939918518066,1.9817229971812247,1739502702.7647223,62.999939918518066,0.0,1739502702.7647257,62.999939918518066,-0.10127075288285939,1739502702.7647295,62.999939918518066,3.1648605996554053,1739502702.7647336,62.999939918518066,2.095847834571857 +1739502702.7863529,63.01993989944458,6.228122458662758,1739502702.7863588,63.01993989944458,-0.09078153256094268,1739502702.7863662,63.01993989944458,106.69832582655529,1739502702.7863734,63.01993989944458,0.4399936624039431,1739502702.7863767,63.01993989944458,0.065,1739502702.7863808,63.01993989944458,3.1146851779070968,1739502702.7863846,63.01993989944458,-0.29040508122020314,1739502702.786388,63.01993989944458,-0.06651252251924519,1739502702.7863913,63.01993989944458,1.9817229971812247,1739502702.786395,63.01993989944458,0.0,1739502702.7863984,63.01993989944458,-0.11412483739063228,1739502702.7864022,63.01993989944458,3.1648605996554053,1739502702.7864056,63.01993989944458,2.095847834571857 +1739502702.8115706,63.04993987083435,6.228122458662758,1739502702.8115804,63.04993987083435,-0.09078153256094268,1739502702.8115923,63.04993987083435,106.69832582655529,1739502702.811606,63.04993987083435,0.4399936624039431,1739502702.8116143,63.04993987083435,0.065,1739502702.8116248,63.04993987083435,3.1146851779070968,1739502702.811634,63.04993987083435,-0.29040508122020314,1739502702.8116434,63.04993987083435,-0.06651252251924519,1739502702.8116524,63.04993987083435,1.9817229971812247,1739502702.8116622,63.04993987083435,0.0,1739502702.811671,63.04993987083435,-0.11412483739063228,1739502702.8116803,63.04993987083435,3.1648605996554053,1739502702.811686,63.04993987083435,2.095847834571857 +1739502702.8244977,63.069939851760864,6.228122458662758,1739502702.8245003,63.069939851760864,-0.09078153256094268,1739502702.824504,63.069939851760864,106.69832582655529,1739502702.824507,63.069939851760864,0.4399936624039431,1739502702.8245084,63.069939851760864,0.065,1739502702.82451,63.069939851760864,3.1146851779070968,1739502702.824512,63.069939851760864,-0.29040508122020314,1739502702.8245134,63.069939851760864,-0.06651252251924519,1739502702.824515,63.069939851760864,1.9817229971812247,1739502702.824517,63.069939851760864,0.0,1739502702.824519,63.069939851760864,-0.11412483739063228,1739502702.8245206,63.069939851760864,3.1648605996554053,1739502702.8245225,63.069939851760864,2.095847834571857 +1739502702.8440626,63.08993983268738,6.228122458662758,1739502702.844066,63.08993983268738,-0.09078153256094268,1739502702.8440695,63.08993983268738,106.69832582655529,1739502702.8440728,63.08993983268738,0.4399936624039431,1739502702.8440745,63.08993983268738,0.065,1739502702.8440764,63.08993983268738,3.1146851779070968,1739502702.844078,63.08993983268738,-0.29040508122020314,1739502702.8440797,63.08993983268738,-0.06651252251924519,1739502702.844081,63.08993983268738,1.9817229971812247,1739502702.8440828,63.08993983268738,0.0,1739502702.8440845,63.08993983268738,-0.11412483739063228,1739502702.844086,63.08993983268738,3.1648605996554053,1739502702.8440876,63.08993983268738,2.095847834571857 +1739502702.869175,63.10993981361389,5.998269372888142,1739502702.8691883,63.10993981361389,-0.09600223189198953,1739502702.869203,63.10993981361389,106.70844458302871,1739502702.8692186,63.10993981361389,0.45488846919810344,1739502702.8692262,63.10993981361389,0.065,1739502702.8692362,63.10993981361389,3.1125567662717675,1739502702.8692443,63.10993981361389,-0.28311602313383283,1739502702.8692522,63.10993981361389,-0.07068538877926611,1739502702.8692596,63.10993981361389,1.9933126706919257,1739502702.869269,63.10993981361389,0.0,1739502702.869278,63.10993981361389,-0.07907543764401656,1739502702.8692873,63.10993981361389,3.1636302468065707,1739502702.8692963,63.10993981361389,2.08334105293807 +1739502702.9127693,63.13993978500366,5.998269372888142,1739502702.9127781,63.13993978500366,-0.09600223189198953,1739502702.9127903,63.13993978500366,106.70844458302871,1739502702.912804,63.13993978500366,0.45488846919810344,1739502702.9128115,63.13993978500366,0.065,1739502702.9128213,63.13993978500366,3.1125567662717675,1739502702.9128299,63.13993978500366,-0.28311602313383283,1739502702.9128387,63.13993978500366,-0.07068538877926611,1739502702.9128473,63.13993978500366,1.9933126706919257,1739502702.912857,63.13993978500366,0.0,1739502702.9128659,63.13993978500366,-0.09002838224614407,1739502702.912875,63.13993978500366,3.1636302468065707,1739502702.912884,63.13993978500366,2.08334105293807 +1739502702.9284434,63.159939765930176,5.998269372888142,1739502702.9284494,63.159939765930176,-0.09600223189198953,1739502702.9284573,63.159939765930176,106.70844458302871,1739502702.9284647,63.159939765930176,0.45488846919810344,1739502702.9284685,63.159939765930176,0.065,1739502702.9284732,63.159939765930176,3.1125567662717675,1739502702.9284768,63.159939765930176,-0.28311602313383283,1739502702.9284801,63.159939765930176,-0.07068538877926611,1739502702.9284837,63.159939765930176,1.9933126706919257,1739502702.9284878,63.159939765930176,0.0,1739502702.9284916,63.159939765930176,-0.09002838224614407,1739502702.9284952,63.159939765930176,3.1636302468065707,1739502702.928499,63.159939765930176,2.08334105293807 +1739502702.950476,63.17993974685669,5.998269372888142,1739502702.9504821,63.17993974685669,-0.09600223189198953,1739502702.9504905,63.17993974685669,106.70844458302871,1739502702.9504993,63.17993974685669,0.45488846919810344,1739502702.9505033,63.17993974685669,0.065,1739502702.9505086,63.17993974685669,3.1125567662717675,1739502702.9505134,63.17993974685669,-0.28311602313383283,1739502702.9505184,63.17993974685669,-0.07068538877926611,1739502702.950523,63.17993974685669,1.9933126706919257,1739502702.9505274,63.17993974685669,0.0,1739502702.9505324,63.17993974685669,-0.09002838224614407,1739502702.950537,63.17993974685669,3.1636302468065707,1739502702.9505415,63.17993974685669,2.08334105293807 +1739502702.9678845,63.20993971824646,5.769638302642161,1739502702.967887,63.20993971824646,-0.10090376610591356,1739502702.96789,63.20993971824646,106.71850925165374,1739502702.9678926,63.20993971824646,0.46412412268247083,1739502702.967894,63.20993971824646,0.065,1739502702.9678957,63.20993971824646,3.1103327760958868,1739502702.9678972,63.20993971824646,-0.27557894270873573,1739502702.9678984,63.20993971824646,-0.07509951043169992,1739502702.9678996,63.20993971824646,2.0053679852467434,1739502702.9679015,63.20993971824646,0.0,1739502702.9679027,63.20993971824646,-0.05845677195048919,1739502702.9679043,63.20993971824646,3.162272736161935,1739502702.9679055,63.20993971824646,2.0736908918833667 +1739502702.9878888,63.229939699172974,5.769638302642161,1739502702.9878912,63.229939699172974,-0.10090376610591356,1739502702.987894,63.229939699172974,106.71850925165374,1739502702.9878967,63.229939699172974,0.46412412268247083,1739502702.9878979,63.229939699172974,0.065,1739502702.9878995,63.229939699172974,3.1103327760958868,1739502702.987901,63.229939699172974,-0.27557894270873573,1739502702.9879026,63.229939699172974,-0.07509951043169992,1739502702.9879038,63.229939699172974,2.0053679852467434,1739502702.9879053,63.229939699172974,0.0,1739502702.9879065,63.229939699172974,-0.06832290663662333,1739502702.987908,63.229939699172974,3.162272736161935,1739502702.987909,63.229939699172974,2.0736908918833667 +1739502703.0077758,63.24993968009949,5.769638302642161,1739502703.00778,63.24993968009949,-0.10090376610591356,1739502703.0077853,63.24993968009949,106.71850925165374,1739502703.00779,63.24993968009949,0.46412412268247083,1739502703.0077932,63.24993968009949,0.065,1739502703.0077972,63.24993968009949,3.1103327760958868,1739502703.0078,63.24993968009949,-0.27557894270873573,1739502703.0078032,63.24993968009949,-0.07509951043169992,1739502703.0078056,63.24993968009949,2.0053679852467434,1739502703.0078087,63.24993968009949,0.0,1739502703.0078115,63.24993968009949,-0.06832290663662333,1739502703.0078144,63.24993968009949,3.162272736161935,1739502703.007817,63.24993968009949,2.0736908918833667 +1739502703.0281653,63.269939661026,5.769638302642161,1739502703.0281684,63.269939661026,-0.10090376610591356,1739502703.0281718,63.269939661026,106.71850925165374,1739502703.0281749,63.269939661026,0.46412412268247083,1739502703.0281763,63.269939661026,0.065,1739502703.028178,63.269939661026,3.1103327760958868,1739502703.0281794,63.269939661026,-0.27557894270873573,1739502703.028181,63.269939661026,-0.07509951043169992,1739502703.0281823,63.269939661026,2.0053679852467434,1739502703.0281842,63.269939661026,0.0,1739502703.0281854,63.269939661026,-0.06832290663662333,1739502703.0281868,63.269939661026,3.162272736161935,1739502703.0281885,63.269939661026,2.0736908918833667 +1739502703.0472162,63.289939641952515,5.769638302642161,1739502703.0472188,63.289939641952515,-0.10090376610591356,1739502703.047222,63.289939641952515,106.71850925165374,1739502703.0472248,63.289939641952515,0.46412412268247083,1739502703.0472264,63.289939641952515,0.065,1739502703.0472288,63.289939641952515,3.1103327760958868,1739502703.0472302,63.289939641952515,-0.27557894270873573,1739502703.0472314,63.289939641952515,-0.07509951043169992,1739502703.0472329,63.289939641952515,2.0053679852467434,1739502703.0472345,63.289939641952515,0.0,1739502703.0472357,63.289939641952515,-0.06832290663662333,1739502703.0472372,63.289939641952515,3.162272736161935,1739502703.0472383,63.289939641952515,2.0736908918833667 +1739502703.0673828,63.30993962287903,5.769638302642161,1739502703.0673866,63.30993962287903,-0.10090376610591356,1739502703.0673912,63.30993962287903,106.71850925165374,1739502703.067395,63.30993962287903,0.46412412268247083,1739502703.067397,63.30993962287903,0.065,1739502703.0674,63.30993962287903,3.1103327760958868,1739502703.0674021,63.30993962287903,-0.27557894270873573,1739502703.0674043,63.30993962287903,-0.07509951043169992,1739502703.0674064,63.30993962287903,2.0053679852467434,1739502703.067409,63.30993962287903,0.0,1739502703.0674112,63.30993962287903,-0.06832290663662333,1739502703.0674143,63.30993962287903,3.162272736161935,1739502703.067417,63.30993962287903,2.0736908918833667 +1739502703.0892262,63.32993960380554,5.541933909912263,1739502703.089229,63.32993960380554,-0.10545646771698358,1739502703.0892322,63.32993960380554,106.99378738957041,1739502703.0892348,63.32993960380554,0.20341726876539967,1739502703.0892363,63.32993960380554,0.065,1739502703.0892382,63.32993960380554,3.10967394133611,1739502703.0892398,63.32993960380554,-0.27261232832108884,1739502703.089241,63.32993960380554,-0.07337301529986268,1739502703.0892425,63.32993960380554,2.0101329601614815,1739502703.089244,63.32993960380554,0.0,1739502703.089245,63.32993960380554,-0.05079473135530159,1739502703.0892465,63.32993960380554,3.160735299162871,1739502703.089248,63.32993960380554,2.0664052498835632 +1739502703.1079617,63.349939584732056,5.541933909912263,1739502703.1079638,63.349939584732056,-0.10545646771698358,1739502703.1079667,63.349939584732056,106.99378738957041,1739502703.1079695,63.349939584732056,0.20341726876539967,1739502703.1079707,63.349939584732056,0.065,1739502703.1079726,63.349939584732056,3.10967394133611,1739502703.1079738,63.349939584732056,-0.27261232832108884,1739502703.1079755,63.349939584732056,-0.07337301529986268,1739502703.1079767,63.349939584732056,2.0101329601614815,1739502703.1079786,63.349939584732056,0.0,1739502703.1079798,63.349939584732056,-0.05627228972208176,1739502703.1079812,63.349939584732056,3.160735299162871,1739502703.1079829,63.349939584732056,2.0664052498835632 +1739502703.1291611,63.36993956565857,5.541933909912263,1739502703.1291635,63.36993956565857,-0.10545646771698358,1739502703.1291664,63.36993956565857,106.99378738957041,1739502703.129169,63.36993956565857,0.20341726876539967,1739502703.1291702,63.36993956565857,0.065,1739502703.129172,63.36993956565857,3.10967394133611,1739502703.1291735,63.36993956565857,-0.27261232832108884,1739502703.1291747,63.36993956565857,-0.07337301529986268,1739502703.1291761,63.36993956565857,2.0101329601614815,1739502703.1291778,63.36993956565857,0.0,1739502703.1291792,63.36993956565857,-0.05627228972208176,1739502703.1291807,63.36993956565857,3.160735299162871,1739502703.129182,63.36993956565857,2.0664052498835632 +1739502703.147612,63.38993954658508,5.541933909912263,1739502703.147615,63.38993954658508,-0.10545646771698358,1739502703.147618,63.38993954658508,106.99378738957041,1739502703.147621,63.38993954658508,0.20341726876539967,1739502703.1476223,63.38993954658508,0.065,1739502703.1476245,63.38993954658508,3.10967394133611,1739502703.1476257,63.38993954658508,-0.27261232832108884,1739502703.1476274,63.38993954658508,-0.07337301529986268,1739502703.1476285,63.38993954658508,2.0101329601614815,1739502703.1476305,63.38993954658508,0.0,1739502703.1476316,63.38993954658508,-0.05627228972208176,1739502703.1476328,63.38993954658508,3.160735299162871,1739502703.1476345,63.38993954658508,2.0664052498835632 +1739502703.1673312,63.4099395275116,5.541933909912263,1739502703.167334,63.4099395275116,-0.10545646771698358,1739502703.167337,63.4099395275116,106.99378738957041,1739502703.1673396,63.4099395275116,0.20341726876539967,1739502703.1673408,63.4099395275116,0.065,1739502703.1673427,63.4099395275116,3.10967394133611,1739502703.167344,63.4099395275116,-0.27261232832108884,1739502703.1673455,63.4099395275116,-0.07337301529986268,1739502703.1673467,63.4099395275116,2.0101329601614815,1739502703.1673484,63.4099395275116,0.0,1739502703.1673498,63.4099395275116,-0.05627228972208176,1739502703.1673512,63.4099395275116,3.160735299162871,1739502703.1673527,63.4099395275116,2.0664052498835632 +1739502703.187617,63.42993950843811,5.3149786312174,1739502703.1876197,63.42993950843811,-0.10964062679466924,1739502703.1876223,63.42993950843811,107.30820996041838,1739502703.1876254,63.42993950843811,-0.0986735353301138,1739502703.187627,63.42993950843811,0.065,1739502703.1876287,63.42993950843811,3.1093445374240027,1739502703.1876302,63.42993950843811,-0.2697953705135101,1739502703.1876318,63.42993950843811,-0.07061274341930904,1739502703.187633,63.42993950843811,2.0146680360783,1739502703.187635,63.42993950843811,0.0,1739502703.1876361,63.42993950843811,-0.04070725338436906,1739502703.1876378,63.42993950843811,3.1591753574167,1739502703.1876395,63.42993950843811,2.0602393665073415 +1739502703.2073588,63.449939489364624,5.3149786312174,1739502703.2073615,63.449939489364624,-0.10964062679466924,1739502703.2073648,63.449939489364624,107.30820996041838,1739502703.2073677,63.449939489364624,-0.0986735353301138,1739502703.2073689,63.449939489364624,0.065,1739502703.2073708,63.449939489364624,3.1093445374240027,1739502703.2073722,63.449939489364624,-0.2697953705135101,1739502703.2073739,63.449939489364624,-0.07061274341930904,1739502703.2073748,63.449939489364624,2.0146680360783,1739502703.2073767,63.449939489364624,0.0,1739502703.2073781,63.449939489364624,-0.04557133042904171,1739502703.2073798,63.449939489364624,3.1591753574167,1739502703.2073812,63.449939489364624,2.0602393665073415 +1739502703.227399,63.46993947029114,5.3149786312174,1739502703.227402,63.46993947029114,-0.10964062679466924,1739502703.2274055,63.46993947029114,107.30820996041838,1739502703.2274084,63.46993947029114,-0.0986735353301138,1739502703.2274098,63.46993947029114,0.065,1739502703.2274117,63.46993947029114,3.1093445374240027,1739502703.2274132,63.46993947029114,-0.2697953705135101,1739502703.227415,63.46993947029114,-0.07061274341930904,1739502703.2274163,63.46993947029114,2.0146680360783,1739502703.2274182,63.46993947029114,0.0,1739502703.2274194,63.46993947029114,-0.04557133042904171,1739502703.227421,63.46993947029114,3.1591753574167,1739502703.2274225,63.46993947029114,2.0602393665073415 +1739502703.2473464,63.48993945121765,5.3149786312174,1739502703.2473493,63.48993945121765,-0.10964062679466924,1739502703.2473521,63.48993945121765,107.30820996041838,1739502703.2473552,63.48993945121765,-0.0986735353301138,1739502703.2473567,63.48993945121765,0.065,1739502703.2473583,63.48993945121765,3.1093445374240027,1739502703.2473595,63.48993945121765,-0.2697953705135101,1739502703.247361,63.48993945121765,-0.07061274341930904,1739502703.2473624,63.48993945121765,2.0146680360783,1739502703.247364,63.48993945121765,0.0,1739502703.2473657,63.48993945121765,-0.04557133042904171,1739502703.247367,63.48993945121765,3.1591753574167,1739502703.247368,63.48993945121765,2.0602393665073415 +1739502703.2674668,63.509939432144165,5.3149786312174,1739502703.26747,63.509939432144165,-0.10964062679466924,1739502703.2674727,63.509939432144165,107.30820996041838,1739502703.2674754,63.509939432144165,-0.0986735353301138,1739502703.2674768,63.509939432144165,0.065,1739502703.2674785,63.509939432144165,3.1093445374240027,1739502703.2674801,63.509939432144165,-0.2697953705135101,1739502703.2674813,63.509939432144165,-0.07061274341930904,1739502703.2674825,63.509939432144165,2.0146680360783,1739502703.2674844,63.509939432144165,0.0,1739502703.2674856,63.509939432144165,-0.04557133042904171,1739502703.2674873,63.509939432144165,3.1591753574167,1739502703.2674885,63.509939432144165,2.0602393665073415 +1739502703.2874165,63.52993941307068,5.3149786312174,1739502703.287419,63.52993941307068,-0.10964062679466924,1739502703.2874224,63.52993941307068,107.30820996041838,1739502703.2874253,63.52993941307068,-0.0986735353301138,1739502703.2874265,63.52993941307068,0.065,1739502703.2874284,63.52993941307068,3.1093445374240027,1739502703.2874298,63.52993941307068,-0.2697953705135101,1739502703.2874312,63.52993941307068,-0.07061274341930904,1739502703.2874324,63.52993941307068,2.0146680360783,1739502703.287434,63.52993941307068,0.0,1739502703.2874353,63.52993941307068,-0.04557133042904171,1739502703.2874367,63.52993941307068,3.1591753574167,1739502703.2874382,63.52993941307068,2.0602393665073415 +1739502703.3075874,63.54993939399719,5.088625304328671,1739502703.3075895,63.54993939399719,-0.11346046359113338,1739502703.3075926,63.54993939399719,107.61939281969823,1739502703.3075955,63.54993939399719,-0.4000691655238664,1739502703.3075972,63.54993939399719,0.065,1739502703.3075986,63.54993939399719,3.109089912438834,1739502703.3076,63.54993939399719,-0.26637783881106597,1739502703.3076017,63.54993939399719,-0.06782476752001479,1739502703.307603,63.54993939399719,2.0201837261673883,1739502703.3076048,63.54993939399719,0.0,1739502703.307606,63.54993939399719,-0.030430519179067732,1739502703.3076077,63.54993939399719,3.157615415670529,1739502703.3076088,63.54993939399719,2.0553457519642904 +1739502703.3273492,63.569939374923706,5.088625304328671,1739502703.327352,63.569939374923706,-0.11346046359113338,1739502703.3273551,63.569939374923706,107.61939281969823,1739502703.327358,63.569939374923706,-0.4000691655238664,1739502703.3273594,63.569939374923706,0.065,1739502703.3273613,63.569939374923706,3.109089912438834,1739502703.3273625,63.569939374923706,-0.26637783881106597,1739502703.3273642,63.569939374923706,-0.06782476752001479,1739502703.3273656,63.569939374923706,2.0201837261673883,1739502703.327367,63.569939374923706,0.0,1739502703.3273687,63.569939374923706,-0.035162025796902086,1739502703.32737,63.569939374923706,3.157615415670529,1739502703.3273718,63.569939374923706,2.0553457519642904 +1739502703.3494434,63.58993935585022,5.088625304328671,1739502703.3494477,63.58993935585022,-0.11346046359113338,1739502703.3494527,63.58993935585022,107.61939281969823,1739502703.3494587,63.58993935585022,-0.4000691655238664,1739502703.349462,63.58993935585022,0.065,1739502703.349466,63.58993935585022,3.109089912438834,1739502703.3494694,63.58993935585022,-0.26637783881106597,1739502703.3494728,63.58993935585022,-0.06782476752001479,1739502703.3494759,63.58993935585022,2.0201837261673883,1739502703.3494792,63.58993935585022,0.0,1739502703.3494825,63.58993935585022,-0.035162025796902086,1739502703.349486,63.58993935585022,3.157615415670529,1739502703.3494892,63.58993935585022,2.0553457519642904 +1739502703.3692374,63.60993933677673,5.088625304328671,1739502703.3692412,63.60993933677673,-0.11346046359113338,1739502703.3692462,63.60993933677673,107.61939281969823,1739502703.3692513,63.60993933677673,-0.4000691655238664,1739502703.3692544,63.60993933677673,0.065,1739502703.369258,63.60993933677673,3.109089912438834,1739502703.369261,63.60993933677673,-0.26637783881106597,1739502703.3692641,63.60993933677673,-0.06782476752001479,1739502703.3692672,63.60993933677673,2.0201837261673883,1739502703.3692703,63.60993933677673,0.0,1739502703.3692734,63.60993933677673,-0.035162025796902086,1739502703.3692765,63.60993933677673,3.157615415670529,1739502703.3692794,63.60993933677673,2.0553457519642904 +1739502703.3898907,63.62993931770325,5.088625304328671,1739502703.3898942,63.62993931770325,-0.11346046359113338,1739502703.3898985,63.62993931770325,107.61939281969823,1739502703.3899038,63.62993931770325,-0.4000691655238664,1739502703.3899064,63.62993931770325,0.065,1739502703.38991,63.62993931770325,3.109089912438834,1739502703.389913,63.62993931770325,-0.26637783881106597,1739502703.389916,63.62993931770325,-0.06782476752001479,1739502703.389919,63.62993931770325,2.0201837261673883,1739502703.3899221,63.62993931770325,0.0,1739502703.3899248,63.62993931770325,-0.035162025796902086,1739502703.3899279,63.62993931770325,3.157615415670529,1739502703.389931,63.62993931770325,2.0553457519642904 +1739502703.4072094,63.64993929862976,4.862758551748229,1739502703.4072118,63.64993929862976,-0.11691964308037406,1739502703.4072146,63.64993929862976,107.64333815465125,1739502703.4072175,63.64993929862976,-0.41630433087978913,1739502703.4072187,63.64993929862976,0.065,1739502703.4072201,63.64993929862976,3.107145690831883,1739502703.4072218,63.64993929862976,-0.25824809335835014,1739502703.407223,63.64993929862976,-0.071070273206053,1739502703.4072244,63.64993929862976,2.0333654087615045,1739502703.4072258,63.64993929862976,0.0,1739502703.407227,63.64993929862976,-0.010381265840513257,1739502703.4072285,63.64993929862976,3.156055473924358,1739502703.40723,63.64993929862976,2.0514906671657465 +1739502703.4279003,63.669939279556274,4.862758551748229,1739502703.4279027,63.669939279556274,-0.11691964308037406,1739502703.4279056,63.669939279556274,107.64333815465125,1739502703.4279082,63.669939279556274,-0.41630433087978913,1739502703.4279094,63.669939279556274,0.065,1739502703.4279108,63.669939279556274,3.107145690831883,1739502703.4279122,63.669939279556274,-0.25824809335835014,1739502703.4279134,63.669939279556274,-0.071070273206053,1739502703.4279144,63.669939279556274,2.0333654087615045,1739502703.427916,63.669939279556274,0.0,1739502703.4279172,63.669939279556274,-0.01812525840424195,1739502703.4279187,63.669939279556274,3.156055473924358,1739502703.4279199,63.669939279556274,2.0514906671657465 +1739502703.4473004,63.68993926048279,4.862758551748229,1739502703.447303,63.68993926048279,-0.11691964308037406,1739502703.4473062,63.68993926048279,107.64333815465125,1739502703.4473093,63.68993926048279,-0.41630433087978913,1739502703.447311,63.68993926048279,0.065,1739502703.4473124,63.68993926048279,3.107145690831883,1739502703.447314,63.68993926048279,-0.25824809335835014,1739502703.4473152,63.68993926048279,-0.071070273206053,1739502703.4473164,63.68993926048279,2.0333654087615045,1739502703.4473186,63.68993926048279,0.0,1739502703.4473197,63.68993926048279,-0.01812525840424195,1739502703.4473214,63.68993926048279,3.156055473924358,1739502703.4473228,63.68993926048279,2.0514906671657465 +1739502703.4675,63.7099392414093,4.862758551748229,1739502703.4675047,63.7099392414093,-0.11691964308037406,1739502703.4675097,63.7099392414093,107.64333815465125,1739502703.4675145,63.7099392414093,-0.41630433087978913,1739502703.4675188,63.7099392414093,0.065,1739502703.4675221,63.7099392414093,3.107145690831883,1739502703.4675236,63.7099392414093,-0.25824809335835014,1739502703.4675248,63.7099392414093,-0.071070273206053,1739502703.4675262,63.7099392414093,2.0333654087615045,1739502703.4675276,63.7099392414093,0.0,1739502703.467529,63.7099392414093,-0.01812525840424195,1739502703.4675305,63.7099392414093,3.156055473924358,1739502703.4675317,63.7099392414093,2.0514906671657465 +1739502703.4874225,63.729939222335815,4.862758551748229,1739502703.487425,63.729939222335815,-0.11691964308037406,1739502703.4874282,63.729939222335815,107.64333815465125,1739502703.4874308,63.729939222335815,-0.41630433087978913,1739502703.4874325,63.729939222335815,0.065,1739502703.4874341,63.729939222335815,3.107145690831883,1739502703.4874356,63.729939222335815,-0.25824809335835014,1739502703.487437,63.729939222335815,-0.071070273206053,1739502703.4874384,63.729939222335815,2.0333654087615045,1739502703.48744,63.729939222335815,0.0,1739502703.4874418,63.729939222335815,-0.01812525840424195,1739502703.4874432,63.729939222335815,3.156055473924358,1739502703.4874444,63.729939222335815,2.0514906671657465 +1739502703.5074859,63.74993920326233,4.862758551748229,1739502703.5074885,63.74993920326233,-0.11691964308037406,1739502703.5074916,63.74993920326233,107.64333815465125,1739502703.5074947,63.74993920326233,-0.41630433087978913,1739502703.5074959,63.74993920326233,0.065,1739502703.5074978,63.74993920326233,3.107145690831883,1739502703.5074997,63.74993920326233,-0.25824809335835014,1739502703.5075011,63.74993920326233,-0.071070273206053,1739502703.5075023,63.74993920326233,2.0333654087615045,1739502703.507504,63.74993920326233,0.0,1739502703.5075054,63.74993920326233,-0.01812525840424195,1739502703.5075068,63.74993920326233,3.156055473924358,1739502703.5075083,63.74993920326233,2.0514906671657465 +1739502703.527605,63.76993918418884,4.63720069758525,1739502703.527607,63.76993918418884,-0.1200221330218536,1739502703.5276098,63.76993918418884,108.02514672260311,1739502703.5276127,63.76993918418884,-0.7944505312137902,1739502703.5276139,63.76993918418884,0.065,1739502703.5276158,63.76993918418884,3.1075421204419786,1739502703.5276172,63.76993918418884,-0.2550887233079274,1739502703.5276186,63.76993918418884,-0.06631539305799157,1739502703.5276198,63.76993918418884,2.038511232065328,1739502703.5276217,63.76993918418884,0.0,1739502703.527623,63.76993918418884,-0.007976881397600367,1739502703.5276244,63.76993918418884,3.1544955321781867,1739502703.5276258,63.76993918418884,2.049659483356816 +1739502703.547573,63.789939165115356,4.63720069758525,1739502703.5475755,63.789939165115356,-0.1200221330218536,1739502703.5475783,63.789939165115356,108.02514672260311,1739502703.547581,63.789939165115356,-0.7944505312137902,1739502703.5475824,63.789939165115356,0.065,1739502703.547584,63.789939165115356,3.1075421204419786,1739502703.5475855,63.789939165115356,-0.2550887233079274,1739502703.547587,63.789939165115356,-0.06631539305799157,1739502703.547588,63.789939165115356,2.038511232065328,1739502703.5475895,63.789939165115356,0.0,1739502703.547591,63.789939165115356,-0.011148251291487998,1739502703.5475924,63.789939165115356,3.1544955321781867,1739502703.5475938,63.789939165115356,2.049659483356816 +1739502703.567315,63.80993914604187,4.63720069758525,1739502703.5673177,63.80993914604187,-0.1200221330218536,1739502703.5673208,63.80993914604187,108.02514672260311,1739502703.5673234,63.80993914604187,-0.7944505312137902,1739502703.5673249,63.80993914604187,0.065,1739502703.5673265,63.80993914604187,3.1075421204419786,1739502703.5673277,63.80993914604187,-0.2550887233079274,1739502703.567329,63.80993914604187,-0.06631539305799157,1739502703.5673304,63.80993914604187,2.038511232065328,1739502703.5673318,63.80993914604187,0.0,1739502703.5673332,63.80993914604187,-0.011148251291487998,1739502703.5673347,63.80993914604187,3.1544955321781867,1739502703.5673358,63.80993914604187,2.049659483356816 +1739502703.5873675,63.829939126968384,4.63720069758525,1739502703.58737,63.829939126968384,-0.1200221330218536,1739502703.587373,63.829939126968384,108.02514672260311,1739502703.5873759,63.829939126968384,-0.7944505312137902,1739502703.587377,63.829939126968384,0.065,1739502703.587379,63.829939126968384,3.1075421204419786,1739502703.5873802,63.829939126968384,-0.2550887233079274,1739502703.5873818,63.829939126968384,-0.06631539305799157,1739502703.5873828,63.829939126968384,2.038511232065328,1739502703.5873845,63.829939126968384,0.0,1739502703.587386,63.829939126968384,-0.011148251291487998,1739502703.587387,63.829939126968384,3.1544955321781867,1739502703.5873885,63.829939126968384,2.049659483356816 +1739502703.6072817,63.8499391078949,4.63720069758525,1739502703.6072843,63.8499391078949,-0.1200221330218536,1739502703.6072874,63.8499391078949,108.02514672260311,1739502703.60729,63.8499391078949,-0.7944505312137902,1739502703.6072915,63.8499391078949,0.065,1739502703.6072931,63.8499391078949,3.1075421204419786,1739502703.6072948,63.8499391078949,-0.2550887233079274,1739502703.6072965,63.8499391078949,-0.06631539305799157,1739502703.6072974,63.8499391078949,2.038511232065328,1739502703.6072993,63.8499391078949,0.0,1739502703.6073005,63.8499391078949,-0.011148251291487998,1739502703.607302,63.8499391078949,3.1544955321781867,1739502703.6073034,63.8499391078949,2.049659483356816 +1739502703.6274621,63.86993908882141,4.411817492289305,1739502703.6274643,63.86993908882141,-0.12277056702030009,1739502703.627467,63.86993908882141,108.04385627707669,1739502703.6274695,63.86993908882141,-0.8107095019584629,1739502703.6274712,63.86993908882141,0.065,1739502703.6274726,63.86993908882141,3.105654166273178,1739502703.6274738,63.86993908882141,-0.2469960112228094,1739502703.6274755,63.86993908882141,-0.06944662482701788,1739502703.6274765,63.86993908882141,2.0517517139674686,1739502703.6274781,63.86993908882141,0.0,1739502703.6274796,63.86993908882141,0.009892880457944654,1739502703.627481,63.86993908882141,3.1529355904320155,1739502703.6274824,63.86993908882141,2.0484341914923623 +1739502703.6473136,63.889939069747925,4.411817492289305,1739502703.6473165,63.889939069747925,-0.12277056702030009,1739502703.6473198,63.889939069747925,108.04385627707669,1739502703.6473224,63.889939069747925,-0.8107095019584629,1739502703.6473238,63.889939069747925,0.065,1739502703.6473258,63.889939069747925,3.105654166273178,1739502703.6473272,63.889939069747925,-0.2469960112228094,1739502703.6473286,63.889939069747925,-0.06944662482701788,1739502703.6473298,63.889939069747925,2.0517517139674686,1739502703.6473312,63.889939069747925,0.0,1739502703.6473327,63.889939069747925,0.003317522475106305,1739502703.647334,63.889939069747925,3.1529355904320155,1739502703.6473355,63.889939069747925,2.0484341914923623 +1739502703.667504,63.90993905067444,4.411817492289305,1739502703.667507,63.90993905067444,-0.12277056702030009,1739502703.6675103,63.90993905067444,108.04385627707669,1739502703.6675134,63.90993905067444,-0.8107095019584629,1739502703.6675146,63.90993905067444,0.065,1739502703.6675167,63.90993905067444,3.105654166273178,1739502703.667518,63.90993905067444,-0.2469960112228094,1739502703.6675196,63.90993905067444,-0.06944662482701788,1739502703.6675205,63.90993905067444,2.0517517139674686,1739502703.6675222,63.90993905067444,0.0,1739502703.6675236,63.90993905067444,0.003317522475106305,1739502703.667525,63.90993905067444,3.1529355904320155,1739502703.6675267,63.90993905067444,2.0484341914923623 +1739502703.687386,63.92993903160095,4.411817492289305,1739502703.6873891,63.92993903160095,-0.12277056702030009,1739502703.6873922,63.92993903160095,108.04385627707669,1739502703.687395,63.92993903160095,-0.8107095019584629,1739502703.6873965,63.92993903160095,0.065,1739502703.6873984,63.92993903160095,3.105654166273178,1739502703.6873996,63.92993903160095,-0.2469960112228094,1739502703.6874013,63.92993903160095,-0.06944662482701788,1739502703.6874025,63.92993903160095,2.0517517139674686,1739502703.6874044,63.92993903160095,0.0,1739502703.6874056,63.92993903160095,0.003317522475106305,1739502703.687407,63.92993903160095,3.1529355904320155,1739502703.6874084,63.92993903160095,2.0484341914923623 +1739502703.7077768,63.949939012527466,4.411817492289305,1739502703.7077806,63.949939012527466,-0.12277056702030009,1739502703.707784,63.949939012527466,108.04385627707669,1739502703.7077875,63.949939012527466,-0.8107095019584629,1739502703.707789,63.949939012527466,0.065,1739502703.7077913,63.949939012527466,3.105654166273178,1739502703.7077932,63.949939012527466,-0.2469960112228094,1739502703.7077951,63.949939012527466,-0.06944662482701788,1739502703.7077968,63.949939012527466,2.0517517139674686,1739502703.7077987,63.949939012527466,0.0,1739502703.7078004,63.949939012527466,0.003317522475106305,1739502703.707802,63.949939012527466,3.1529355904320155,1739502703.707804,63.949939012527466,2.0484341914923623 +1739502703.728531,63.96993899345398,4.411817492289305,1739502703.7285337,63.96993899345398,-0.12277056702030009,1739502703.728537,63.96993899345398,108.04385627707669,1739502703.7285402,63.96993899345398,-0.8107095019584629,1739502703.7285416,63.96993899345398,0.065,1739502703.728544,63.96993899345398,3.105654166273178,1739502703.728546,63.96993899345398,-0.2469960112228094,1739502703.7285473,63.96993899345398,-0.06944662482701788,1739502703.7285488,63.96993899345398,2.0517517139674686,1739502703.7285507,63.96993899345398,0.0,1739502703.7285523,63.96993899345398,0.003317522475106305,1739502703.728554,63.96993899345398,3.1529355904320155,1739502703.7285557,63.96993899345398,2.0484341914923623 +1739502703.7479532,63.98993897438049,4.186471853868161,1739502703.7479565,63.98993897438049,-0.12516694767297132,1739502703.7479613,63.98993897438049,108.4565589482467,1739502703.7479646,63.98993897438049,-1.2243994673469625,1739502703.7479663,63.98993897438049,0.065,1739502703.7479684,63.98993897438049,3.106461766790521,1739502703.7479703,63.98993897438049,-0.24309153082962062,1739502703.747972,63.98993897438049,-0.06367886263747273,1739502703.7479737,63.98993897438049,2.058170553112274,1739502703.7479753,63.98993897438049,0.0,1739502703.747977,63.98993897438049,0.011935986186242201,1739502703.7479787,63.98993897438049,3.1513756486858444,1739502703.7479808,63.98993897438049,2.048927838601608 +1739502703.7676573,64.009938955307,4.186471853868161,1739502703.7676601,64.009938955307,-0.12516694767297132,1739502703.767663,64.009938955307,108.4565589482467,1739502703.7676659,64.009938955307,-1.2243994673469625,1739502703.7676675,64.009938955307,0.065,1739502703.7676692,64.009938955307,3.106461766790521,1739502703.7676709,64.009938955307,-0.24309153082962062,1739502703.7676723,64.009938955307,-0.06367886263747273,1739502703.7676735,64.009938955307,2.058170553112274,1739502703.7676752,64.009938955307,0.0,1739502703.7676764,64.009938955307,0.009242714510665717,1739502703.767678,64.009938955307,3.1513756486858444,1739502703.7676795,64.009938955307,2.048927838601608 +1739502703.7874637,64.02993893623352,4.186471853868161,1739502703.7874665,64.02993893623352,-0.12516694767297132,1739502703.7874706,64.02993893623352,108.4565589482467,1739502703.7874737,64.02993893623352,-1.2243994673469625,1739502703.787475,64.02993893623352,0.065,1739502703.787477,64.02993893623352,3.106461766790521,1739502703.7874784,64.02993893623352,-0.24309153082962062,1739502703.7874804,64.02993893623352,-0.06367886263747273,1739502703.7874815,64.02993893623352,2.058170553112274,1739502703.7874835,64.02993893623352,0.0,1739502703.787485,64.02993893623352,0.009242714510665717,1739502703.7874866,64.02993893623352,3.1513756486858444,1739502703.787488,64.02993893623352,2.048927838601608 +1739502703.8074574,64.04993891716003,4.186471853868161,1739502703.8074605,64.04993891716003,-0.12516694767297132,1739502703.807464,64.04993891716003,108.4565589482467,1739502703.8074667,64.04993891716003,-1.2243994673469625,1739502703.8074682,64.04993891716003,0.065,1739502703.80747,64.04993891716003,3.106461766790521,1739502703.8074715,64.04993891716003,-0.24309153082962062,1739502703.8074732,64.04993891716003,-0.06367886263747273,1739502703.8074746,64.04993891716003,2.058170553112274,1739502703.8074763,64.04993891716003,0.0,1739502703.8074777,64.04993891716003,0.009242714510665717,1739502703.8074794,64.04993891716003,3.1513756486858444,1739502703.8074806,64.04993891716003,2.048927838601608 +1739502703.8275766,64.06993889808655,4.186471853868161,1739502703.82758,64.06993889808655,-0.12516694767297132,1739502703.8275833,64.06993889808655,108.4565589482467,1739502703.8275864,64.06993889808655,-1.2243994673469625,1739502703.8275878,64.06993889808655,0.065,1739502703.8275898,64.06993889808655,3.106461766790521,1739502703.8275912,64.06993889808655,-0.24309153082962062,1739502703.8275926,64.06993889808655,-0.06367886263747273,1739502703.8275943,64.06993889808655,2.058170553112274,1739502703.8275957,64.06993889808655,0.0,1739502703.8275974,64.06993889808655,0.009242714510665717,1739502703.8275988,64.06993889808655,3.1513756486858444,1739502703.8276005,64.06993889808655,2.048927838601608 +1739502703.8474813,64.08993887901306,3.9610497810537746,1739502703.8474844,64.08993887901306,-0.127212453332338,1739502703.8474874,64.08993887901306,108.47977946725223,1739502703.84749,64.08993887901306,-1.2496327387905874,1739502703.8474915,64.08993887901306,0.065,1739502703.8474934,64.08993887901306,3.104721218752833,1739502703.8474948,64.08993887901306,-0.2350531922675907,1739502703.8474965,64.08993887901306,-0.06638602928407587,1739502703.847498,64.08993887901306,2.071448618166799,1739502703.8474998,64.08993887901306,0.0,1739502703.8475013,64.08993887901306,0.027092449045553958,1739502703.847503,64.08993887901306,3.1498157069396733,1739502703.8475041,64.08993887901306,2.049934214820649 +1739502703.872414,64.10993885993958,3.9610497810537746,1739502703.8724236,64.10993885993958,-0.127212453332338,1739502703.872434,64.10993885993958,108.47977946725223,1739502703.872444,64.10993885993958,-1.2496327387905874,1739502703.8724487,64.10993885993958,0.065,1739502703.872455,64.10993885993958,3.104721218752833,1739502703.8724606,64.10993885993958,-0.2350531922675907,1739502703.8724654,64.10993885993958,-0.06638602928407587,1739502703.87247,64.10993885993958,2.071448618166799,1739502703.8724754,64.10993885993958,0.0,1739502703.8724802,64.10993885993958,0.021514403346149624,1739502703.8724854,64.10993885993958,3.1498157069396733,1739502703.8724902,64.10993885993958,2.049934214820649 +1739502703.8906693,64.11993885040283,3.9610497810537746,1739502703.8906739,64.11993885040283,-0.127212453332338,1739502703.8906798,64.11993885040283,108.47977946725223,1739502703.890685,64.11993885040283,-1.2496327387905874,1739502703.890688,64.11993885040283,0.065,1739502703.8906913,64.11993885040283,3.104721218752833,1739502703.8906941,64.11993885040283,-0.2350531922675907,1739502703.8906968,64.11993885040283,-0.06638602928407587,1739502703.8906991,64.11993885040283,2.071448618166799,1739502703.890702,64.11993885040283,0.0,1739502703.8907049,64.11993885040283,0.021514403346149624,1739502703.8907077,64.11993885040283,3.1498157069396733,1739502703.8907106,64.11993885040283,2.049934214820649 +1739502703.9089267,64.1499388217926,3.9610497810537746,1739502703.9089303,64.1499388217926,-0.127212453332338,1739502703.9089346,64.1499388217926,108.47977946725223,1739502703.9089386,64.1499388217926,-1.2496327387905874,1739502703.9089408,64.1499388217926,0.065,1739502703.9089437,64.1499388217926,3.104721218752833,1739502703.9089456,64.1499388217926,-0.2350531922675907,1739502703.908948,64.1499388217926,-0.06638602928407587,1739502703.9089499,64.1499388217926,2.071448618166799,1739502703.9089522,64.1499388217926,0.0,1739502703.9089544,64.1499388217926,0.021514403346149624,1739502703.9089568,64.1499388217926,3.1498157069396733,1739502703.908959,64.1499388217926,2.049934214820649 +1739502703.9291074,64.16993880271912,3.9610497810537746,1739502703.9291108,64.16993880271912,-0.127212453332338,1739502703.9291146,64.16993880271912,108.47977946725223,1739502703.9291182,64.16993880271912,-1.2496327387905874,1739502703.92912,64.16993880271912,0.065,1739502703.9291222,64.16993880271912,3.104721218752833,1739502703.9291244,64.16993880271912,-0.2350531922675907,1739502703.9291263,64.16993880271912,-0.06638602928407587,1739502703.9291277,64.16993880271912,2.071448618166799,1739502703.9291298,64.16993880271912,0.0,1739502703.9291315,64.16993880271912,0.021514403346149624,1739502703.9291337,64.16993880271912,3.1498157069396733,1739502703.9291356,64.16993880271912,2.049934214820649 +1739502703.949089,64.18993878364563,3.9610497810537746,1739502703.9490924,64.18993878364563,-0.127212453332338,1739502703.949096,64.18993878364563,108.47977946725223,1739502703.9490998,64.18993878364563,-1.2496327387905874,1739502703.9491017,64.18993878364563,0.065,1739502703.9491038,64.18993878364563,3.104721218752833,1739502703.9491057,64.18993878364563,-0.2350531922675907,1739502703.9491074,64.18993878364563,-0.06638602928407587,1739502703.9491093,64.18993878364563,2.071448618166799,1739502703.9491112,64.18993878364563,0.0,1739502703.9491131,64.18993878364563,0.021514403346149624,1739502703.9491148,64.18993878364563,3.1498157069396733,1739502703.949117,64.18993878364563,2.049934214820649 +1739502703.9700682,64.20993876457214,3.7354348451228407,1739502703.9700723,64.20993876457214,-0.12890771884868357,1739502703.9700773,64.20993876457214,108.87687748548294,1739502703.9700818,64.20993876457214,-1.6516636451934015,1739502703.9700842,64.20993876457214,0.065,1739502703.9700866,64.20993876457214,3.105613352275686,1739502703.970089,64.20993876457214,-0.22979798725620312,1739502703.9700913,64.20993876457214,-0.06072618069245609,1739502703.9700937,64.20993876457214,2.080175659997404,1739502703.9700963,64.20993876457214,0.0,1739502703.9700987,64.20993876457214,0.030620730052122284,1739502703.9701009,64.20993876457214,3.148255765193502,1739502703.9701033,64.20993876457214,2.0524006589067034 +1739502703.9895706,64.22993874549866,3.7354348451228407,1739502703.9895747,64.22993874549866,-0.12890771884868357,1739502703.9895794,64.22993874549866,108.87687748548294,1739502703.9895842,64.22993874549866,-1.6516636451934015,1739502703.9895864,64.22993874549866,0.065,1739502703.9895895,64.22993874549866,3.105613352275686,1739502703.989592,64.22993874549866,-0.22979798725620312,1739502703.9895947,64.22993874549866,-0.06072618069245609,1739502703.989597,64.22993874549866,2.080175659997404,1739502703.9896002,64.22993874549866,0.0,1739502703.9896028,64.22993874549866,0.027775001090700524,1739502703.9896054,64.22993874549866,3.148255765193502,1739502703.9896076,64.22993874549866,2.0524006589067034 +1739502704.0092943,64.24993872642517,3.7354348451228407,1739502704.009299,64.24993872642517,-0.12890771884868357,1739502704.0093036,64.24993872642517,108.87687748548294,1739502704.0093079,64.24993872642517,-1.6516636451934015,1739502704.0093102,64.24993872642517,0.065,1739502704.009313,64.24993872642517,3.105613352275686,1739502704.0093157,64.24993872642517,-0.22979798725620312,1739502704.009318,64.24993872642517,-0.06072618069245609,1739502704.0093212,64.24993872642517,2.080175659997404,1739502704.009324,64.24993872642517,0.0,1739502704.0093262,64.24993872642517,0.027775001090700524,1739502704.0093296,64.24993872642517,3.148255765193502,1739502704.0093322,64.24993872642517,2.0524006589067034 +1739502704.0307176,64.26993870735168,3.7354348451228407,1739502704.0307245,64.26993870735168,-0.12890771884868357,1739502704.0307314,64.26993870735168,108.87687748548294,1739502704.030737,64.26993870735168,-1.6516636451934015,1739502704.0307395,64.26993870735168,0.065,1739502704.0307434,64.26993870735168,3.105613352275686,1739502704.0307465,64.26993870735168,-0.22979798725620312,1739502704.03075,64.26993870735168,-0.06072618069245609,1739502704.0307522,64.26993870735168,2.080175659997404,1739502704.0307562,64.26993870735168,0.0,1739502704.03076,64.26993870735168,0.027775001090700524,1739502704.0307639,64.26993870735168,3.148255765193502,1739502704.030767,64.26993870735168,2.0524006589067034 +1739502704.0505517,64.2899386882782,3.7354348451228407,1739502704.0505557,64.2899386882782,-0.12890771884868357,1739502704.0505605,64.2899386882782,108.87687748548294,1739502704.0505657,64.2899386882782,-1.6516636451934015,1739502704.0505683,64.2899386882782,0.065,1739502704.0505724,64.2899386882782,3.105613352275686,1739502704.050576,64.2899386882782,-0.22979798725620312,1739502704.0505793,64.2899386882782,-0.06072618069245609,1739502704.0505824,64.2899386882782,2.080175659997404,1739502704.0505862,64.2899386882782,0.0,1739502704.0505898,64.2899386882782,0.027775001090700524,1739502704.0505934,64.2899386882782,3.148255765193502,1739502704.050597,64.2899386882782,2.0524006589067034 +1739502704.0700045,64.30993866920471,3.5095240909689966,1739502704.0700083,64.30993866920471,-0.13025277449007877,1739502704.070013,64.30993866920471,109.1818177456125,1739502704.0700173,64.30993866920471,-1.962671083416914,1739502704.0700195,64.30993866920471,0.065,1739502704.0700226,64.30993866920471,3.105926897696744,1739502704.070025,64.30993866920471,-0.2231756523366671,1739502704.0700276,64.30993866920471,-0.057158360105618825,1739502704.07003,64.30993866920471,2.091225400114128,1739502704.0700328,64.30993866920471,0.0,1739502704.070035,64.30993866920471,0.0394348606670638,1739502704.0700376,64.30993866920471,3.146695823447331,1739502704.0700397,64.30993866920471,2.0554342479536793 +1739502704.0903203,64.32993865013123,3.5095240909689966,1739502704.0903249,64.32993865013123,-0.13025277449007877,1739502704.09033,64.32993865013123,109.1818177456125,1739502704.0903347,64.32993865013123,-1.962671083416914,1739502704.0903373,64.32993865013123,0.065,1739502704.0903404,64.32993865013123,3.105926897696744,1739502704.090343,64.32993865013123,-0.2231756523366671,1739502704.0903454,64.32993865013123,-0.057158360105618825,1739502704.0903478,64.32993865013123,2.091225400114128,1739502704.0903509,64.32993865013123,0.0,1739502704.0903533,64.32993865013123,0.035791152160448814,1739502704.0903559,64.32993865013123,3.146695823447331,1739502704.0903583,64.32993865013123,2.0554342479536793 +1739502704.1099308,64.34993863105774,3.5095240909689966,1739502704.109935,64.34993863105774,-0.13025277449007877,1739502704.10994,64.34993863105774,109.1818177456125,1739502704.1099446,64.34993863105774,-1.962671083416914,1739502704.1099472,64.34993863105774,0.065,1739502704.1099503,64.34993863105774,3.105926897696744,1739502704.109953,64.34993863105774,-0.2231756523366671,1739502704.1099555,64.34993863105774,-0.057158360105618825,1739502704.1099582,64.34993863105774,2.091225400114128,1739502704.109961,64.34993863105774,0.0,1739502704.109964,64.34993863105774,0.035791152160448814,1739502704.1099665,64.34993863105774,3.146695823447331,1739502704.1099691,64.34993863105774,2.0554342479536793 +1739502704.1294546,64.36993861198425,3.5095240909689966,1739502704.1294577,64.36993861198425,-0.13025277449007877,1739502704.1294618,64.36993861198425,109.1818177456125,1739502704.1294663,64.36993861198425,-1.962671083416914,1739502704.1294692,64.36993861198425,0.065,1739502704.1294725,64.36993861198425,3.105926897696744,1739502704.1294756,64.36993861198425,-0.2231756523366671,1739502704.1294787,64.36993861198425,-0.057158360105618825,1739502704.1294818,64.36993861198425,2.091225400114128,1739502704.1294851,64.36993861198425,0.0,1739502704.1294882,64.36993861198425,0.035791152160448814,1739502704.129491,64.36993861198425,3.146695823447331,1739502704.1294947,64.36993861198425,2.0554342479536793 +1739502704.1497414,64.38993859291077,3.5095240909689966,1739502704.149745,64.38993859291077,-0.13025277449007877,1739502704.149749,64.38993859291077,109.1818177456125,1739502704.1497536,64.38993859291077,-1.962671083416914,1739502704.1497564,64.38993859291077,0.065,1739502704.1497598,64.38993859291077,3.105926897696744,1739502704.149763,64.38993859291077,-0.2231756523366671,1739502704.1497662,64.38993859291077,-0.057158360105618825,1739502704.1497693,64.38993859291077,2.091225400114128,1739502704.1497726,64.38993859291077,0.0,1739502704.1497755,64.38993859291077,0.035791152160448814,1739502704.1497786,64.38993859291077,3.146695823447331,1739502704.149782,64.38993859291077,2.0554342479536793 +1739502704.1696243,64.40993857383728,3.5095240909689966,1739502704.1696277,64.40993857383728,-0.13025277449007877,1739502704.1696317,64.40993857383728,109.1818177456125,1739502704.169637,64.40993857383728,-1.962671083416914,1739502704.1696396,64.40993857383728,0.065,1739502704.1696432,64.40993857383728,3.105926897696744,1739502704.1696465,64.40993857383728,-0.2231756523366671,1739502704.1696496,64.40993857383728,-0.057158360105618825,1739502704.169653,64.40993857383728,2.091225400114128,1739502704.1696563,64.40993857383728,0.0,1739502704.1696596,64.40993857383728,0.035791152160448814,1739502704.169663,64.40993857383728,3.146695823447331,1739502704.1696663,64.40993857383728,2.0554342479536793 +1739502704.1898246,64.4299385547638,3.2832253205519537,1739502704.189828,64.4299385547638,-0.13124710522716043,1739502704.1898324,64.4299385547638,109.2053538120666,1739502704.189838,64.4299385547638,-1.994189912850366,1739502704.1898403,64.4299385547638,0.065,1739502704.1898441,64.4299385547638,3.104423563469736,1739502704.1898475,64.4299385547638,-0.21494492022389952,1739502704.1898506,64.4299385547638,-0.05918196713756528,1739502704.189854,64.4299385547638,2.1050406870134633,1739502704.1898572,64.4299385547638,0.0,1739502704.1898603,64.4299385547638,0.050080473378509294,1739502704.189864,64.4299385547638,3.14513588170116,1739502704.1898673,64.4299385547638,2.0594256294433526 +1739502704.2096581,64.44993853569031,3.2832253205519537,1739502704.2096615,64.44993853569031,-0.13124710522716043,1739502704.2096658,64.44993853569031,109.2053538120666,1739502704.2096705,64.44993853569031,-1.994189912850366,1739502704.2096734,64.44993853569031,0.065,1739502704.209677,64.44993853569031,3.104423563469736,1739502704.2096803,64.44993853569031,-0.21494492022389952,1739502704.2096837,64.44993853569031,-0.05918196713756528,1739502704.2096868,64.44993853569031,2.1050406870134633,1739502704.2096903,64.44993853569031,0.0,1739502704.2096934,64.44993853569031,0.04561505757011064,1739502704.2096968,64.44993853569031,3.14513588170116,1739502704.2097,64.44993853569031,2.0594256294433526 +1739502704.2295275,64.46993851661682,3.2832253205519537,1739502704.2295308,64.46993851661682,-0.13124710522716043,1739502704.2295353,64.46993851661682,109.2053538120666,1739502704.2295403,64.46993851661682,-1.994189912850366,1739502704.229543,64.46993851661682,0.065,1739502704.2295468,64.46993851661682,3.104423563469736,1739502704.22955,64.46993851661682,-0.21494492022389952,1739502704.2295532,64.46993851661682,-0.05918196713756528,1739502704.2295563,64.46993851661682,2.1050406870134633,1739502704.2295597,64.46993851661682,0.0,1739502704.229563,64.46993851661682,0.04561505757011064,1739502704.229566,64.46993851661682,3.14513588170116,1739502704.2295694,64.46993851661682,2.0594256294433526 +1739502704.2492568,64.48993849754333,3.2832253205519537,1739502704.24926,64.48993849754333,-0.13124710522716043,1739502704.2492642,64.48993849754333,109.2053538120666,1739502704.249269,64.48993849754333,-1.994189912850366,1739502704.2492716,64.48993849754333,0.065,1739502704.249275,64.48993849754333,3.104423563469736,1739502704.249278,64.48993849754333,-0.21494492022389952,1739502704.2492812,64.48993849754333,-0.05918196713756528,1739502704.2492843,64.48993849754333,2.1050406870134633,1739502704.2492874,64.48993849754333,0.0,1739502704.2492905,64.48993849754333,0.04561505757011064,1739502704.2492938,64.48993849754333,3.14513588170116,1739502704.2492971,64.48993849754333,2.0594256294433526 +1739502704.270973,64.50993847846985,3.2832253205519537,1739502704.2709765,64.50993847846985,-0.13124710522716043,1739502704.2709808,64.50993847846985,109.2053538120666,1739502704.270986,64.50993847846985,-1.994189912850366,1739502704.2709887,64.50993847846985,0.065,1739502704.2709923,64.50993847846985,3.104423563469736,1739502704.2709956,64.50993847846985,-0.21494492022389952,1739502704.2709987,64.50993847846985,-0.05918196713756528,1739502704.271002,64.50993847846985,2.1050406870134633,1739502704.2710054,64.50993847846985,0.0,1739502704.2710085,64.50993847846985,0.04561505757011064,1739502704.2710118,64.50993847846985,3.14513588170116,1739502704.2710152,64.50993847846985,2.0594256294433526 +1739502704.2898562,64.52993845939636,3.0564418179771966,1739502704.28986,64.52993845939636,-0.13188977703805893,1739502704.2898645,64.52993845939636,109.50939174658738,1739502704.2898695,64.52993845939636,-2.308192847008122,1739502704.2898724,64.52993845939636,0.065,1739502704.2898757,64.52993845939636,3.1049076866693643,1739502704.289879,64.52993845939636,-0.20752898962292887,1739502704.2898824,64.52993845939636,-0.05530009739978756,1739502704.2898858,64.52993845939636,2.1175664749411145,1739502704.289889,64.52993845939636,0.0,1739502704.2898924,64.52993845939636,0.0565871162715442,1739502704.2898958,64.52993845939636,3.1435759399549887,1739502704.289899,64.52993845939636,2.0644081292618455 +1739502704.3092961,64.54993844032288,3.0564418179771966,1739502704.3092997,64.54993844032288,-0.13188977703805893,1739502704.3093038,64.54993844032288,109.50939174658738,1739502704.3093085,64.54993844032288,-2.308192847008122,1739502704.309311,64.54993844032288,0.065,1739502704.3093143,64.54993844032288,3.1049076866693643,1739502704.3093176,64.54993844032288,-0.20752898962292887,1739502704.3093207,64.54993844032288,-0.05530009739978756,1739502704.3093238,64.54993844032288,2.1175664749411145,1739502704.3093271,64.54993844032288,0.0,1739502704.3093302,64.54993844032288,0.053158345679269026,1739502704.3093333,64.54993844032288,3.1435759399549887,1739502704.3093364,64.54993844032288,2.0644081292618455 +1739502704.3293436,64.56993842124939,3.0564418179771966,1739502704.3293464,64.56993842124939,-0.13188977703805893,1739502704.3293505,64.56993842124939,109.50939174658738,1739502704.329355,64.56993842124939,-2.308192847008122,1739502704.3293579,64.56993842124939,0.065,1739502704.3293612,64.56993842124939,3.1049076866693643,1739502704.3293645,64.56993842124939,-0.20752898962292887,1739502704.3293679,64.56993842124939,-0.05530009739978756,1739502704.329371,64.56993842124939,2.1175664749411145,1739502704.3293738,64.56993842124939,0.0,1739502704.329377,64.56993842124939,0.053158345679269026,1739502704.3293803,64.56993842124939,3.1435759399549887,1739502704.3293834,64.56993842124939,2.0644081292618455 +1739502704.3478193,64.5899384021759,3.0564418179771966,1739502704.3478222,64.5899384021759,-0.13188977703805893,1739502704.3478248,64.5899384021759,109.50939174658738,1739502704.3478274,64.5899384021759,-2.308192847008122,1739502704.3478286,64.5899384021759,0.065,1739502704.3478303,64.5899384021759,3.1049076866693643,1739502704.3478317,64.5899384021759,-0.20752898962292887,1739502704.3478332,64.5899384021759,-0.05530009739978756,1739502704.347834,64.5899384021759,2.1175664749411145,1739502704.3478363,64.5899384021759,0.0,1739502704.3478372,64.5899384021759,0.053158345679269026,1739502704.3478386,64.5899384021759,3.1435759399549887,1739502704.34784,64.5899384021759,2.0644081292618455 +1739502704.367746,64.60993838310242,3.0564418179771966,1739502704.367749,64.60993838310242,-0.13188977703805893,1739502704.3677526,64.60993838310242,109.50939174658738,1739502704.367755,64.60993838310242,-2.308192847008122,1739502704.3677564,64.60993838310242,0.065,1739502704.367758,64.60993838310242,3.1049076866693643,1739502704.3677597,64.60993838310242,-0.20752898962292887,1739502704.367761,64.60993838310242,-0.05530009739978756,1739502704.367762,64.60993838310242,2.1175664749411145,1739502704.3677638,64.60993838310242,0.0,1739502704.367765,64.60993838310242,0.053158345679269026,1739502704.3677666,64.60993838310242,3.1435759399549887,1739502704.3677678,64.60993838310242,2.0644081292618455 +1739502704.387737,64.62993836402893,3.0564418179771966,1739502704.3877394,64.62993836402893,-0.13188977703805893,1739502704.387742,64.62993836402893,109.50939174658738,1739502704.3877444,64.62993836402893,-2.308192847008122,1739502704.3877459,64.62993836402893,0.065,1739502704.3877475,64.62993836402893,3.1049076866693643,1739502704.3877494,64.62993836402893,-0.20752898962292887,1739502704.3877506,64.62993836402893,-0.05530009739978756,1739502704.3877518,64.62993836402893,2.1175664749411145,1739502704.3877535,64.62993836402893,0.0,1739502704.3877544,64.62993836402893,0.053158345679269026,1739502704.387756,64.62993836402893,3.1435759399549887,1739502704.3877573,64.62993836402893,2.0644081292618455 +1739502704.4078765,64.64993834495544,2.8290590703242344,1739502704.4078786,64.64993834495544,-0.1321794300237844,1739502704.4078813,64.64993834495544,109.62709741107713,1739502704.4078841,64.64993834495544,-2.437676057107843,1739502704.4078853,64.64993834495544,0.065,1739502704.4078867,64.64993834495544,3.104171485257836,1739502704.4078884,64.64993834495544,-0.19940905626389288,1739502704.40789,64.64993834495544,-0.055127202376807495,1739502704.4078915,64.64993834495544,2.131366848586526,1739502704.407893,64.64993834495544,0.0,1739502704.4078944,64.64993834495544,0.06466613214948479,1739502704.4078956,64.64993834495544,3.1420159982088176,1739502704.407897,64.64993834495544,2.0702969020668265 +1739502704.4278684,64.66993832588196,2.8290590703242344,1739502704.4278708,64.66993832588196,-0.1321794300237844,1739502704.427874,64.66993832588196,109.62709741107713,1739502704.4278767,64.66993832588196,-2.437676057107843,1739502704.4278781,64.66993832588196,0.065,1739502704.4278796,64.66993832588196,3.104171485257836,1739502704.427881,64.66993832588196,-0.19940905626389288,1739502704.4278824,64.66993832588196,-0.055127202376807495,1739502704.4278839,64.66993832588196,2.131366848586526,1739502704.4278853,64.66993832588196,0.0,1739502704.4278865,64.66993832588196,0.061069946519699325,1739502704.4278882,64.66993832588196,3.1420159982088176,1739502704.4278896,64.66993832588196,2.0702969020668265 +1739502704.4478133,64.68993830680847,2.8290590703242344,1739502704.4478157,64.68993830680847,-0.1321794300237844,1739502704.4478183,64.68993830680847,109.62709741107713,1739502704.447821,64.68993830680847,-2.437676057107843,1739502704.4478223,64.68993830680847,0.065,1739502704.4478242,64.68993830680847,3.104171485257836,1739502704.4478254,64.68993830680847,-0.19940905626389288,1739502704.4478269,64.68993830680847,-0.055127202376807495,1739502704.4478283,64.68993830680847,2.131366848586526,1739502704.4478297,64.68993830680847,0.0,1739502704.4478314,64.68993830680847,0.061069946519699325,1739502704.4478328,64.68993830680847,3.1420159982088176,1739502704.447834,64.68993830680847,2.0702969020668265 +1739502704.4680307,64.70993828773499,2.8290590703242344,1739502704.468033,64.70993828773499,-0.1321794300237844,1739502704.468036,64.70993828773499,109.62709741107713,1739502704.4680388,64.70993828773499,-2.437676057107843,1739502704.4680402,64.70993828773499,0.065,1739502704.468042,64.70993828773499,3.104171485257836,1739502704.4680433,64.70993828773499,-0.19940905626389288,1739502704.4680448,64.70993828773499,-0.055127202376807495,1739502704.4680462,64.70993828773499,2.131366848586526,1739502704.4680476,64.70993828773499,0.0,1739502704.468049,64.70993828773499,0.061069946519699325,1739502704.4680505,64.70993828773499,3.1420159982088176,1739502704.468052,64.70993828773499,2.0702969020668265 +1739502704.4882393,64.7299382686615,2.8290590703242344,1739502704.4882421,64.7299382686615,-0.1321794300237844,1739502704.488245,64.7299382686615,109.62709741107713,1739502704.488248,64.7299382686615,-2.437676057107843,1739502704.4882493,64.7299382686615,0.065,1739502704.4882512,64.7299382686615,3.104171485257836,1739502704.4882524,64.7299382686615,-0.19940905626389288,1739502704.488254,64.7299382686615,-0.055127202376807495,1739502704.4882553,64.7299382686615,2.131366848586526,1739502704.4882567,64.7299382686615,0.0,1739502704.4882584,64.7299382686615,0.061069946519699325,1739502704.4882596,64.7299382686615,3.1420159982088176,1739502704.4882612,64.7299382686615,2.0702969020668265 +1739502704.5080638,64.74993824958801,2.6009938006687117,1739502704.5080657,64.74993824958801,-0.13211417190690877,1739502704.5080686,64.74993824958801,110.28876297607985,1739502704.5080712,64.74993824958801,-3.112691027938346,1739502704.5080724,64.74993824958801,0.065,1739502704.5080743,64.74993824958801,3.1071077222582573,1739502704.5080755,64.74993824958801,-0.19061988822228146,1739502704.5080771,64.74993824958801,-0.044786593783934604,1739502704.508078,64.74993824958801,2.1464060124333826,1739502704.5080798,64.74993824958801,0.0,1739502704.508081,64.74993824958801,0.07323643877535904,1739502704.5080824,64.74993824958801,3.1404560564626465,1739502704.5080838,64.74993824958801,2.076971604980723 +1739502704.530672,64.76993823051453,2.6009938006687117,1739502704.5306756,64.76993823051453,-0.13211417190690877,1739502704.5306804,64.76993823051453,110.28876297607985,1739502704.5306852,64.76993823051453,-3.112691027938346,1739502704.530688,64.76993823051453,0.065,1739502704.5306916,64.76993823051453,3.1071077222582573,1739502704.530695,64.76993823051453,-0.19061988822228146,1739502704.5306983,64.76993823051453,-0.044786593783934604,1739502704.5307014,64.76993823051453,2.1464060124333826,1739502704.530705,64.76993823051453,0.0,1739502704.530708,64.76993823051453,0.06943440745265939,1739502704.5307117,64.76993823051453,3.1404560564626465,1739502704.5307145,64.76993823051453,2.076971604980723 +1739502704.549636,64.78993821144104,2.6009938006687117,1739502704.5496387,64.78993821144104,-0.13211417190690877,1739502704.549642,64.78993821144104,110.28876297607985,1739502704.5496447,64.78993821144104,-3.112691027938346,1739502704.5496461,64.78993821144104,0.065,1739502704.5496478,64.78993821144104,3.1071077222582573,1739502704.5496495,64.78993821144104,-0.19061988822228146,1739502704.5496507,64.78993821144104,-0.044786593783934604,1739502704.5496523,64.78993821144104,2.1464060124333826,1739502704.5496538,64.78993821144104,0.0,1739502704.5496552,64.78993821144104,0.06943440745265939,1739502704.5496566,64.78993821144104,3.1404560564626465,1739502704.549658,64.78993821144104,2.076971604980723 +1739502704.5714588,64.80993819236755,2.6009938006687117,1739502704.5714622,64.80993819236755,-0.13211417190690877,1739502704.5714667,64.80993819236755,110.28876297607985,1739502704.5714717,64.80993819236755,-3.112691027938346,1739502704.5714743,64.80993819236755,0.065,1739502704.5714781,64.80993819236755,3.1071077222582573,1739502704.571481,64.80993819236755,-0.19061988822228146,1739502704.5714843,64.80993819236755,-0.044786593783934604,1739502704.5714877,64.80993819236755,2.1464060124333826,1739502704.571491,64.80993819236755,0.0,1739502704.571494,64.80993819236755,0.06943440745265939,1739502704.5714974,64.80993819236755,3.1404560564626465,1739502704.5715008,64.80993819236755,2.076971604980723 +1739502704.5897963,64.82993817329407,2.6009938006687117,1739502704.5897996,64.82993817329407,-0.13211417190690877,1739502704.589804,64.82993817329407,110.28876297607985,1739502704.589809,64.82993817329407,-3.112691027938346,1739502704.5898118,64.82993817329407,0.065,1739502704.5898154,64.82993817329407,3.1071077222582573,1739502704.5898187,64.82993817329407,-0.19061988822228146,1739502704.5898216,64.82993817329407,-0.044786593783934604,1739502704.589825,64.82993817329407,2.1464060124333826,1739502704.5898285,64.82993817329407,0.0,1739502704.5898316,64.82993817329407,0.06943440745265939,1739502704.589835,64.82993817329407,3.1404560564626465,1739502704.5898385,64.82993817329407,2.076971604980723 +1739502704.6099997,64.84993815422058,2.6009938006687117,1739502704.6100032,64.84993815422058,-0.13211417190690877,1739502704.6100075,64.84993815422058,110.28876297607985,1739502704.6100128,64.84993815422058,-3.112691027938346,1739502704.6100154,64.84993815422058,0.065,1739502704.6100194,64.84993815422058,3.1071077222582573,1739502704.6100223,64.84993815422058,-0.19061988822228146,1739502704.6100256,64.84993815422058,-0.044786593783934604,1739502704.6100287,64.84993815422058,2.1464060124333826,1739502704.610032,64.84993815422058,0.0,1739502704.6100354,64.84993815422058,0.06943440745265939,1739502704.6100388,64.84993815422058,3.1404560564626465,1739502704.6100423,64.84993815422058,2.076971604980723 +1739502704.631351,64.8699381351471,2.372139299384786,1739502704.6313543,64.8699381351471,-0.13169167485870403,1739502704.6313586,64.8699381351471,110.8453512604161,1739502704.6313636,64.8699381351471,-3.6846358836149373,1739502704.6313665,64.8699381351471,0.065,1739502704.63137,64.8699381351471,3.109129408917118,1739502704.6313732,64.8699381351471,-0.1803586498199208,1739502704.6313767,64.8699381351471,-0.037716782600405924,1739502704.6313796,64.8699381351471,2.1640983582727653,1739502704.631383,64.8699381351471,0.0,1739502704.6313863,64.8699381351471,0.08400031749431276,1739502704.6313896,64.8699381351471,3.1388961147164753,1739502704.631393,64.8699381351471,2.0846498906508946 +1739502704.6494448,64.88993811607361,2.372139299384786,1739502704.6494472,64.88993811607361,-0.13169167485870403,1739502704.64945,64.88993811607361,110.8453512604161,1739502704.6494527,64.88993811607361,-3.6846358836149373,1739502704.649454,64.88993811607361,0.065,1739502704.6494555,64.88993811607361,3.109129408917118,1739502704.649457,64.88993811607361,-0.1803586498199208,1739502704.6494582,64.88993811607361,-0.037716782600405924,1739502704.6494594,64.88993811607361,2.1640983582727653,1739502704.649461,64.88993811607361,0.0,1739502704.6494622,64.88993811607361,0.07944846762187074,1739502704.649464,64.88993811607361,3.1388961147164753,1739502704.649465,64.88993811607361,2.0846498906508946 +1739502704.6685462,64.90993809700012,2.372139299384786,1739502704.6685498,64.90993809700012,-0.13169167485870403,1739502704.6685545,64.90993809700012,110.8453512604161,1739502704.6685596,64.90993809700012,-3.6846358836149373,1739502704.6685624,64.90993809700012,0.065,1739502704.668566,64.90993809700012,3.109129408917118,1739502704.6685693,64.90993809700012,-0.1803586498199208,1739502704.6685724,64.90993809700012,-0.037716782600405924,1739502704.6685755,64.90993809700012,2.1640983582727653,1739502704.6685789,64.90993809700012,0.0,1739502704.6685822,64.90993809700012,0.07944846762187074,1739502704.6685858,64.90993809700012,3.1388961147164753,1739502704.668589,64.90993809700012,2.0846498906508946 +1739502704.687881,64.92993807792664,2.372139299384786,1739502704.6878836,64.92993807792664,-0.13169167485870403,1739502704.6878862,64.92993807792664,110.8453512604161,1739502704.6878893,64.92993807792664,-3.6846358836149373,1739502704.6878908,64.92993807792664,0.065,1739502704.6878922,64.92993807792664,3.109129408917118,1739502704.6878934,64.92993807792664,-0.1803586498199208,1739502704.6878948,64.92993807792664,-0.037716782600405924,1739502704.687896,64.92993807792664,2.1640983582727653,1739502704.6878977,64.92993807792664,0.0,1739502704.6878989,64.92993807792664,0.07944846762187074,1739502704.6879003,64.92993807792664,3.1388961147164753,1739502704.6879017,64.92993807792664,2.0846498906508946 +1739502704.707839,64.94993805885315,2.372139299384786,1739502704.7078414,64.94993805885315,-0.13169167485870403,1739502704.7078443,64.94993805885315,110.8453512604161,1739502704.707847,64.94993805885315,-3.6846358836149373,1739502704.7078488,64.94993805885315,0.065,1739502704.707851,64.94993805885315,3.109129408917118,1739502704.7078526,64.94993805885315,-0.1803586498199208,1739502704.707854,64.94993805885315,-0.037716782600405924,1739502704.7078557,64.94993805885315,2.1640983582727653,1739502704.7078574,64.94993805885315,0.0,1739502704.7078588,64.94993805885315,0.07944846762187074,1739502704.7078602,64.94993805885315,3.1388961147164753,1739502704.7078617,64.94993805885315,2.0846498906508946 +1739502704.7280219,64.96993803977966,2.142396362894166,1739502704.7280242,64.96993803977966,-0.13090913450562702,1739502704.728027,64.96993803977966,110.86304224906624,1739502704.7280297,64.96993803977966,-3.7196938406021967,1739502704.728031,64.96993803977966,0.065,1739502704.7280328,64.96993803977966,3.1081854146633763,1739502704.728034,64.96993803977966,-0.1709555618078109,1739502704.7280357,64.96993803977966,-0.038162011048326755,1739502704.7280369,64.96993803977966,2.180439108484636,1739502704.7280383,64.96993803977966,0.0,1739502704.7280397,64.96993803977966,0.09058631245875191,1739502704.7280412,64.96993803977966,3.137336172970304,1739502704.7280426,64.96993803977966,2.093333374819455 +1739502704.747807,64.98993802070618,2.142396362894166,1739502704.7478092,64.98993802070618,-0.13090913450562702,1739502704.747812,64.98993802070618,110.86304224906624,1739502704.7478147,64.98993802070618,-3.7196938406021967,1739502704.747816,64.98993802070618,0.065,1739502704.7478178,64.98993802070618,3.1081854146633763,1739502704.747819,64.98993802070618,-0.1709555618078109,1739502704.7478204,64.98993802070618,-0.038162011048326755,1739502704.7478216,64.98993802070618,2.180439108484636,1739502704.747823,64.98993802070618,0.0,1739502704.7478244,64.98993802070618,0.08710573366518126,1739502704.7478259,64.98993802070618,3.137336172970304,1739502704.7478273,64.98993802070618,2.093333374819455 +1739502704.7726653,65.00993800163269,2.142396362894166,1739502704.7727082,65.00993800163269,-0.13090913450562702,1739502704.7727208,65.00993800163269,110.86304224906624,1739502704.7727373,65.00993800163269,-3.7196938406021967,1739502704.7727587,65.00993800163269,0.065,1739502704.7727773,65.00993800163269,3.1081854146633763,1739502704.7727888,65.00993800163269,-0.1709555618078109,1739502704.7728004,65.00993800163269,-0.038162011048326755,1739502704.7728124,65.00993800163269,2.180439108484636,1739502704.7728243,65.00993800163269,0.0,1739502704.7728355,65.00993800163269,0.08710573366518126,1739502704.7728474,65.00993800163269,3.137336172970304,1739502704.772859,65.00993800163269,2.093333374819455 +1739502704.7905772,65.0299379825592,2.142396362894166,1739502704.7905817,65.0299379825592,-0.13090913450562702,1739502704.7905874,65.0299379825592,110.86304224906624,1739502704.7905924,65.0299379825592,-3.7196938406021967,1739502704.7905953,65.0299379825592,0.065,1739502704.7905986,65.0299379825592,3.1081854146633763,1739502704.7906015,65.0299379825592,-0.1709555618078109,1739502704.790604,65.0299379825592,-0.038162011048326755,1739502704.7906065,65.0299379825592,2.180439108484636,1739502704.7906096,65.0299379825592,0.0,1739502704.7906122,65.0299379825592,0.08710573366518126,1739502704.790615,65.0299379825592,3.137336172970304,1739502704.790618,65.0299379825592,2.093333374819455 +1739502704.8138065,65.04993796348572,2.142396362894166,1739502704.8138137,65.04993796348572,-0.13090913450562702,1739502704.8138232,65.04993796348572,110.86304224906624,1739502704.8138337,65.04993796348572,-3.7196938406021967,1739502704.8138394,65.04993796348572,0.065,1739502704.813847,65.04993796348572,3.1081854146633763,1739502704.8138537,65.04993796348572,-0.1709555618078109,1739502704.8138607,65.04993796348572,-0.038162011048326755,1739502704.8138673,65.04993796348572,2.180439108484636,1739502704.8138742,65.04993796348572,0.0,1739502704.8138812,65.04993796348572,0.08710573366518126,1739502704.8138883,65.04993796348572,3.137336172970304,1739502704.813895,65.04993796348572,2.093333374819455 +1739502704.8300743,65.06993794441223,2.142396362894166,1739502704.8300793,65.06993794441223,-0.13090913450562702,1739502704.8300853,65.06993794441223,110.86304224906624,1739502704.8300908,65.06993794441223,-3.7196938406021967,1739502704.8300934,65.06993794441223,0.065,1739502704.830097,65.06993794441223,3.1081854146633763,1739502704.8300998,65.06993794441223,-0.1709555618078109,1739502704.8301022,65.06993794441223,-0.038162011048326755,1739502704.8301048,65.06993794441223,2.180439108484636,1739502704.830108,65.06993794441223,0.0,1739502704.8301108,65.06993794441223,0.08710573366518126,1739502704.8301136,65.06993794441223,3.137336172970304,1739502704.8301163,65.06993794441223,2.093333374819455 +1739502704.8527114,65.08993792533875,1.9116482100809211,1739502704.8527174,65.08993792533875,-0.12976319873784892,1739502704.8527248,65.08993792533875,111.06207247057928,1739502704.8527334,65.08993792533875,-3.937937496014207,1739502704.8527381,65.08993792533875,0.065,1739502704.852744,65.08993792533875,3.1083097363492187,1739502704.8527496,65.08993792533875,-0.16073643496273585,1739502704.8527548,65.08993792533875,-0.03603489557098839,1739502704.8527603,65.08993792533875,2.198337919946936,1739502704.8527663,65.08993792533875,0.0,1739502704.8527715,65.08993792533875,0.0991669656419935,1739502704.8527772,65.08993792533875,3.135776231224133,1739502704.852783,65.08993792533875,2.1029400917689354 +1739502704.8708127,65.10993790626526,1.9116482100809211,1739502704.870816,65.10993790626526,-0.12976319873784892,1739502704.8708205,65.10993790626526,111.06207247057928,1739502704.8708258,65.10993790626526,-3.937937496014207,1739502704.8708286,65.10993790626526,0.065,1739502704.8708324,65.10993790626526,3.1083097363492187,1739502704.8708355,65.10993790626526,-0.16073643496273585,1739502704.8708389,65.10993790626526,-0.03603489557098839,1739502704.8708422,65.10993790626526,2.198337919946936,1739502704.8708456,65.10993790626526,0.0,1739502704.8708487,65.10993790626526,0.09539782817800058,1739502704.8708525,65.10993790626526,3.135776231224133,1739502704.8708556,65.10993790626526,2.1029400917689354 +1739502704.890934,65.12993788719177,1.9116482100809211,1739502704.890956,65.12993788719177,-0.12976319873784892,1739502704.890961,65.12993788719177,111.06207247057928,1739502704.890966,65.12993788719177,-3.937937496014207,1739502704.8909688,65.12993788719177,0.065,1739502704.8909729,65.12993788719177,3.1083097363492187,1739502704.8909762,65.12993788719177,-0.16073643496273585,1739502704.8909795,65.12993788719177,-0.03603489557098839,1739502704.8909829,65.12993788719177,2.198337919946936,1739502704.8909862,65.12993788719177,0.0,1739502704.8909895,65.12993788719177,0.09539782817800058,1739502704.891012,65.12993788719177,3.135776231224133,1739502704.891015,65.12993788719177,2.1029400917689354 +1739502704.9100425,65.14993786811829,1.9116482100809211,1739502704.9100454,65.14993786811829,-0.12976319873784892,1739502704.910048,65.14993786811829,111.06207247057928,1739502704.9100506,65.14993786811829,-3.937937496014207,1739502704.910052,65.14993786811829,0.065,1739502704.9100537,65.14993786811829,3.1083097363492187,1739502704.910055,65.14993786811829,-0.16073643496273585,1739502704.910056,65.14993786811829,-0.03603489557098839,1739502704.9100573,65.14993786811829,2.198337919946936,1739502704.910059,65.14993786811829,0.0,1739502704.91006,65.14993786811829,0.09539782817800058,1739502704.9100614,65.14993786811829,3.135776231224133,1739502704.9100628,65.14993786811829,2.1029400917689354 +1739502704.9287817,65.1699378490448,1.9116482100809211,1739502704.9287841,65.1699378490448,-0.12976319873784892,1739502704.928787,65.1699378490448,111.06207247057928,1739502704.9287899,65.1699378490448,-3.937937496014207,1739502704.928791,65.1699378490448,0.065,1739502704.9287925,65.1699378490448,3.1083097363492187,1739502704.9287941,65.1699378490448,-0.16073643496273585,1739502704.9287953,65.1699378490448,-0.03603489557098839,1739502704.9287965,65.1699378490448,2.198337919946936,1739502704.9287982,65.1699378490448,0.0,1739502704.9287996,65.1699378490448,0.09539782817800058,1739502704.928801,65.1699378490448,3.135776231224133,1739502704.9288025,65.1699378490448,2.1029400917689354 +1739502704.9482656,65.18993782997131,1.679809271786361,1739502704.9482687,65.18993782997131,-0.12825016665506528,1739502704.9482722,65.18993782997131,111.08340316593448,1739502704.9482746,65.18993782997131,-3.9801270676132456,1739502704.9482765,65.18993782997131,0.065,1739502704.9482787,65.18993782997131,3.107462389251528,1739502704.94828,65.18993782997131,-0.15149553655152623,1739502704.9482815,65.18993782997131,-0.036275282296105625,1739502704.948283,65.18993782997131,2.2146498342673566,1739502704.9482846,65.18993782997131,0.0,1739502704.948286,65.18993782997131,0.10395415974399604,1739502704.9482872,65.18993782997131,3.134216289477962,1739502704.9482884,65.18993782997131,2.1133695298908504 +1739502704.9700632,65.20993781089783,1.679809271786361,1739502704.9700675,65.20993781089783,-0.12825016665506528,1739502704.970073,65.20993781089783,111.08340316593448,1739502704.9700785,65.20993781089783,-3.9801270676132456,1739502704.9700818,65.20993781089783,0.065,1739502704.9700856,65.20993781089783,3.107462389251528,1739502704.9700887,65.20993781089783,-0.15149553655152623,1739502704.9700916,65.20993781089783,-0.036275282296105625,1739502704.9700947,65.20993781089783,2.2146498342673566,1739502704.970098,65.20993781089783,0.0,1739502704.9701014,65.20993781089783,0.10128030437650626,1739502704.9701042,65.20993781089783,3.134216289477962,1739502704.9701073,65.20993781089783,2.1133695298908504 +1739502705.0021002,65.2399377822876,1.679809271786361,1739502705.0021048,65.2399377822876,-0.12825016665506528,1739502705.0021102,65.2399377822876,111.08340316593448,1739502705.0021152,65.2399377822876,-3.9801270676132456,1739502705.002118,65.2399377822876,0.065,1739502705.002122,65.2399377822876,3.107462389251528,1739502705.002125,65.2399377822876,-0.15149553655152623,1739502705.002128,65.2399377822876,-0.036275282296105625,1739502705.002131,65.2399377822876,2.2146498342673566,1739502705.0021343,65.2399377822876,0.0,1739502705.0021374,65.2399377822876,0.10128030437650626,1739502705.0021408,65.2399377822876,3.134216289477962,1739502705.002144,65.2399377822876,2.1133695298908504 +1739502705.0282164,65.26993775367737,1.679809271786361,1739502705.0282185,65.26993775367737,-0.12825016665506528,1739502705.0282214,65.26993775367737,111.08340316593448,1739502705.028224,65.26993775367737,-3.9801270676132456,1739502705.0282254,65.26993775367737,0.065,1739502705.028227,65.26993775367737,3.107462389251528,1739502705.0282283,65.26993775367737,-0.15149553655152623,1739502705.0282297,65.26993775367737,-0.036275282296105625,1739502705.0282307,65.26993775367737,2.2146498342673566,1739502705.0282323,65.26993775367737,0.0,1739502705.0282338,65.26993775367737,0.10128030437650626,1739502705.0282352,65.26993775367737,3.134216289477962,1739502705.0282366,65.26993775367737,2.1133695298908504 +1739502705.050959,65.28993773460388,1.679809271786361,1739502705.050962,65.28993773460388,-0.12825016665506528,1739502705.0509653,65.28993773460388,111.08340316593448,1739502705.0509682,65.28993773460388,-3.9801270676132456,1739502705.0509696,65.28993773460388,0.065,1739502705.0509715,65.28993773460388,3.107462389251528,1739502705.0509727,65.28993773460388,-0.15149553655152623,1739502705.050974,65.28993773460388,-0.036275282296105625,1739502705.0509756,65.28993773460388,2.2146498342673566,1739502705.050977,65.28993773460388,0.0,1739502705.050978,65.28993773460388,0.10128030437650626,1739502705.0509796,65.28993773460388,3.134216289477962,1739502705.0509808,65.28993773460388,2.1133695298908504 +1739502705.0695975,65.3099377155304,1.4467857031320621,1739502705.0696006,65.3099377155304,-0.12636587231858876,1739502705.0696042,65.3099377155304,111.104843218545,1739502705.069607,65.3099377155304,-4.023852218526322,1739502705.0696084,65.3099377155304,0.065,1739502705.0696106,65.3099377155304,3.1066263702942973,1739502705.0696118,65.3099377155304,-0.14247158832449025,1739502705.069613,65.3099377155304,-0.03651413372872196,1739502705.0696146,65.3099377155304,2.2306955913692534,1739502705.069616,65.3099377155304,0.0,1739502705.0696175,65.3099377155304,0.1084122453392422,1739502705.069619,65.3099377155304,3.132656347731791,1739502705.0696208,65.3099377155304,2.1245120790421375 +1739502705.0881698,65.32993769645691,1.4467857031320621,1739502705.0881724,65.32993769645691,-0.12636587231858876,1739502705.0881755,65.32993769645691,111.104843218545,1739502705.0881786,65.32993769645691,-4.023852218526322,1739502705.08818,65.32993769645691,0.065,1739502705.0881815,65.32993769645691,3.1066263702942973,1739502705.088183,65.32993769645691,-0.14247158832449025,1739502705.0881844,65.32993769645691,-0.03651413372872196,1739502705.0881855,65.32993769645691,2.2306955913692534,1739502705.0881872,65.32993769645691,0.0,1739502705.0881886,65.32993769645691,0.10618351232711598,1739502705.0881898,65.32993769645691,3.132656347731791,1739502705.0881913,65.32993769645691,2.1245120790421375 +1739502705.1084993,65.34993767738342,1.4467857031320621,1739502705.1085012,65.34993767738342,-0.12636587231858876,1739502705.1085043,65.34993767738342,111.104843218545,1739502705.1085072,65.34993767738342,-4.023852218526322,1739502705.1085086,65.34993767738342,0.065,1739502705.1085103,65.34993767738342,3.1066263702942973,1739502705.1085114,65.34993767738342,-0.14247158832449025,1739502705.1085129,65.34993767738342,-0.03651413372872196,1739502705.1085143,65.34993767738342,2.2306955913692534,1739502705.1085157,65.34993767738342,0.0,1739502705.1085172,65.34993767738342,0.10618351232711598,1739502705.1085184,65.34993767738342,3.132656347731791,1739502705.10852,65.34993767738342,2.1245120790421375 +1739502705.1280694,65.36993765830994,1.4467857031320621,1739502705.1280723,65.36993765830994,-0.12636587231858876,1739502705.1280751,65.36993765830994,111.104843218545,1739502705.1280777,65.36993765830994,-4.023852218526322,1739502705.1280792,65.36993765830994,0.065,1739502705.1280806,65.36993765830994,3.1066263702942973,1739502705.1280823,65.36993765830994,-0.14247158832449025,1739502705.1280837,65.36993765830994,-0.03651413372872196,1739502705.128085,65.36993765830994,2.2306955913692534,1739502705.1280866,65.36993765830994,0.0,1739502705.1280878,65.36993765830994,0.10618351232711598,1739502705.1280894,65.36993765830994,3.132656347731791,1739502705.1280909,65.36993765830994,2.1245120790421375 +1739502705.1480742,65.38993763923645,1.4467857031320621,1739502705.1480765,65.38993763923645,-0.12636587231858876,1739502705.1480794,65.38993763923645,111.104843218545,1739502705.1480823,65.38993763923645,-4.023852218526322,1739502705.1480834,65.38993763923645,0.065,1739502705.1480854,65.38993763923645,3.1066263702942973,1739502705.1480868,65.38993763923645,-0.14247158832449025,1739502705.148088,65.38993763923645,-0.03651413372872196,1739502705.1480896,65.38993763923645,2.2306955913692534,1739502705.148091,65.38993763923645,0.0,1739502705.1480925,65.38993763923645,0.10618351232711598,1739502705.148094,65.38993763923645,3.132656347731791,1739502705.1480951,65.38993763923645,2.1245120790421375 +1739502705.168931,65.40993762016296,1.2125200385432535,1739502705.168934,65.40993762016296,-0.12410605795789564,1739502705.1689372,65.40993762016296,111.73204429385052,1739502705.16894,65.40993762016296,-4.67427674256826,1739502705.1689413,65.40993762016296,0.065,1739502705.1689432,65.40993762016296,3.109479934775411,1739502705.1689446,65.40993762016296,-0.12730749898191793,1739502705.168946,65.40993762016296,-0.028183596272671616,1739502705.1689472,65.40993762016296,2.2579215741602696,1739502705.1689487,65.40993762016296,0.0,1739502705.16895,65.40993762016296,0.12889516771071696,1739502705.1689515,65.40993762016296,3.1310964059856197,1739502705.1689532,65.40993762016296,2.136123803410344 +1739502705.1884995,65.42993760108948,1.2125200385432535,1739502705.1885037,65.42993760108948,-0.12410605795789564,1739502705.1885087,65.42993760108948,111.73204429385052,1739502705.1885126,65.42993760108948,-4.67427674256826,1739502705.1885145,65.42993760108948,0.065,1739502705.1885176,65.42993760108948,3.109479934775411,1739502705.1885195,65.42993760108948,-0.12730749898191793,1739502705.1885216,65.42993760108948,-0.028183596272671616,1739502705.188524,65.42993760108948,2.2579215741602696,1739502705.1885264,65.42993760108948,0.0,1739502705.188528,65.42993760108948,0.1217977707499256,1739502705.1885302,65.42993760108948,3.1310964059856197,1739502705.188532,65.42993760108948,2.136123803410344 +1739502705.2116296,65.44993758201599,1.2125200385432535,1739502705.2116368,65.44993758201599,-0.12410605795789564,1739502705.2116466,65.44993758201599,111.73204429385052,1739502705.2116542,65.44993758201599,-4.67427674256826,1739502705.2116578,65.44993758201599,0.065,1739502705.2116628,65.44993758201599,3.109479934775411,1739502705.2116666,65.44993758201599,-0.12730749898191793,1739502705.2116702,65.44993758201599,-0.028183596272671616,1739502705.211674,65.44993758201599,2.2579215741602696,1739502705.2116783,65.44993758201599,0.0,1739502705.2116823,65.44993758201599,0.1217977707499256,1739502705.2116864,65.44993758201599,3.1310964059856197,1739502705.21169,65.44993758201599,2.136123803410344 +1739502705.2328527,65.4699375629425,1.2125200385432535,1739502705.23286,65.4699375629425,-0.12410605795789564,1739502705.2328691,65.4699375629425,111.73204429385052,1739502705.2328768,65.4699375629425,-4.67427674256826,1739502705.2328804,65.4699375629425,0.065,1739502705.232885,65.4699375629425,3.109479934775411,1739502705.2328892,65.4699375629425,-0.12730749898191793,1739502705.232893,65.4699375629425,-0.028183596272671616,1739502705.2328966,65.4699375629425,2.2579215741602696,1739502705.2329006,65.4699375629425,0.0,1739502705.2329044,65.4699375629425,0.1217977707499256,1739502705.2329082,65.4699375629425,3.1310964059856197,1739502705.2329123,65.4699375629425,2.136123803410344 +1739502705.2556245,65.48993754386902,1.2125200385432535,1739502705.2556329,65.48993754386902,-0.12410605795789564,1739502705.2556431,65.48993754386902,111.73204429385052,1739502705.2556515,65.48993754386902,-4.67427674256826,1739502705.2556562,65.48993754386902,0.065,1739502705.2556624,65.48993754386902,3.109479934775411,1739502705.2556665,65.48993754386902,-0.12730749898191793,1739502705.2556703,65.48993754386902,-0.028183596272671616,1739502705.2556744,65.48993754386902,2.2579215741602696,1739502705.2556798,65.48993754386902,0.0,1739502705.255684,65.48993754386902,0.1217977707499256,1739502705.2556882,65.48993754386902,3.1310964059856197,1739502705.2556922,65.48993754386902,2.136123803410344 +1739502705.2734284,65.50993752479553,1.2125200385432535,1739502705.2734349,65.50993752479553,-0.12410605795789564,1739502705.2734427,65.50993752479553,111.73204429385052,1739502705.2734506,65.50993752479553,-4.67427674256826,1739502705.2734542,65.50993752479553,0.065,1739502705.2734587,65.50993752479553,3.109479934775411,1739502705.2734625,65.50993752479553,-0.12730749898191793,1739502705.273466,65.50993752479553,-0.028183596272671616,1739502705.2734697,65.50993752479553,2.2579215741602696,1739502705.2734742,65.50993752479553,0.0,1739502705.2734787,65.50993752479553,0.1217977707499256,1739502705.2734833,65.50993752479553,3.1310964059856197,1739502705.2734873,65.50993752479553,2.136123803410344 +1739502705.2918854,65.51993751525879,0.9768797817716139,1739502705.2918906,65.51993751525879,-0.12146533422960815,1739502705.2918966,65.51993751525879,111.73958478206721,1739502705.2919023,65.51993751525879,-4.708770145932242,1739502705.291905,65.51993751525879,0.065,1739502705.2919085,65.51993751525879,3.108808622221034,1739502705.2919116,65.51993751525879,-0.11790617132380896,1739502705.2919145,65.51993751525879,-0.027980667530258595,1739502705.2919173,65.51993751525879,2.2749675642189704,1739502705.2919204,65.51993751525879,0.0,1739502705.2919235,65.51993751525879,0.1269898195482718,1739502705.2919264,65.51993751525879,3.1295364642394485,1739502705.291929,65.51993751525879,2.1496002609839864 +1739502705.311102,65.54993748664856,0.9768797817716139,1739502705.311106,65.54993748664856,-0.12146533422960815,1739502705.3111112,65.54993748664856,111.73958478206721,1739502705.3111157,65.54993748664856,-4.708770145932242,1739502705.311118,65.54993748664856,0.065,1739502705.3111207,65.54993748664856,3.108808622221034,1739502705.3111231,65.54993748664856,-0.11790617132380896,1739502705.3111253,65.54993748664856,-0.027980667530258595,1739502705.3111277,65.54993748664856,2.2749675642189704,1739502705.31113,65.54993748664856,0.0,1739502705.3111324,65.54993748664856,0.12536730323498402,1739502705.3111348,65.54993748664856,3.1295364642394485,1739502705.3111372,65.54993748664856,2.1496002609839864 +1739502705.3321009,65.56993746757507,0.9768797817716139,1739502705.3321047,65.56993746757507,-0.12146533422960815,1739502705.33211,65.56993746757507,111.73958478206721,1739502705.3321168,65.56993746757507,-4.708770145932242,1739502705.3321197,65.56993746757507,0.065,1739502705.3321242,65.56993746757507,3.108808622221034,1739502705.3321285,65.56993746757507,-0.11790617132380896,1739502705.332132,65.56993746757507,-0.027980667530258595,1739502705.3321354,65.56993746757507,2.2749675642189704,1739502705.3321393,65.56993746757507,0.0,1739502705.3321438,65.56993746757507,0.12536730323498402,1739502705.3321474,65.56993746757507,3.1295364642394485,1739502705.332151,65.56993746757507,2.1496002609839864 +1739502705.3513243,65.58993744850159,0.9768797817716139,1739502705.3513286,65.58993744850159,-0.12146533422960815,1739502705.3513331,65.58993744850159,111.73958478206721,1739502705.3513384,65.58993744850159,-4.708770145932242,1739502705.3513412,65.58993744850159,0.065,1739502705.3513448,65.58993744850159,3.108808622221034,1739502705.3513482,65.58993744850159,-0.11790617132380896,1739502705.3513513,65.58993744850159,-0.027980667530258595,1739502705.3513544,65.58993744850159,2.2749675642189704,1739502705.3513577,65.58993744850159,0.0,1739502705.3513606,65.58993744850159,0.12536730323498402,1739502705.351364,65.58993744850159,3.1295364642394485,1739502705.3513672,65.58993744850159,2.1496002609839864 +1739502705.3693023,65.6099374294281,0.9768797817716139,1739502705.3693051,65.6099374294281,-0.12146533422960815,1739502705.3693078,65.6099374294281,111.73958478206721,1739502705.3693106,65.6099374294281,-4.708770145932242,1739502705.3693123,65.6099374294281,0.065,1739502705.3693137,65.6099374294281,3.108808622221034,1739502705.3693151,65.6099374294281,-0.11790617132380896,1739502705.3693163,65.6099374294281,-0.027980667530258595,1739502705.3693175,65.6099374294281,2.2749675642189704,1739502705.3693197,65.6099374294281,0.0,1739502705.3693209,65.6099374294281,0.12536730323498402,1739502705.3693223,65.6099374294281,3.1295364642394485,1739502705.3693237,65.6099374294281,2.1496002609839864 +1739502705.391635,65.62993741035461,0.7397511377517079,1739502705.391639,65.62993741035461,-0.11843796712413734,1739502705.3916428,65.62993741035461,111.74717289867584,1739502705.3916461,65.62993741035461,-4.743907604581089,1739502705.3916483,65.62993741035461,0.065,1739502705.3916528,65.62993741035461,3.1081533755282353,1739502705.391655,65.62993741035461,-0.10875705360504968,1739502705.3916569,65.62993741035461,-0.027744679934665346,1739502705.391659,65.62993741035461,2.2916798073629856,1739502705.3916614,65.62993741035461,0.0,1739502705.3916636,65.62993741035461,0.12964013668861438,1739502705.3916657,65.62993741035461,3.1279765224932774,1739502705.3916676,65.62993741035461,2.1633749320040963 +1739502705.4093106,65.64993739128113,0.7397511377517079,1739502705.4093127,65.64993739128113,-0.11843796712413734,1739502705.4093158,65.64993739128113,111.74717289867584,1739502705.4093187,65.64993739128113,-4.743907604581089,1739502705.40932,65.64993739128113,0.065,1739502705.4093218,65.64993739128113,3.1081533755282353,1739502705.4093232,65.64993739128113,-0.10875705360504968,1739502705.4093246,65.64993739128113,-0.027744679934665346,1739502705.4093258,65.64993739128113,2.2916798073629856,1739502705.4093275,65.64993739128113,0.0,1739502705.4093292,65.64993739128113,0.12830487535888935,1739502705.4093304,65.64993739128113,3.1279765224932774,1739502705.409332,65.64993739128113,2.1633749320040963 +1739502705.4308808,65.66993737220764,0.7397511377517079,1739502705.4308846,65.66993737220764,-0.11843796712413734,1739502705.4308894,65.66993737220764,111.74717289867584,1739502705.4308949,65.66993737220764,-4.743907604581089,1739502705.4308982,65.66993737220764,0.065,1739502705.4309022,65.66993737220764,3.1081533755282353,1739502705.4309058,65.66993737220764,-0.10875705360504968,1739502705.4309092,65.66993737220764,-0.027744679934665346,1739502705.4309127,65.66993737220764,2.2916798073629856,1739502705.4309163,65.66993737220764,0.0,1739502705.4309196,65.66993737220764,0.12830487535888935,1739502705.4309232,65.66993737220764,3.1279765224932774,1739502705.4309268,65.66993737220764,2.1633749320040963 +1739502705.4489846,65.68993735313416,0.7397511377517079,1739502705.4489872,65.68993735313416,-0.11843796712413734,1739502705.4489896,65.68993735313416,111.74717289867584,1739502705.4489925,65.68993735313416,-4.743907604581089,1739502705.4489942,65.68993735313416,0.065,1739502705.4489958,65.68993735313416,3.1081533755282353,1739502705.448997,65.68993735313416,-0.10875705360504968,1739502705.4489985,65.68993735313416,-0.027744679934665346,1739502705.4489996,65.68993735313416,2.2916798073629856,1739502705.4490013,65.68993735313416,0.0,1739502705.4490025,65.68993735313416,0.12830487535888935,1739502705.4490037,65.68993735313416,3.1279765224932774,1739502705.4490056,65.68993735313416,2.1633749320040963 +1739502705.4690132,65.70993733406067,0.7397511377517079,1739502705.4690158,65.70993733406067,-0.11843796712413734,1739502705.4690187,65.70993733406067,111.74717289867584,1739502705.4690216,65.70993733406067,-4.743907604581089,1739502705.469023,65.70993733406067,0.065,1739502705.4690247,65.70993733406067,3.1081533755282353,1739502705.4690263,65.70993733406067,-0.10875705360504968,1739502705.4690275,65.70993733406067,-0.027744679934665346,1739502705.469029,65.70993733406067,2.2916798073629856,1739502705.4690304,65.70993733406067,0.0,1739502705.4690316,65.70993733406067,0.12830487535888935,1739502705.469033,65.70993733406067,3.1279765224932774,1739502705.4690344,65.70993733406067,2.1633749320040963 diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/behavior.json b/tuning logs/2025-02-13_21-10-39 (fine tuning)/behavior.json new file mode 100644 index 000000000..88d24e1fd --- /dev/null +++ b/tuning logs/2025-02-13_21-10-39 (fine tuning)/behavior.json @@ -0,0 +1,6605 @@ +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502638.589087, "x": 4.0, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": 0.0, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": -1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.629087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": -2, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 0, "brake_pedal_position": 0, "brake_pedal_speed": 0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": -1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.629087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.0, "x": 0.0, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": 0.0, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": -1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.659087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36000000000000004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.683742855172885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": -1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.659087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.0, "x": 0.0, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": 0.0, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": -1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.679087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36000000000000004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.683742855172885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.015995993600000008, "gear": 1, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08614717687913853, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.679087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502638.699087, "x": 4.000479839636091, "y": 4.999999993195597, "z": null, "yaw": -4.6415014108958415e-05, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.17209949070995442, "front_wheel_angle": -0.007921433607650973, "heading_rate": -9.894547402327468e-05, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.699087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.551868899589124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03197591848874033, "gear": 1, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.17209949070995442, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.699087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.00047983963609077307, "y": -6.804403263060976e-09, "z": null, "yaw": 6.283138892165478, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.17209949070995442, "front_wheel_angle": -0.007921433607650973, "heading_rate": -9.894547402327468e-05, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.719087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.551868899589124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05197084453690334, "gear": 1, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2575150543639356, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.719087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.00047983963609077307, "y": -6.804403263060976e-09, "z": null, "yaw": 6.283138892165478, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.17209949070995442, "front_wheel_angle": -0.007921433607650973, "heading_rate": -9.894547402327468e-05, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.7390869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.551868899589124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11183287562172607, "gear": 1, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5126018812412664, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.7390869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.00047983963609077307, "y": -6.804403263060976e-09, "z": null, "yaw": 6.283138892165478, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.17209949070995442, "front_wheel_angle": -0.007921433607650973, "heading_rate": -9.894547402327468e-05, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.7790868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.551868899589124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11183287562172607, "gear": 1, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5126018812412664, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.7790868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.00047983963609077307, "y": -6.804403263060976e-09, "z": null, "yaw": 6.283138892165478, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.17209949070995442, "front_wheel_angle": -0.007921433607650973, "heading_rate": -9.894547402327468e-05, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.7990868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.551868899589124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.13174550971148086, "gear": 1, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5972442021721722, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.7990868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502638.8090868, "x": 4.009488760476915, "y": 4.999996419713743, "z": null, "yaw": -0.0008106689266637859, "pitch": null, "roll": null}, "v": 0.1416939914738729, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "acceleration": 0.9943235490721771, "steering_wheel_angle": -0.6394928711323367, "front_wheel_angle": -0.0296184321337821, "heading_rate": -0.0016398365249685966, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.8290868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3931656754313427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.1435982984250344, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.24122759505359873, "gear": 1, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.056288940593094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.8290868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.009488760476915381, "y": -3.58028625679907e-06, "z": null, "yaw": 6.282374638252922, "pitch": null, "roll": null}, "v": 0.1416939914738729, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "acceleration": 0.9943235490721771, "steering_wheel_angle": -0.6394928711323367, "front_wheel_angle": -0.0296184321337821, "heading_rate": -0.0016398365249685966, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.9090867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3931656754313427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.1435982984250344, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26111497576260423, "gear": 1, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1386731819129978, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.9090867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502638.9190867, "x": 4.03054701984167, "y": 4.999963086200438, "z": null, "yaw": -0.0025060902395537053, "pitch": null, "roll": null}, "v": 0.2511740168952693, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.994095886733495, "steering_wheel_angle": -1.0975046434689273, "front_wheel_angle": -0.05114825033772567, "heading_rate": -0.0050227837994094695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.9390867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941103335539835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7581640131937317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2710504548861251, "gear": 1, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.9390867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.030547019841669965, "y": -3.691379956194396e-05, "z": null, "yaw": 6.280679216940032, "pitch": null, "roll": null}, "v": 0.2511740168952693, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.994095886733495, "steering_wheel_angle": -1.0975046434689273, "front_wheel_angle": -0.05114825033772567, "heading_rate": -0.0050227837994094695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.9590867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941103335539835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7581640131937317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.291022956459828, "gear": 1, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.9590867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.030547019841669965, "y": -3.691379956194396e-05, "z": null, "yaw": 6.280679216940032, "pitch": null, "roll": null}, "v": 0.2511740168952693, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.994095886733495, "steering_wheel_angle": -1.0975046434689273, "front_wheel_angle": -0.05114825033772567, "heading_rate": -0.0050227837994094695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.9790866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941103335539835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7581640131937317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.31097320665157313, "gear": 1, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.9790866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.030547019841669965, "y": -3.691379956194396e-05, "z": null, "yaw": 6.280679216940032, "pitch": null, "roll": null}, "v": 0.2511740168952693, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.994095886733495, "steering_wheel_angle": -1.0975046434689273, "front_wheel_angle": -0.05114825033772567, "heading_rate": -0.0050227837994094695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.9990866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941103335539835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7581640131937317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3309010710913795, "gear": 1, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.9990866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.030547019841669965, "y": -3.691379956194396e-05, "z": null, "yaw": 6.280679216940032, "pitch": null, "roll": null}, "v": 0.2511740168952693, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.994095886733495, "steering_wheel_angle": -1.0975046434689273, "front_wheel_angle": -0.05114825033772567, "heading_rate": -0.0050227837994094695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.0190866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941103335539835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7581640131937317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.35080641609485474, "gear": 1, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.0190866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.0290866, "x": 4.063655593446573, "y": 4.9998428022115675, "z": null, "yaw": -0.0048508136236434084, "pitch": null, "roll": null}, "v": 0.36075060221977395, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "acceleration": 0.9938506446313888, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.007764741931406749, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.0390866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950942304129613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4193851803411235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37068910866608784, "gear": 1, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.0390866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06365559344657257, "y": -0.00015719778843248378, "z": null, "yaw": 6.278334493555943, "pitch": null, "roll": null}, "v": 0.36075060221977395, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "acceleration": 0.9938506446313888, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.007764741931406749, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.0590866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950942304129613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4193851803411235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.390671968179558, "gear": 1, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.0590866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06365559344657257, "y": -0.00015719778843248378, "z": null, "yaw": 6.278334493555943, "pitch": null, "roll": null}, "v": 0.36075060221977395, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "acceleration": 0.9938506446313888, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.007764741931406749, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.0790865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950942304129613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4193851803411235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4106317687352455, "gear": 1, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.0790865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06365559344657257, "y": -0.00015719778843248378, "z": null, "yaw": 6.278334493555943, "pitch": null, "roll": null}, "v": 0.36075060221977395, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "acceleration": 0.9938506446313888, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.007764741931406749, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.0990865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950942304129613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4193851803411235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4305683776306325, "gear": 1, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.0990865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06365559344657257, "y": -0.00015719778843248378, "z": null, "yaw": 6.278334493555943, "pitch": null, "roll": null}, "v": 0.36075060221977395, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "acceleration": 0.9938506446313888, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.007764741931406749, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.1190865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950942304129613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4193851803411235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45048166287175256, "gear": 1, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.1190865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.1390865, "x": 4.108821696674257, "y": 4.999572738443982, "z": null, "yaw": -0.007218437148591534, "pitch": null, "roll": null}, "v": 0.47037149317593346, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "acceleration": 0.993607872006286, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01012420557007563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.1390865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961169708919556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1356043896108887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.47037149317593346, "gear": 1, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.1390865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10882169667425678, "y": -0.0004272615560179105, "z": null, "yaw": 6.275966870030994, "pitch": null, "roll": null}, "v": 0.47037149317593346, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "acceleration": 0.993607872006286, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01012420557007563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.1590865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961169708919556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1356043896108887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4903655424329471, "gear": 1, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.1590865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10882169667425678, "y": -0.0004272615560179105, "z": null, "yaw": 6.275966870030994, "pitch": null, "roll": null}, "v": 0.47037149317593346, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "acceleration": 0.993607872006286, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01012420557007563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.1790864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961169708919556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1356043896108887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5302819038945259, "gear": 1, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.1790864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10882169667425678, "y": -0.0004272615560179105, "z": null, "yaw": 6.275966870030994, "pitch": null, "roll": null}, "v": 0.47037149317593346, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "acceleration": 0.993607872006286, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01012420557007563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.1990864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961169708919556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1356043896108887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5302819038945259, "gear": 1, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.1990864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10882169667425678, "y": -0.0004272615560179105, "z": null, "yaw": 6.275966870030994, "pitch": null, "roll": null}, "v": 0.47037149317593346, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "acceleration": 0.993607872006286, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01012420557007563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.2190864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961169708919556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1356043896108887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.550203954868394, "gear": 1, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.2190864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10882169667425678, "y": -0.0004272615560179105, "z": null, "yaw": 6.275966870030994, "pitch": null, "roll": null}, "v": 0.47037149317593346, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "acceleration": 0.993607872006286, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01012420557007563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.2390864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961169708919556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1356043896108887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5701017464054556, "gear": 1, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.2390864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.2490864, "x": 4.1660506865518885, "y": 4.999095672957929, "z": null, "yaw": -0.00958606067353966, "pitch": null, "roll": null}, "v": 0.5800415046128746, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "acceleration": 0.9933645113733428, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.012484726470615926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.2590864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971786490722207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9156972606132593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.589975149726608, "gear": 1, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.2590864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16605068655188848, "y": -0.0009043270420709959, "z": null, "yaw": 6.273599246506047, "pitch": null, "roll": null}, "v": 0.5800415046128746, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "acceleration": 0.9933645113733428, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.012484726470615926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.2790864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971786490722207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9156972606132593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6099567054251431, "gear": 1, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.2790864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16605068655188848, "y": -0.0009043270420709959, "z": null, "yaw": 6.273599246506047, "pitch": null, "roll": null}, "v": 0.5800415046128746, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "acceleration": 0.9933645113733428, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.012484726470615926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.2990863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971786490722207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9156972606132593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.629913452058564, "gear": 1, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.2990863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16605068655188848, "y": -0.0009043270420709959, "z": null, "yaw": 6.273599246506047, "pitch": null, "roll": null}, "v": 0.5800415046128746, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "acceleration": 0.9933645113733428, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.012484726470615926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.3190863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971786490722207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9156972606132593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6498452611708999, "gear": 1, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.3190863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16605068655188848, "y": -0.0009043270420709959, "z": null, "yaw": 6.273599246506047, "pitch": null, "roll": null}, "v": 0.5800415046128746, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "acceleration": 0.9933645113733428, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.012484726470615926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.3390863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971786490722207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9156972606132593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6796959378524123, "gear": 1, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.3390863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.3590863, "x": 4.2353344217403, "y": 4.99835456379934, "z": null, "yaw": -0.011953684198487786, "pitch": null, "roll": null}, "v": 0.6896335567937066, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "acceleration": 0.9931289344351348, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.014843569387803937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.3590863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3982780195625992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7400758668327561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6896335567937066, "gear": 1, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.3590863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.2353344217403004, "y": -0.0016454362006603773, "z": null, "yaw": 6.271231622981098, "pitch": null, "roll": null}, "v": 0.6896335567937066, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "acceleration": 0.9931289344351348, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.014843569387803937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.3790863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3982780195625992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7400758668327561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7295951576453222, "gear": 1, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.3790863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.2353344217403004, "y": -0.0016454362006603773, "z": null, "yaw": 6.271231622981098, "pitch": null, "roll": null}, "v": 0.6896335567937066, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "acceleration": 0.9931289344351348, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.014843569387803937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.3990862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3982780195625992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7400758668327561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7395695053797561, "gear": 1, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.3990862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.2353344217403004, "y": -0.0016454362006603773, "z": null, "yaw": 6.271231622981098, "pitch": null, "roll": null}, "v": 0.6896335567937066, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "acceleration": 0.9931289344351348, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.014843569387803937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.4190862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3982780195625992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7400758668327561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7495374005443999, "gear": 1, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.4190862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.2353344217403004, "y": -0.0016454362006603773, "z": null, "yaw": 6.271231622981098, "pitch": null, "roll": null}, "v": 0.6896335567937066, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "acceleration": 0.9931289344351348, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.014843569387803937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.4390862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3982780195625992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7400758668327561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7794022138243517, "gear": 1, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.4390862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.2353344217403004, "y": -0.0016454362006603773, "z": null, "yaw": 6.271231622981098, "pitch": null, "roll": null}, "v": 0.6896335567937066, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "acceleration": 0.9931289344351348, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.014843569387803937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.4590862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3982780195625992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7400758668327561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7893441421590105, "gear": 1, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.4590862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.4690862, "x": 4.316676563322144, "y": 4.997292264762089, "z": null, "yaw": -0.014321307723435912, "pitch": null, "roll": null}, "v": 0.7992795398931174, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "acceleration": 0.9928851674426713, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01720357310600603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.4790862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941639277177177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5801172679023778, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8092083915675441, "gear": 1, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.4790862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.3166765633221438, "y": -0.002707735237910569, "z": null, "yaw": 6.26886399945615, "pitch": null, "roll": null}, "v": 0.7992795398931174, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "acceleration": 0.9928851674426713, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01720357310600603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.4990861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941639277177177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5801172679023778, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.829188644567241, "gear": 1, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.4990861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.3166765633221438, "y": -0.002707735237910569, "z": null, "yaw": 6.26886399945615, "pitch": null, "roll": null}, "v": 0.7992795398931174, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "acceleration": 0.9928851674426713, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01720357310600603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.5190861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941639277177177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5801172679023778, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8591091882276143, "gear": 1, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.5190861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.3166765633221438, "y": -0.002707735237910569, "z": null, "yaw": 6.26886399945615, "pitch": null, "roll": null}, "v": 0.7992795398931174, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "acceleration": 0.9928851674426713, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01720357310600603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.539086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941639277177177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5801172679023778, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8889695580719712, "gear": 1, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.539086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.3166765633221438, "y": -0.002707735237910569, "z": null, "yaw": 6.26886399945615, "pitch": null, "roll": null}, "v": 0.7992795398931174, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "acceleration": 0.9928851674426713, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01720357310600603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.559086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941639277177177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5801172679023778, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8889695580719712, "gear": 1, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.559086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.579086, "x": 4.410068133942758, "y": 4.995851794311904, "z": null, "yaw": -0.016688931248384036, "pitch": null, "roll": null}, "v": 0.9088428370746009, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "acceleration": 0.9926503599448252, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01956179710489479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.579086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4005923351805997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4477938085583233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9188428370746009, "gear": 1, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.579086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.4100681339427581, "y": -0.0041482056880957074, "z": null, "yaw": 6.266496375931202, "pitch": null, "roll": null}, "v": 0.9088428370746009, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "acceleration": 0.9926503599448252, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01956179710489479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.599086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4005923351805997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4477938085583233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9288360093889267, "gear": 1, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.599086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.4100681339427581, "y": -0.0041482056880957074, "z": null, "yaw": 6.266496375931202, "pitch": null, "roll": null}, "v": 0.9088428370746009, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "acceleration": 0.9926503599448252, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01956179710489479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.619086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4005923351805997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4477938085583233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9488018097408595, "gear": 1, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.619086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.4100681339427581, "y": -0.0041482056880957074, "z": null, "yaw": 6.266496375931202, "pitch": null, "roll": null}, "v": 0.9088428370746009, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "acceleration": 0.9926503599448252, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01956179710489479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.639086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4005923351805997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4477938085583233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9687401162060897, "gear": 1, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.639086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.4100681339427581, "y": -0.0041482056880957074, "z": null, "yaw": 6.266496375931202, "pitch": null, "roll": null}, "v": 0.9088428370746009, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "acceleration": 0.9926503599448252, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01956179710489479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.659086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4005923351805997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4477938085583233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9886508076857429, "gear": 1, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.659086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.689086, "x": 4.515512822324933, "y": 4.993975998601396, "z": null, "yaw": -0.019056554773332162, "pitch": null, "roll": null}, "v": 1.0184648039397393, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "acceleration": 0.992406149113121, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.021921283901267387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.689086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018073513225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29744631951598405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0384577570101314, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.689086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5155128223249328, "y": -0.006024001398603929, "z": null, "yaw": 6.264128752406254, "pitch": null, "roll": null}, "v": 1.0184648039397393, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "acceleration": 0.992406149113121, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.021921283901267387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.709086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018073513225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29744631951598405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.048443648137973, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.709086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5155128223249328, "y": -0.006024001398603929, "z": null, "yaw": 6.264128752406254, "pitch": null, "roll": null}, "v": 1.0184648039397393, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "acceleration": 0.992406149113121, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.021921283901267387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.729086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018073513225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29744631951598405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0584224623632283, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.729086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5155128223249328, "y": -0.006024001398603929, "z": null, "yaw": 6.264128752406254, "pitch": null, "roll": null}, "v": 1.0184648039397393, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "acceleration": 0.992406149113121, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.021921283901267387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.749086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018073513225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29744631951598405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0783588005306795, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.749086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5155128223249328, "y": -0.006024001398603929, "z": null, "yaw": 6.264128752406254, "pitch": null, "roll": null}, "v": 1.0184648039397393, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "acceleration": 0.992406149113121, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.021921283901267387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.769086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018073513225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29744631951598405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.098266652892293, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.769086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5155128223249328, "y": -0.006024001398603929, "z": null, "yaw": 6.264128752406254, "pitch": null, "roll": null}, "v": 1.0184648039397393, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "acceleration": 0.992406149113121, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.021921283901267387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.7890859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018073513225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29744631951598405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.137996429967674, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.7890859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.7990859, "x": 4.633008456601953, "y": 4.9916113704074645, "z": null, "yaw": -0.021351682213653866, "pitch": null, "roll": null}, "v": 1.1280747631587245, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "acceleration": 0.9921666808949349, "steering_wheel_angle": -1.1407446082810997, "front_wheel_angle": -0.05319492473024455, "heading_rate": -0.02346270221191366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.8090858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4030606823793108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16681047596192075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.137996429967674, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.8090858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.6330084566019529, "y": -0.008388629592535501, "z": null, "yaw": 6.2618336249659325, "pitch": null, "roll": null}, "v": 1.1280747631587245, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "acceleration": 0.9921666808949349, "steering_wheel_angle": -1.1407446082810997, "front_wheel_angle": -0.05319492473024455, "heading_rate": -0.02346270221191366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.8390858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4030606823793108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16681047596192075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.187887430693919, "gear": 1, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0237458350603676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.8390858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.6330084566019529, "y": -0.008388629592535501, "z": null, "yaw": 6.2618336249659325, "pitch": null, "roll": null}, "v": 1.1280747631587245, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "acceleration": 0.9921666808949349, "steering_wheel_angle": -1.1407446082810997, "front_wheel_angle": -0.05319492473024455, "heading_rate": -0.02346270221191366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.8590858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4030606823793108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16681047596192075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.187887430693919, "gear": 1, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0237458350603676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.8590858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.6330084566019529, "y": -0.008388629592535501, "z": null, "yaw": 6.2618336249659325, "pitch": null, "roll": null}, "v": 1.1280747631587245, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "acceleration": 0.9921666808949349, "steering_wheel_angle": -1.1407446082810997, "front_wheel_angle": -0.05319492473024455, "heading_rate": -0.02346270221191366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.8790858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4030606823793108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16681047596192075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2177340799209784, "gear": 1, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0237458350603676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.8790858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.6330084566019529, "y": -0.008388629592535501, "z": null, "yaw": 6.2618336249659325, "pitch": null, "roll": null}, "v": 1.1280747631587245, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "acceleration": 0.9921666808949349, "steering_wheel_angle": -1.1407446082810997, "front_wheel_angle": -0.05319492473024455, "heading_rate": -0.02346270221191366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.8990858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4030606823793108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16681047596192075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2276682179007847, "gear": 1, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0237458350603676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.8990858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.9090858, "x": 4.762544446194814, "y": 4.988715496391628, "z": null, "yaw": -0.023466234438233532, "pitch": null, "roll": null}, "v": 1.237594959515217, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "acceleration": 0.9919331040567566, "steering_wheel_angle": -1.0237458350603676, "front_wheel_angle": -0.04766269828541294, "heading_rate": -0.02305930602983657, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.9190857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40435138573022966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.045431341580688775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2475142905557846, "gear": 1, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0237458350603676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.9190857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7625444461948137, "y": -0.011284503608371743, "z": null, "yaw": 6.259719072741353, "pitch": null, "roll": null}, "v": 1.237594959515217, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "acceleration": 0.9919331040567566, "steering_wheel_angle": -1.0237458350603676, "front_wheel_angle": -0.04766269828541294, "heading_rate": -0.02305930602983657, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.9390857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40435138573022966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.045431341580688775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.277469503706695, "gear": 1, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9067418378242836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.9390857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40435138573022966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.045431341580688775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.277469503706695, "gear": 1, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9067418378242836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.9490857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7625444461948137, "y": -0.011284503608371743, "z": null, "yaw": 6.259719072741353, "pitch": null, "roll": null}, "v": 1.237594959515217, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "acceleration": 0.9919331040567566, "steering_wheel_angle": -1.0237458350603676, "front_wheel_angle": -0.04766269828541294, "heading_rate": -0.02305930602983657, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.9790857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40435138573022966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.045431341580688775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3173043298057185, "gear": 1, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.867656560426274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.9790857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7625444461948137, "y": -0.011284503608371743, "z": null, "yaw": 6.259719072741353, "pitch": null, "roll": null}, "v": 1.237594959515217, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "acceleration": 0.9919331040567566, "steering_wheel_angle": -1.0237458350603676, "front_wheel_angle": -0.04766269828541294, "heading_rate": -0.02305930602983657, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.9990857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40435138573022966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.045431341580688775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3272441101792225, "gear": 1, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.867656560426274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.9990857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.0190856, "x": 4.904117469719066, "y": 4.985268174745568, "z": null, "yaw": -0.025299955738351757, "pitch": null, "roll": null}, "v": 1.347100861457992, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "acceleration": 0.9916943104316268, "steering_wheel_angle": -0.867656560426274, "front_wheel_angle": -0.04030992087529883, "heading_rate": -0.021223031092673244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.0190856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40568029606116934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06836287461861668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.347100861457992, "gear": 1, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.867656560426274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.0190856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9041174697190657, "y": -0.014731825254432174, "z": null, "yaw": 6.257885351441234, "pitch": null, "roll": null}, "v": 1.347100861457992, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "acceleration": 0.9916943104316268, "steering_wheel_angle": -0.867656560426274, "front_wheel_angle": -0.04030992087529883, "heading_rate": -0.021223031092673244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.0390856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40568029606116934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06836287461861668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.367093157256269, "gear": 1, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7892303706327148, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.0390856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9041174697190657, "y": -0.014731825254432174, "z": null, "yaw": 6.257885351441234, "pitch": null, "roll": null}, "v": 1.347100861457992, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "acceleration": 0.9916943104316268, "steering_wheel_angle": -0.867656560426274, "front_wheel_angle": -0.04030992087529883, "heading_rate": -0.021223031092673244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.0590856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40568029606116934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06836287461861668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3870545801390484, "gear": 1, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7892303706327148, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.0590856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9041174697190657, "y": -0.014731825254432174, "z": null, "yaw": 6.257885351441234, "pitch": null, "roll": null}, "v": 1.347100861457992, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "acceleration": 0.9916943104316268, "steering_wheel_angle": -0.867656560426274, "front_wheel_angle": -0.04030992087529883, "heading_rate": -0.021223031092673244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.0790856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40568029606116934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06836287461861668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4069850184600847, "gear": 1, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7892303706327148, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.0790856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9041174697190657, "y": -0.014731825254432174, "z": null, "yaw": 6.257885351441234, "pitch": null, "roll": null}, "v": 1.347100861457992, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "acceleration": 0.9916943104316268, "steering_wheel_angle": -0.867656560426274, "front_wheel_angle": -0.04030992087529883, "heading_rate": -0.021223031092673244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.0990856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40568029606116934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06836287461861668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4368223379123544, "gear": 1, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7892303706327148, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.0990856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9041174697190657, "y": -0.014731825254432174, "z": null, "yaw": 6.257885351441234, "pitch": null, "roll": null}, "v": 1.347100861457992, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "acceleration": 0.9916943104316268, "steering_wheel_angle": -0.867656560426274, "front_wheel_angle": -0.04030992087529883, "heading_rate": -0.021223031092673244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.1190856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40568029606116934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06836287461861668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4566748323788168, "gear": 1, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7892303706327148, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.1190856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.1290855, "x": 5.057733673796732, "y": 4.981266344334359, "z": null, "yaw": -0.026896104036239907, "pitch": null, "roll": null}, "v": 1.4566748323788168, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "acceleration": 0.9914490930905087, "steering_wheel_angle": -0.7892303706327148, "front_wheel_angle": -0.03662744785490479, "heading_rate": -0.020850841318412184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.1390855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3986025404824454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17871005704156534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.485510357561833, "gear": 1, "accelerator_pedal_position": 0.3986025404824454, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7104062261326988, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.1390855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.057733673796732, "y": -0.018733655665641002, "z": null, "yaw": 6.256289203143346, "pitch": null, "roll": null}, "v": 1.4566748323788168, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "acceleration": 0.9914490930905087, "steering_wheel_angle": -0.7892303706327148, "front_wheel_angle": -0.03662744785490479, "heading_rate": -0.020850841318412184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.1590855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4070484411666879, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17871005704156534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4949595870609624, "gear": 1, "accelerator_pedal_position": 0.3986025404824454, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6709306175229047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.1590855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.057733673796732, "y": -0.018733655665641002, "z": null, "yaw": 6.256289203143346, "pitch": null, "roll": null}, "v": 1.4566748323788168, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "acceleration": 0.9914490930905087, "steering_wheel_angle": -0.7892303706327148, "front_wheel_angle": -0.03662744785490479, "heading_rate": -0.020850841318412184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.1890855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4070484411666879, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17871005704156534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.514890726251388, "gear": 1, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6709306175229047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.1890855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.057733673796732, "y": -0.018733655665641002, "z": null, "yaw": 6.256289203143346, "pitch": null, "roll": null}, "v": 1.4566748323788168, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "acceleration": 0.9914490930905087, "steering_wheel_angle": -0.7892303706327148, "front_wheel_angle": -0.03662744785490479, "heading_rate": -0.020850841318412184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.2090855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4070484411666879, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17871005704156534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.534789909463575, "gear": 1, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6709306175229047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.2090855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.057733673796732, "y": -0.018733655665641002, "z": null, "yaw": 6.256289203143346, "pitch": null, "roll": null}, "v": 1.4566748323788168, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "acceleration": 0.9914490930905087, "steering_wheel_angle": -0.7892303706327148, "front_wheel_angle": -0.03662744785490479, "heading_rate": -0.020850841318412184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.2290854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4070484411666879, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17871005704156534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.554657029606017, "gear": 1, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6709306175229047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.2290854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.2390854, "x": 5.223257022434613, "y": 4.976702662887181, "z": null, "yaw": -0.028297323564877165, "pitch": null, "roll": null}, "v": 1.5645785328161617, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "acceleration": 0.9913447707974994, "steering_wheel_angle": -0.6709306175229047, "front_wheel_angle": -0.0310876255498557, "heading_rate": -0.019005744742388843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.2490854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38029893986951396, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26484427208034017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5744919805241366, "gear": 1, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6709306175229047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.2490854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2232570224346127, "y": -0.023297337112818894, "z": null, "yaw": 6.254887983614709, "pitch": null, "roll": null}, "v": 1.5645785328161617, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "acceleration": 0.9913447707974994, "steering_wheel_angle": -0.6709306175229047, "front_wheel_angle": -0.0310876255498557, "heading_rate": -0.019005744742388843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.2690854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3894796959152692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26484427208034017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5909523347541736, "gear": 1, "accelerator_pedal_position": 0.38029893986951396, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5916711940647781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.2690854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2232570224346127, "y": -0.023297337112818894, "z": null, "yaw": 6.254887983614709, "pitch": null, "roll": null}, "v": 1.5645785328161617, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "acceleration": 0.9913447707974994, "steering_wheel_angle": -0.6709306175229047, "front_wheel_angle": -0.0310876255498557, "heading_rate": -0.019005744742388843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.2890854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3894796959152692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26484427208034017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6085329157307675, "gear": 1, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5916711940647781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.2890854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2232570224346127, "y": -0.023297337112818894, "z": null, "yaw": 6.254887983614709, "pitch": null, "roll": null}, "v": 1.5645785328161617, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "acceleration": 0.9913447707974994, "steering_wheel_angle": -0.6709306175229047, "front_wheel_angle": -0.0310876255498557, "heading_rate": -0.019005744742388843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.3090854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3894796959152692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26484427208034017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6260846473145067, "gear": 1, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5916711940647781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.3090854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2232570224346127, "y": -0.023297337112818894, "z": null, "yaw": 6.254887983614709, "pitch": null, "roll": null}, "v": 1.5645785328161617, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "acceleration": 0.9913447707974994, "steering_wheel_angle": -0.6709306175229047, "front_wheel_angle": -0.0310876255498557, "heading_rate": -0.019005744742388843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.3290854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3894796959152692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26484427208034017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6436074536721759, "gear": 1, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5916711940647781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.3290854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.3490853, "x": 5.40013567806967, "y": 4.971595014687976, "z": null, "yaw": -0.029510537955780052, "pitch": null, "roll": null}, "v": 1.6611012597038548, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "acceleration": 0.8736004625353424, "steering_wheel_angle": -0.5916711940647781, "front_wheel_angle": -0.027385960225383893, "heading_rate": -0.017774308209128127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.3490853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.360673015762224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3395022059286818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6611012597038548, "gear": 1, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5916711940647781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.3490853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4001356780696703, "y": -0.028404985312024067, "z": null, "yaw": 6.253674769223807, "pitch": null, "roll": null}, "v": 1.6611012597038548, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "acceleration": 0.8736004625353424, "steering_wheel_angle": -0.5916711940647781, "front_wheel_angle": -0.027385960225383893, "heading_rate": -0.017774308209128127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.3690853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3700720919946048, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3395022059286818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6749666571891373, "gear": 1, "accelerator_pedal_position": 0.360673015762224, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5120832145906543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.3690853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4001356780696703, "y": -0.028404985312024067, "z": null, "yaw": 6.253674769223807, "pitch": null, "roll": null}, "v": 1.6611012597038548, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "acceleration": 0.8736004625353424, "steering_wheel_angle": -0.5916711940647781, "front_wheel_angle": -0.027385960225383893, "heading_rate": -0.017774308209128127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.3890853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3700720919946048, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3395022059286818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6899833217002447, "gear": 1, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5120832145906543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.3890853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4001356780696703, "y": -0.028404985312024067, "z": null, "yaw": 6.253674769223807, "pitch": null, "roll": null}, "v": 1.6611012597038548, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "acceleration": 0.8736004625353424, "steering_wheel_angle": -0.5916711940647781, "front_wheel_angle": -0.027385960225383893, "heading_rate": -0.017774308209128127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.4090853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3700720919946048, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3395022059286818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7049748514676437, "gear": 1, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5120832145906543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.4090853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4001356780696703, "y": -0.028404985312024067, "z": null, "yaw": 6.253674769223807, "pitch": null, "roll": null}, "v": 1.6611012597038548, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "acceleration": 0.8736004625353424, "steering_wheel_angle": -0.5916711940647781, "front_wheel_angle": -0.027385960225383893, "heading_rate": -0.017774308209128127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.4290853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3700720919946048, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3395022059286818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7199411987010031, "gear": 1, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5120832145906543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.4290853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4001356780696703, "y": -0.028404985312024067, "z": null, "yaw": 6.253674769223807, "pitch": null, "roll": null}, "v": 1.6611012597038548, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "acceleration": 0.8736004625353424, "steering_wheel_angle": -0.5916711940647781, "front_wheel_angle": -0.027385960225383893, "heading_rate": -0.017774308209128127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.4490852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3700720919946048, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3395022059286818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.734882316142702, "gear": 1, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5120832145906543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.4490852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.4590852, "x": 5.586788894306497, "y": 4.965994434070277, "z": null, "yaw": -0.030549842397879546, "pitch": null, "roll": null}, "v": 1.742343399069207, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "acceleration": 0.745475799810019, "steering_wheel_angle": -0.5120832145906543, "front_wheel_angle": -0.02367692324113134, "heading_rate": -0.016117594326344496, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.4690852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3485524708696682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4067163021019893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7497981570673071, "gear": 1, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5120832145906543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.4690852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.5867888943064967, "y": -0.03400556592972315, "z": null, "yaw": 6.252635464781707, "pitch": null, "roll": null}, "v": 1.742343399069207, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "acceleration": 0.745475799810019, "steering_wheel_angle": -0.5120832145906543, "front_wheel_angle": -0.02367692324113134, "heading_rate": -0.016117594326344496, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.4890852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35561871401525946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4067163021019893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7619998676386863, "gear": 1, "accelerator_pedal_position": 0.3485524708696682, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4321806685856667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.4890852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.5867888943064967, "y": -0.03400556592972315, "z": null, "yaw": 6.252635464781707, "pitch": null, "roll": null}, "v": 1.742343399069207, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "acceleration": 0.745475799810019, "steering_wheel_angle": -0.5120832145906543, "front_wheel_angle": -0.02367692324113134, "heading_rate": -0.016117594326344496, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.5090852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35561871401525946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4067163021019893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.775063703863348, "gear": 1, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4321806685856667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.5090852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.5867888943064967, "y": -0.03400556592972315, "z": null, "yaw": 6.252635464781707, "pitch": null, "roll": null}, "v": 1.742343399069207, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "acceleration": 0.745475799810019, "steering_wheel_angle": -0.5120832145906543, "front_wheel_angle": -0.02367692324113134, "heading_rate": -0.016117594326344496, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.5290852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35561871401525946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4067163021019893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7881052272045255, "gear": 1, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4321806685856667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.5290852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.5867888943064967, "y": -0.03400556592972315, "z": null, "yaw": 6.252635464781707, "pitch": null, "roll": null}, "v": 1.742343399069207, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "acceleration": 0.745475799810019, "steering_wheel_angle": -0.5120832145906543, "front_wheel_angle": -0.02367692324113134, "heading_rate": -0.016117594326344496, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.5490851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35561871401525946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4067163021019893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8011244077689847, "gear": 1, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4321806685856667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.5490851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.5690851, "x": 5.7819622468259055, "y": 4.959947382555641, "z": null, "yaw": -0.03144396792533213, "pitch": null, "roll": null}, "v": 1.8141212160639495, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "acceleration": 0.6490005439264406, "steering_wheel_angle": -0.4321806685856667, "front_wheel_angle": -0.01996121178409785, "heading_rate": -0.014147214112136009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.5690851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.332741986403961, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47792069430194456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8141212160639495, "gear": 1, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4321806685856667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.5690851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.7819622468259055, "y": -0.04005261744435895, "z": null, "yaw": 6.251741339254254, "pitch": null, "roll": null}, "v": 1.8141212160639495, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "acceleration": 0.6490005439264406, "steering_wheel_angle": -0.4321806685856667, "front_wheel_angle": -0.01996121178409785, "heading_rate": -0.014147214112136009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.589085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34019805084670207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47792069430194456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.824237267358661, "gear": 1, "accelerator_pedal_position": 0.332741986403961, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3519532324444116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.589085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.7819622468259055, "y": -0.04005261744435895, "z": null, "yaw": 6.251741339254254, "pitch": null, "roll": null}, "v": 1.8141212160639495, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "acceleration": 0.6490005439264406, "steering_wheel_angle": -0.4321806685856667, "front_wheel_angle": -0.01996121178409785, "heading_rate": -0.014147214112136009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.609085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34019805084670207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47792069430194456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8352674433068277, "gear": 1, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3519532324444116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.609085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.7819622468259055, "y": -0.04005261744435895, "z": null, "yaw": 6.251741339254254, "pitch": null, "roll": null}, "v": 1.8141212160639495, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "acceleration": 0.6490005439264406, "steering_wheel_angle": -0.4321806685856667, "front_wheel_angle": -0.01996121178409785, "heading_rate": -0.014147214112136009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.629085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34019805084670207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47792069430194456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8462785122033998, "gear": 1, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3519532324444116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.629085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.7819622468259055, "y": -0.04005261744435895, "z": null, "yaw": 6.251741339254254, "pitch": null, "roll": null}, "v": 1.8141212160639495, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "acceleration": 0.6490005439264406, "steering_wheel_angle": -0.4321806685856667, "front_wheel_angle": -0.01996121178409785, "heading_rate": -0.014147214112136009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.649085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34019805084670207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47792069430194456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8572704586702233, "gear": 1, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3519532324444116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.649085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.7819622468259055, "y": -0.04005261744435895, "z": null, "yaw": 6.251741339254254, "pitch": null, "roll": null}, "v": 1.8141212160639495, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "acceleration": 0.6490005439264406, "steering_wheel_angle": -0.4321806685856667, "front_wheel_angle": -0.01996121178409785, "heading_rate": -0.014147214112136009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.669085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34019805084670207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47792069430194456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.86824326760825, "gear": 1, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3519532324444116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.669085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.679085, "x": 5.984356637505177, "y": 4.953512668578091, "z": null, "yaw": -0.03216359292291094, "pitch": null, "roll": null}, "v": 1.8737224908616685, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "acceleration": 0.5474433335211958, "steering_wheel_angle": -0.3519532324444116, "front_wheel_angle": -0.016238390157444264, "heading_rate": -0.01188629353623964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.689085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32403757131639066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5448423961189416, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8791969241968804, "gear": 1, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3519532324444116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.689085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9843566375051767, "y": -0.04648733142190942, "z": null, "yaw": 6.251021714256675, "pitch": null, "roll": null}, "v": 1.8737224908616685, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "acceleration": 0.5474433335211958, "steering_wheel_angle": -0.3519532324444116, "front_wheel_angle": -0.016238390157444264, "heading_rate": -0.01188629353623964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.709085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3293466279305898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5448423961189416, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8881122395789236, "gear": 1, "accelerator_pedal_position": 0.32403757131639066, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3117023927185367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.709085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9843566375051767, "y": -0.04648733142190942, "z": null, "yaw": 6.251021714256675, "pitch": null, "roll": null}, "v": 1.8737224908616685, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "acceleration": 0.5474433335211958, "steering_wheel_angle": -0.3519532324444116, "front_wheel_angle": -0.016238390157444264, "heading_rate": -0.01188629353623964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.729085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3293466279305898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5448423961189416, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8976752617718284, "gear": 1, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3117023927185367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.729085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9843566375051767, "y": -0.04648733142190942, "z": null, "yaw": 6.251021714256675, "pitch": null, "roll": null}, "v": 1.8737224908616685, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "acceleration": 0.5474433335211958, "steering_wheel_angle": -0.3519532324444116, "front_wheel_angle": -0.016238390157444264, "heading_rate": -0.01188629353623964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.749085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3293466279305898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5448423961189416, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9072214784771742, "gear": 1, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3117023927185367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.749085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9843566375051767, "y": -0.04648733142190942, "z": null, "yaw": 6.251021714256675, "pitch": null, "roll": null}, "v": 1.8737224908616685, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "acceleration": 0.5474433335211958, "steering_wheel_angle": -0.3519532324444116, "front_wheel_angle": -0.016238390157444264, "heading_rate": -0.01188629353623964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.769085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3293466279305898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5448423961189416, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9167508827918767, "gear": 1, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3117023927185367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.769085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.789085, "x": 6.192998476012089, "y": 4.94673811761934, "z": null, "yaw": -0.03279582385818046, "pitch": null, "roll": null}, "v": 1.926263468017414, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "acceleration": 0.47499834168313054, "steering_wheel_angle": -0.3117023927185367, "front_wheel_angle": -0.01437361941300669, "heading_rate": -0.010816126907073322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.789085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3115670314501999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5902408259748769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.926263468017414, "gear": 1, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3117023927185367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.789085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.1929984760120886, "y": -0.0532618823806601, "z": null, "yaw": 6.250389483321406, "pitch": null, "roll": null}, "v": 1.926263468017414, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "acceleration": 0.47499834168313054, "steering_wheel_angle": -0.3117023927185367, "front_wheel_angle": -0.01437361941300669, "heading_rate": -0.010816126907073322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.809085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3173543390753945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5902408259748769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9335377627460868, "gear": 1, "accelerator_pedal_position": 0.3115670314501999, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27135885559125744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.809085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.1929984760120886, "y": -0.0532618823806601, "z": null, "yaw": 6.250389483321406, "pitch": null, "roll": null}, "v": 1.926263468017414, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "acceleration": 0.47499834168313054, "steering_wheel_angle": -0.3117023927185367, "front_wheel_angle": -0.01437361941300669, "heading_rate": -0.010816126907073322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.8290849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3173543390753945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5902408259748769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9415222605884248, "gear": 1, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27135885559125744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.8290849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.1929984760120886, "y": -0.0532618823806601, "z": null, "yaw": 6.250389483321406, "pitch": null, "roll": null}, "v": 1.926263468017414, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "acceleration": 0.47499834168313054, "steering_wheel_angle": -0.3117023927185367, "front_wheel_angle": -0.01437361941300669, "heading_rate": -0.010816126907073322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.8490849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3173543390753945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5902408259748769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.94949258577363, "gear": 1, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27135885559125744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.8490849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.1929984760120886, "y": -0.0532618823806601, "z": null, "yaw": 6.250389483321406, "pitch": null, "roll": null}, "v": 1.926263468017414, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "acceleration": 0.47499834168313054, "steering_wheel_angle": -0.3117023927185367, "front_wheel_angle": -0.01437361941300669, "heading_rate": -0.010816126907073322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.8690848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3173543390753945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5902408259748769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.95744873805934, "gear": 1, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27135885559125744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.8690848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.1929984760120886, "y": -0.0532618823806601, "z": null, "yaw": 6.250389483321406, "pitch": null, "roll": null}, "v": 1.926263468017414, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "acceleration": 0.47499834168313054, "steering_wheel_angle": -0.3117023927185367, "front_wheel_angle": -0.01437361941300669, "heading_rate": -0.010816126907073322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.8890848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3173543390753945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5902408259748769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9653907173390566, "gear": 1, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27135885559125744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.8890848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.8990848, "x": 6.406896542279541, "y": 4.939666697009486, "z": null, "yaw": -0.0333405376086837, "pitch": null, "roll": null}, "v": 1.969356392105419, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "acceleration": 0.39621315362467996, "steering_wheel_angle": -0.27135885559125744, "front_wheel_angle": -0.012506558968784396, "heading_rate": -0.009621545344206147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.9090848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3025241227527877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.637236262518994, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9733185236416657, "gear": 1, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27135885559125744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.9090848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.406896542279541, "y": -0.060333302990514426, "z": null, "yaw": 6.2498447695709025, "pitch": null, "roll": null}, "v": 1.969356392105419, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "acceleration": 0.39621315362467996, "steering_wheel_angle": -0.27135885559125744, "front_wheel_angle": -0.012506558968784396, "heading_rate": -0.009621545344206147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.9290848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3073502376535239, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.637236262518994, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9793792099920684, "gear": 1, "accelerator_pedal_position": 0.3025241227527877, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.9290848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.406896542279541, "y": -0.060333302990514426, "z": null, "yaw": 6.2498447695709025, "pitch": null, "roll": null}, "v": 1.969356392105419, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "acceleration": 0.39621315362467996, "steering_wheel_angle": -0.27135885559125744, "front_wheel_angle": -0.012506558968784396, "heading_rate": -0.009621545344206147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.9490848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3073502376535239, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.637236262518994, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9860320395792532, "gear": 1, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.9490848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.406896542279541, "y": -0.060333302990514426, "z": null, "yaw": 6.2498447695709025, "pitch": null, "roll": null}, "v": 1.969356392105419, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "acceleration": 0.39621315362467996, "steering_wheel_angle": -0.27135885559125744, "front_wheel_angle": -0.012506558968784396, "heading_rate": -0.009621545344206147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.9690847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3073502376535239, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.637236262518994, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9926729410231807, "gear": 1, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.9690847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.406896542279541, "y": -0.060333302990514426, "z": null, "yaw": 6.2498447695709025, "pitch": null, "roll": null}, "v": 1.969356392105419, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "acceleration": 0.39621315362467996, "steering_wheel_angle": -0.27135885559125744, "front_wheel_angle": -0.012506558968784396, "heading_rate": -0.009621545344206147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.9890847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3073502376535239, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.637236262518994, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9993019180776197, "gear": 1, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.9890847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.0090847, "x": 6.625244380468361, "y": 4.932339920735235, "z": null, "yaw": -0.03375380002388734, "pitch": null, "roll": null}, "v": 2.005918974584547, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "acceleration": 0.3304059272793134, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006870197614528951, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.0090847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2906735039473695, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6479939915490437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.005918974584547, "gear": 1, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.0090847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625244380468361, "y": -0.06766007926476458, "z": null, "yaw": 6.249431507155699, "pitch": null, "roll": null}, "v": 2.005918974584547, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "acceleration": 0.3304059272793134, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006870197614528951, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.0290847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2960490663779699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6479939915490437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0104404626407684, "gear": 1, "accelerator_pedal_position": 0.2906735039473695, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.0290847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625244380468361, "y": -0.06766007926476458, "z": null, "yaw": 6.249431507155699, "pitch": null, "roll": null}, "v": 2.005918974584547, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "acceleration": 0.3304059272793134, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006870197614528951, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.0490847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2960490663779699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6479939915490437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.015625440922703, "gear": 1, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.0490847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625244380468361, "y": -0.06766007926476458, "z": null, "yaw": 6.249431507155699, "pitch": null, "roll": null}, "v": 2.005918974584547, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "acceleration": 0.3304059272793134, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006870197614528951, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.0690846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2960490663779699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6479939915490437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0208010607529343, "gear": 1, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.0690846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625244380468361, "y": -0.06766007926476458, "z": null, "yaw": 6.249431507155699, "pitch": null, "roll": null}, "v": 2.005918974584547, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "acceleration": 0.3304059272793134, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006870197614528951, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.0890846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2960490663779699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6479939915490437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0259673283127086, "gear": 1, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.0890846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625244380468361, "y": -0.06766007926476458, "z": null, "yaw": 6.249431507155699, "pitch": null, "roll": null}, "v": 2.005918974584547, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "acceleration": 0.3304059272793134, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006870197614528951, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.1090846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2960490663779699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6479939915490437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0311242498301425, "gear": 1, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.1090846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.1190846, "x": 6.847129021323694, "y": 4.924809488539774, "z": null, "yaw": -0.034130545918000396, "pitch": null, "roll": null}, "v": 2.0336992077820257, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "acceleration": 0.2572623797958782, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006965343876298525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.1290846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28279054617741145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6714079145261908, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0362718315799846, "gear": 1, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.1290846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.8471290213236937, "y": -0.07519051146022626, "z": null, "yaw": 6.249054761261585, "pitch": null, "roll": null}, "v": 2.0336992077820257, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "acceleration": 0.2572623797958782, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006965343876298525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.1490846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2870593978895244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6714079145261908, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0397535170187613, "gear": 1, "accelerator_pedal_position": 0.28279054617741145, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.1490846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.8471290213236937, "y": -0.07519051146022626, "z": null, "yaw": 6.249054761261585, "pitch": null, "roll": null}, "v": 2.0336992077820257, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "acceleration": 0.2572623797958782, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006965343876298525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.1690845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2870593978895244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6714079145261908, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.043762248261874, "gear": 1, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.1690845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.8471290213236937, "y": -0.07519051146022626, "z": null, "yaw": 6.249054761261585, "pitch": null, "roll": null}, "v": 2.0336992077820257, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "acceleration": 0.2572623797958782, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006965343876298525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.1890845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2870593978895244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6714079145261908, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.047763698533108, "gear": 1, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.1890845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.8471290213236937, "y": -0.07519051146022626, "z": null, "yaw": 6.249054761261585, "pitch": null, "roll": null}, "v": 2.0336992077820257, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "acceleration": 0.2572623797958782, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006965343876298525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.2090845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2870593978895244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6714079145261908, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.051757874655004, "gear": 1, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.2090845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.2290845, "x": 7.071817351510738, "y": 4.9170991769563255, "z": null, "yaw": -0.034507291812113455, "pitch": null, "roll": null}, "v": 2.055744783472604, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "acceleration": 0.19907313148814898, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.007040849150160194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.2290845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28164814736982113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7401422442002977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.055744783472604, "gear": 1, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.2290845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.071817351510738, "y": -0.08290082304367452, "z": null, "yaw": 6.248678015367473, "pitch": null, "roll": null}, "v": 2.055744783472604, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "acceleration": 0.19907313148814898, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.007040849150160194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.2490845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834393553443831, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7401422442002977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0590483338150127, "gear": 1, "accelerator_pedal_position": 0.28164814736982113, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10911745138502597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.2490845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.071817351510738, "y": -0.08290082304367452, "z": null, "yaw": 6.248678015367473, "pitch": null, "roll": null}, "v": 2.055744783472604, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "acceleration": 0.19907313148814898, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.007040849150160194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.2690845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834393553443831, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7401422442002977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.062569662457643, "gear": 1, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10911745138502597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.2690845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.071817351510738, "y": -0.08290082304367452, "z": null, "yaw": 6.248678015367473, "pitch": null, "roll": null}, "v": 2.055744783472604, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "acceleration": 0.19907313148814898, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.007040849150160194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.2890844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834393553443831, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7401422442002977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.066084568748933, "gear": 1, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10911745138502597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.2890844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.071817351510738, "y": -0.08290082304367452, "z": null, "yaw": 6.248678015367473, "pitch": null, "roll": null}, "v": 2.055744783472604, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "acceleration": 0.19907313148814898, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.007040849150160194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.3090844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834393553443831, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7401422442002977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.069593059462673, "gear": 1, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10911745138502597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.3090844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.071817351510738, "y": -0.08290082304367452, "z": null, "yaw": 6.248678015367473, "pitch": null, "roll": null}, "v": 2.055744783472604, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "acceleration": 0.19907313148814898, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.007040849150160194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.3290844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834393553443831, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7401422442002977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0730951413873315, "gear": 1, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10911745138502597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.3290844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.3390844, "x": 7.298759796063872, "y": 4.90923820085875, "z": null, "yaw": -0.0347448943453936, "pitch": null, "roll": null}, "v": 2.0748437811791374, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "acceleration": 0.17470401468045993, "steering_wheel_angle": -0.10911745138502597, "front_wheel_angle": -0.00501831746056114, "heading_rate": -0.0040673094458455045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.3490844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27798512712019996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8008589239660826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.076590821325942, "gear": 1, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10911745138502597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.3490844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.298759796063872, "y": -0.09076179914124971, "z": null, "yaw": 6.248440412834193, "pitch": null, "roll": null}, "v": 2.0748437811791374, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "acceleration": 0.17470401468045993, "steering_wheel_angle": -0.10911745138502597, "front_wheel_angle": -0.00501831746056114, "heading_rate": -0.0040673094458455045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.3690844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2797767671599757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8008589239660826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.07939863969748, "gear": 1, "accelerator_pedal_position": 0.27798512712019996, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.3690844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.298759796063872, "y": -0.09076179914124971, "z": null, "yaw": 6.248440412834193, "pitch": null, "roll": null}, "v": 2.0748437811791374, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "acceleration": 0.17470401468045993, "steering_wheel_angle": -0.10911745138502597, "front_wheel_angle": -0.00501831746056114, "heading_rate": -0.0040673094458455045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.3890843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2797767671599757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8008589239660826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0824251703788828, "gear": 1, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.3890843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.298759796063872, "y": -0.09076179914124971, "z": null, "yaw": 6.248440412834193, "pitch": null, "roll": null}, "v": 2.0748437811791374, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "acceleration": 0.17470401468045993, "steering_wheel_angle": -0.10911745138502597, "front_wheel_angle": -0.00501831746056114, "heading_rate": -0.0040673094458455045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.4090843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2797767671599757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8008589239660826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.085446156977823, "gear": 1, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.4090843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.298759796063872, "y": -0.09076179914124971, "z": null, "yaw": 6.248440412834193, "pitch": null, "roll": null}, "v": 2.0748437811791374, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "acceleration": 0.17470401468045993, "steering_wheel_angle": -0.10911745138502597, "front_wheel_angle": -0.00501831746056114, "heading_rate": -0.0040673094458455045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.4290843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2797767671599757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8008589239660826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0884616060012324, "gear": 1, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.4290843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.4490843, "x": 7.527690424979127, "y": 4.901268131757438, "z": null, "yaw": -0.03483582827024726, "pitch": null, "roll": null}, "v": 2.091471523964178, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "acceleration": 0.1502886871961086, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010316257174313843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.4490843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.267048691126001, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7836121012683116, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.091471523964178, "gear": 1, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.4490843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.527690424979127, "y": -0.09873186824256219, "z": null, "yaw": 6.248349478909339, "pitch": null, "roll": null}, "v": 2.091471523964178, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "acceleration": 0.1502886871961086, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010316257174313843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.4690843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711024251110435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7836121012683116, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0928856385688426, "gear": 1, "accelerator_pedal_position": 0.267048691126001, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.4690843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.527690424979127, "y": -0.09873186824256219, "z": null, "yaw": 6.248349478909339, "pitch": null, "roll": null}, "v": 2.091471523964178, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "acceleration": 0.1502886871961086, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010316257174313843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.4890842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711024251110435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7836121012683116, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.094803640596656, "gear": 1, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.4890842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.527690424979127, "y": -0.09873186824256219, "z": null, "yaw": 6.248349478909339, "pitch": null, "roll": null}, "v": 2.091471523964178, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "acceleration": 0.1502886871961086, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010316257174313843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.5090842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711024251110435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7836121012683116, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0967181194748243, "gear": 1, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.5090842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.527690424979127, "y": -0.09873186824256219, "z": null, "yaw": 6.248349478909339, "pitch": null, "roll": null}, "v": 2.091471523964178, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "acceleration": 0.1502886871961086, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010316257174313843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.5290842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711024251110435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7836121012683116, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0986290802095513, "gear": 1, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.5290842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.527690424979127, "y": -0.09873186824256219, "z": null, "yaw": 6.248349478909339, "pitch": null, "roll": null}, "v": 2.091471523964178, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "acceleration": 0.1502886871961086, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010316257174313843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.5490842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711024251110435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7836121012683116, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1005365278059176, "gear": 1, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.5490842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.5590842, "x": 7.758091227316167, "y": 4.893232986476363, "z": null, "yaw": -0.0348900861588282, "pitch": null, "roll": null}, "v": 2.1014889357409903, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "acceleration": 0.09515315268655422, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010365668411773448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.5690842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26836943427445964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8424013848910704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1024404672678556, "gear": 1, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.5690842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.758091227316167, "y": -0.10676701352363693, "z": null, "yaw": 6.248295221020758, "pitch": null, "roll": null}, "v": 2.1014889357409903, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "acceleration": 0.09515315268655422, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010365668411773448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.5890841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692695393362334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8424013848910704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1039994370034507, "gear": 1, "accelerator_pedal_position": 0.26836943427445964, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013437279784330465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.5890841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.758091227316167, "y": -0.10676701352363693, "z": null, "yaw": 6.248295221020758, "pitch": null, "roll": null}, "v": 2.1014889357409903, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "acceleration": 0.09515315268655422, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010365668411773448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.6090841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692695393362334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8424013848910704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1056679986280726, "gear": 1, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013437279784330465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.6090841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.758091227316167, "y": -0.10676701352363693, "z": null, "yaw": 6.248295221020758, "pitch": null, "roll": null}, "v": 2.1014889357409903, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "acceleration": 0.09515315268655422, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010365668411773448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.629084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692695393362334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8424013848910704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107333488010378, "gear": 1, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013437279784330465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.629084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.758091227316167, "y": -0.10676701352363693, "z": null, "yaw": 6.248295221020758, "pitch": null, "roll": null}, "v": 2.1014889357409903, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "acceleration": 0.09515315268655422, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010365668411773448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.649084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692695393362334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8424013848910704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108995909698107, "gear": 1, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013437279784330465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.649084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.669084, "x": 7.989574984388282, "y": 4.885153074897152, "z": null, "yaw": -0.034878252602318284, "pitch": null, "roll": null}, "v": 2.110655268236752, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "acceleration": 0.08285320082626535, "steering_wheel_angle": 0.013437279784330465, "front_wheel_angle": 0.0006172053164278363, "heading_rate": 0.0005088702414535276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.669084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2668931456056679, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9060995092860595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110655268236752, "gear": 1, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013437279784330465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.669084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 3.989574984388282, "y": -0.11484692510284766, "z": null, "yaw": 6.248307054577268, "pitch": null, "roll": null}, "v": 2.110655268236752, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "acceleration": 0.08285320082626535, "steering_wheel_angle": 0.013437279784330465, "front_wheel_angle": 0.0006172053164278363, "heading_rate": 0.0005088702414535276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.689084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26767798994944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9060995092860595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112014655934775, "gear": 1, "accelerator_pedal_position": 0.2668931456056679, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.054408102801085864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.689084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 3.989574984388282, "y": -0.11484692510284766, "z": null, "yaw": 6.248307054577268, "pitch": null, "roll": null}, "v": 2.110655268236752, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "acceleration": 0.08285320082626535, "steering_wheel_angle": 0.013437279784330465, "front_wheel_angle": 0.0006172053164278363, "heading_rate": 0.0005088702414535276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.709084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26767798994944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9060995092860595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.113469597457368, "gear": 1, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.054408102801085864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.709084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 3.989574984388282, "y": -0.11484692510284766, "z": null, "yaw": 6.248307054577268, "pitch": null, "roll": null}, "v": 2.110655268236752, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "acceleration": 0.08285320082626535, "steering_wheel_angle": 0.013437279784330465, "front_wheel_angle": 0.0006172053164278363, "heading_rate": 0.0005088702414535276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.729084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26767798994944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9060995092860595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.114921855498841, "gear": 1, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.054408102801085864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.729084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 3.989574984388282, "y": -0.11484692510284766, "z": null, "yaw": 6.248307054577268, "pitch": null, "roll": null}, "v": 2.110655268236752, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "acceleration": 0.08285320082626535, "steering_wheel_angle": 0.013437279784330465, "front_wheel_angle": 0.0006172053164278363, "heading_rate": 0.0005088702414535276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.749084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26767798994944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9060995092860595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1163714341653503, "gear": 1, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.054408102801085864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.749084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 3.989574984388282, "y": -0.11484692510284766, "z": null, "yaw": 6.248307054577268, "pitch": null, "roll": null}, "v": 2.110655268236752, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "acceleration": 0.08285320082626535, "steering_wheel_angle": 0.013437279784330465, "front_wheel_angle": 0.0006172053164278363, "heading_rate": 0.0005088702414535276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.769084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26767798994944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9060995092860595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1178183375601436, "gear": 1, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.054408102801085864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.769084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.779084, "x": 8.221996556602605, "y": 4.877053143585977, "z": null, "yaw": -0.034778168266129214, "pitch": null, "roll": null}, "v": 2.1185407873121127, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "acceleration": 0.07217824714334387, "steering_wheel_angle": 0.054408102801085864, "front_wheel_angle": 0.002500433255905069, "heading_rate": 0.0020692503431321905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.789084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.265802489568141, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9749783595168136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119262569783546, "gear": 1, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.054408102801085864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.789084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.221996556602605, "y": -0.12294685641402303, "z": null, "yaw": 6.248407138913457, "pitch": null, "roll": null}, "v": 2.1185407873121127, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "acceleration": 0.07217824714334387, "steering_wheel_angle": 0.054408102801085864, "front_wheel_angle": 0.002500433255905069, "heading_rate": 0.0020692503431321905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.809084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2664249723462016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9749783595168136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.120469805693678, "gear": 1, "accelerator_pedal_position": 0.265802489568141, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.809084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.221996556602605, "y": -0.12294685641402303, "z": null, "yaw": 6.248407138913457, "pitch": null, "roll": null}, "v": 2.1185407873121127, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "acceleration": 0.07217824714334387, "steering_wheel_angle": 0.054408102801085864, "front_wheel_angle": 0.002500433255905069, "heading_rate": 0.0020692503431321905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.829084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2664249723462016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9749783595168136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1217525859719544, "gear": 1, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.829084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.221996556602605, "y": -0.12294685641402303, "z": null, "yaw": 6.248407138913457, "pitch": null, "roll": null}, "v": 2.1185407873121127, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "acceleration": 0.07217824714334387, "steering_wheel_angle": 0.054408102801085864, "front_wheel_angle": 0.002500433255905069, "heading_rate": 0.0020692503431321905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.849084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2664249723462016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9749783595168136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1230329960335177, "gear": 1, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.849084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.221996556602605, "y": -0.12294685641402303, "z": null, "yaw": 6.248407138913457, "pitch": null, "roll": null}, "v": 2.1185407873121127, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "acceleration": 0.07217824714334387, "steering_wheel_angle": 0.054408102801085864, "front_wheel_angle": 0.002500433255905069, "heading_rate": 0.0020692503431321905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.869084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2664249723462016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9749783595168136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124311039602384, "gear": 1, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.869084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.8890839, "x": 8.455249790099751, "y": 4.868959186220881, "z": null, "yaw": -0.034545429095979026, "pitch": null, "roll": null}, "v": 2.125586720399321, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "acceleration": 0.06369555208441452, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005209460123255481, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.8890839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612891134525636, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9794231838866834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.125586720399321, "gear": 1, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.8890839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.455249790099751, "y": -0.13104081377911925, "z": null, "yaw": 6.248639878083607, "pitch": null, "roll": null}, "v": 2.125586720399321, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "acceleration": 0.06369555208441452, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005209460123255481, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.9090838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26292663718240417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9794231838866834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.12621835676523, "gear": 1, "accelerator_pedal_position": 0.2612891134525636, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.9090838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.455249790099751, "y": -0.13104081377911925, "z": null, "yaw": 6.248639878083607, "pitch": null, "roll": null}, "v": 2.125586720399321, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "acceleration": 0.06369555208441452, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005209460123255481, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.9290838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26292663718240417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9794231838866834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127053420641093, "gear": 1, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.9290838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.455249790099751, "y": -0.13104081377911925, "z": null, "yaw": 6.248639878083607, "pitch": null, "roll": null}, "v": 2.125586720399321, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "acceleration": 0.06369555208441452, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005209460123255481, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.9490838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26292663718240417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9794231838866834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1278869397477282, "gear": 1, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.9490838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.455249790099751, "y": -0.13104081377911925, "z": null, "yaw": 6.248639878083607, "pitch": null, "roll": null}, "v": 2.125586720399321, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "acceleration": 0.06369555208441452, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005209460123255481, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.9690838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26292663718240417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9794231838866834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128718916665002, "gear": 1, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.9690838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.455249790099751, "y": -0.13104081377911925, "z": null, "yaw": 6.248639878083607, "pitch": null, "roll": null}, "v": 2.125586720399321, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "acceleration": 0.06369555208441452, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005209460123255481, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.9890838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26292663718240417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9794231838866834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.129549353969549, "gear": 1, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.9890838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.9990838, "x": 8.689135754434787, "y": 4.860904985406072, "z": null, "yaw": -0.03427583736017332, "pitch": null, "roll": null}, "v": 2.1299639960713654, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "acceleration": 0.04142581634085468, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005220188099132998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.0090837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26019254613353937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0183881190989668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.130378254234774, "gear": 1, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.0090837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.689135754434787, "y": -0.13909501459392803, "z": null, "yaw": 6.248909469819413, "pitch": null, "roll": null}, "v": 2.1299639960713654, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "acceleration": 0.04142581634085468, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005220188099132998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.0290837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26106720720827337, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0183881190989668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1308640169094106, "gear": 1, "accelerator_pedal_position": 0.26019254613353937, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.17733828785346603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.0290837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.689135754434787, "y": -0.13909501459392803, "z": null, "yaw": 6.248909469819413, "pitch": null, "roll": null}, "v": 2.1299639960713654, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "acceleration": 0.04142581634085468, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005220188099132998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.0490837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26106720720827337, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0183881190989668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131458162224897, "gear": 1, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.17733828785346603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.0490837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.689135754434787, "y": -0.13909501459392803, "z": null, "yaw": 6.248909469819413, "pitch": null, "roll": null}, "v": 2.1299639960713654, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "acceleration": 0.04142581634085468, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005220188099132998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.0690837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26106720720827337, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0183881190989668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1320512073817857, "gear": 1, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.17733828785346603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.0690837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.689135754434787, "y": -0.13909501459392803, "z": null, "yaw": 6.248909469819413, "pitch": null, "roll": null}, "v": 2.1299639960713654, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "acceleration": 0.04142581634085468, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005220188099132998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.0890837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26106720720827337, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0183881190989668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.132643154276587, "gear": 1, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.17733828785346603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.0890837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.1090837, "x": 8.923461037747035, "y": 4.852904567404205, "z": null, "yaw": -0.03393982926155971, "pitch": null, "roll": null}, "v": 2.13323400480308, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "acceleration": 0.029501471619072628, "steering_wheel_angle": 0.17733828785346603, "front_wheel_angle": 0.00816313015830927, "heading_rate": 0.006802442832221776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.1090837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2576387205961097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0411191043669976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.13323400480308, "gear": 1, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.17733828785346603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.1090837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.923461037747035, "y": -0.14709543259579494, "z": null, "yaw": 6.249245477918026, "pitch": null, "roll": null}, "v": 2.13323400480308, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "acceleration": 0.029501471619072628, "steering_wheel_angle": 0.17733828785346603, "front_wheel_angle": 0.00816313015830927, "heading_rate": 0.006802442832221776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.1290836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25872526874398055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0411191043669976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1333953985961056, "gear": 1, "accelerator_pedal_position": 0.2576387205961097, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.1290836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.923461037747035, "y": -0.14709543259579494, "z": null, "yaw": 6.249245477918026, "pitch": null, "roll": null}, "v": 2.13323400480308, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "acceleration": 0.029501471619072628, "steering_wheel_angle": 0.17733828785346603, "front_wheel_angle": 0.00816313015830927, "heading_rate": 0.006802442832221776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.1490836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25872526874398055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0411191043669976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133692248996664, "gear": 1, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.1490836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.923461037747035, "y": -0.14709543259579494, "z": null, "yaw": 6.249245477918026, "pitch": null, "roll": null}, "v": 2.13323400480308, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "acceleration": 0.029501471619072628, "steering_wheel_angle": 0.17733828785346603, "front_wheel_angle": 0.00816313015830927, "heading_rate": 0.006802442832221776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.1690836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25872526874398055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0411191043669976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1339885494556188, "gear": 1, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.1690836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.923461037747035, "y": -0.14709543259579494, "z": null, "yaw": 6.249245477918026, "pitch": null, "roll": null}, "v": 2.13323400480308, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "acceleration": 0.029501471619072628, "steering_wheel_angle": 0.17733828785346603, "front_wheel_angle": 0.00816313015830927, "heading_rate": 0.006802442832221776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.1890836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25872526874398055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0411191043669976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134284300956684, "gear": 1, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.1890836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.923461037747035, "y": -0.14709543259579494, "z": null, "yaw": 6.249245477918026, "pitch": null, "roll": null}, "v": 2.13323400480308, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "acceleration": 0.029501471619072628, "steering_wheel_angle": 0.17733828785346603, "front_wheel_angle": 0.00816313015830927, "heading_rate": 0.006802442832221776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.2090836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25872526874398055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0411191043669976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134579504481946, "gear": 1, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.2090836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.2190835, "x": 9.15805178025884, "y": 4.8449840859451125, "z": null, "yaw": -0.033515217215993896, "pitch": null, "roll": null}, "v": 2.1347269010601084, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "acceleration": 0.014725995175775997, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.00838358722481706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.2290835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25524366629961837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.040032359871897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134874161011866, "gear": 1, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.2290835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.158051780258839, "y": -0.15501591405488746, "z": null, "yaw": 6.249670089963592, "pitch": null, "roll": null}, "v": 2.1347269010601084, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "acceleration": 0.014725995175775997, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.00838358722481706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.2490835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25633858583344005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.040032359871897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1347332729312702, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.2490835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.158051780258839, "y": -0.15501591405488746, "z": null, "yaw": 6.249670089963592, "pitch": null, "roll": null}, "v": 2.1347269010601084, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "acceleration": 0.014725995175775997, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.00838358722481706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.2690835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25633858583344005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.040032359871897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1347294474320457, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.2690835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.158051780258839, "y": -0.15501591405488746, "z": null, "yaw": 6.249670089963592, "pitch": null, "roll": null}, "v": 2.1347269010601084, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "acceleration": 0.014725995175775997, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.00838358722481706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.2890835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25633858583344005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.040032359871897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134725629021597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.2890835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.158051780258839, "y": -0.15501591405488746, "z": null, "yaw": 6.249670089963592, "pitch": null, "roll": null}, "v": 2.1347269010601084, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "acceleration": 0.014725995175775997, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.00838358722481706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.3090835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25633858583344005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.040032359871897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134721817686783, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.3090835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.3290834, "x": 9.392743621505659, "y": 4.837161527182354, "z": null, "yaw": -0.03308322069490637, "pitch": null, "roll": null}, "v": 2.134718013414486, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3523061106386872, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.008383552320889883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.3290834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2570016068815075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134718013414486, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.3290834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.392743621505659, "y": -0.16283847281764618, "z": null, "yaw": 6.25010208648468, "pitch": null, "roll": null}, "v": 2.134718013414486, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3523061106386872, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.008383552320889883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.3490834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25679437147634154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134797055411021, "gear": 1, "accelerator_pedal_position": 0.2570016068815075, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.3490834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.392743621505659, "y": -0.16283847281764618, "z": null, "yaw": 6.25010208648468, "pitch": null, "roll": null}, "v": 2.134718013414486, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3523061106386872, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.008383552320889883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.3690834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25679437147634154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134850058519268, "gear": 1, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.3690834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.392743621505659, "y": -0.16283847281764618, "z": null, "yaw": 6.25010208648468, "pitch": null, "roll": null}, "v": 2.134718013414486, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3523061106386872, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.008383552320889883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.3890834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25679437147634154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1349029634087557, "gear": 1, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.3890834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.392743621505659, "y": -0.16283847281764618, "z": null, "yaw": 6.25010208648468, "pitch": null, "roll": null}, "v": 2.134718013414486, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3523061106386872, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.008383552320889883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.4090834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25679437147634154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134955770260373, "gear": 1, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.4090834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.392743621505659, "y": -0.16283847281764618, "z": null, "yaw": 6.25010208648468, "pitch": null, "roll": null}, "v": 2.134718013414486, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3523061106386872, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.008383552320889883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.4290833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25679437147634154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1350084792546777, "gear": 1, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.4290833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25679437147634154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1350347971116728, "gear": 1, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.4390833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.4390833, "x": 9.627452886215226, "y": 4.829447006871201, "z": null, "yaw": -0.03257722770093844, "pitch": null, "roll": null}, "v": 2.1350347971116728, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "acceleration": 0.002629346022774093, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009964646851478005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.4690833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2515867373724662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0577428377234444, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.135113604391944, "gear": 1, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.4690833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.6274528862152255, "y": -0.17055299312879857, "z": null, "yaw": 6.250608079478647, "pitch": null, "roll": null}, "v": 2.1350347971116728, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "acceleration": 0.002629346022774093, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009964646851478005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.4890833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25321559235117147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0577428377234444, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1343184695992115, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.4890833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.6274528862152255, "y": -0.17055299312879857, "z": null, "yaw": 6.250608079478647, "pitch": null, "roll": null}, "v": 2.1350347971116728, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "acceleration": 0.002629346022774093, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009964646851478005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.5090833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25321559235117147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0577428377234444, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134121753353393, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.5090833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.6274528862152255, "y": -0.17055299312879857, "z": null, "yaw": 6.250608079478647, "pitch": null, "roll": null}, "v": 2.1350347971116728, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "acceleration": 0.002629346022774093, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009964646851478005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.5290833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25321559235117147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0577428377234444, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1337288676608694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.5290833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.5490832, "x": 9.862122618578281, "y": 4.821854223530829, "z": null, "yaw": -0.032063835059682466, "pitch": null, "roll": null}, "v": 2.1333367098566516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35217809066905265, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009956721528742201, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.5490832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25466357082110647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.131896160429709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1333367098566516, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.5490832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.862122618578281, "y": -0.1781457764691714, "z": null, "yaw": 6.2511214721199035, "pitch": null, "roll": null}, "v": 2.1333367098566516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35217809066905265, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009956721528742201, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.5690832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254203207995649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.131896160429709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1331261919800344, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.5690832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.862122618578281, "y": -0.1781457764691714, "z": null, "yaw": 6.2511214721199035, "pitch": null, "roll": null}, "v": 2.1333367098566516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35217809066905265, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009956721528742201, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.5890832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254203207995649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.131896160429709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1328585453770628, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.5890832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.862122618578281, "y": -0.1781457764691714, "z": null, "yaw": 6.2511214721199035, "pitch": null, "roll": null}, "v": 2.1333367098566516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35217809066905265, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009956721528742201, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.6090832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254203207995649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.131896160429709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1325913945390083, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.6090832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.862122618578281, "y": -0.1781457764691714, "z": null, "yaw": 6.2511214721199035, "pitch": null, "roll": null}, "v": 2.1333367098566516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35217809066905265, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009956721528742201, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.6290832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254203207995649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.131896160429709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1323247385190247, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.6290832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.862122618578281, "y": -0.1781457764691714, "z": null, "yaw": 6.2511214721199035, "pitch": null, "roll": null}, "v": 2.1333367098566516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35217809066905265, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009956721528742201, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.6490831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254203207995649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.131896160429709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1320585763721787, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.6490831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.6590831, "x": 10.096602949372915, "y": 4.814395183066751, "z": null, "yaw": -0.03147640483522101, "pitch": null, "roll": null}, "v": 2.1319256802064124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35204735506955637, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011528562212293847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.669083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2515765347012109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0952570979006788, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131792907155445, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.669083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.096602949372915, "y": -0.1856048169332487, "z": null, "yaw": 6.251708902344365, "pitch": null, "roll": null}, "v": 2.1319256802064124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35204735506955637, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011528562212293847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.689083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523908338596441, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0952570979006788, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131199547836431, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.689083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.096602949372915, "y": -0.1856048169332487, "z": null, "yaw": 6.251708902344365, "pitch": null, "roll": null}, "v": 2.1319256802064124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35204735506955637, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011528562212293847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.709083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523908338596441, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0952570979006788, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1307090274875042, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.709083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.096602949372915, "y": -0.1856048169332487, "z": null, "yaw": 6.251708902344365, "pitch": null, "roll": null}, "v": 2.1319256802064124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35204735506955637, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011528562212293847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.729083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523908338596441, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0952570979006788, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1302194153246923, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.729083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.096602949372915, "y": -0.1856048169332487, "z": null, "yaw": 6.251708902344365, "pitch": null, "roll": null}, "v": 2.1319256802064124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35204735506955637, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011528562212293847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.749083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523908338596441, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0952570979006788, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1297307095706675, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.749083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.769083, "x": 10.330868366519734, "y": 4.807082301621625, "z": null, "yaw": -0.03088157085243903, "pitch": null, "roll": null}, "v": 2.1292429084519253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35179889905452444, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011514054904951878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.769083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25412339704589015, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.166948328376467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1292429084519253, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.769083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.330868366519734, "y": -0.19291769837837514, "z": null, "yaw": 6.252303736327147, "pitch": null, "roll": null}, "v": 2.1292429084519253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35179889905452444, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011514054904951878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.789083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356954788630487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.166948328376467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128972480345459, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.789083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.330868366519734, "y": -0.19291769837837514, "z": null, "yaw": 6.252303736327147, "pitch": null, "roll": null}, "v": 2.1292429084519253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35179889905452444, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011514054904951878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.809083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356954788630487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.166948328376467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1286333536371282, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.809083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.330868366519734, "y": -0.19291769837837514, "z": null, "yaw": 6.252303736327147, "pitch": null, "roll": null}, "v": 2.1292429084519253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35179889905452444, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011514054904951878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.829083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356954788630487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.166948328376467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1281258399437992, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.829083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.330868366519734, "y": -0.19291769837837514, "z": null, "yaw": 6.252303736327147, "pitch": null, "roll": null}, "v": 2.1292429084519253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35179889905452444, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011514054904951878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.839083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356954788630487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.166948328376467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1279569818076576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.839083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.330868366519734, "y": -0.19291769837837514, "z": null, "yaw": 6.252303736327147, "pitch": null, "roll": null}, "v": 2.1292429084519253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35179889905452444, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011514054904951878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.869083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356954788630487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.166948328376467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1276197342744787, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.869083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.879083, "x": 10.56488898159465, "y": 4.7999235042026145, "z": null, "yaw": -0.030212622934581546, "pitch": null, "roll": null}, "v": 2.127451344576868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35163305946426265, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.013081104785278729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.889083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532404816634855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1943453621147595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1272831107251196, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.889083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.564888981594651, "y": -0.2000764957973855, "z": null, "yaw": 6.252972684245004, "pitch": null, "roll": null}, "v": 2.127451344576868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35163305946426265, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.013081104785278729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.909083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333502294058957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1943453621147595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1269059957147105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.909083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.564888981594651, "y": -0.2000764957973855, "z": null, "yaw": 6.252972684245004, "pitch": null, "roll": null}, "v": 2.127451344576868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35163305946426265, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.013081104785278729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.9290829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333502294058957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1943453621147595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1263593409477504, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.9290829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.564888981594651, "y": -0.2000764957973855, "z": null, "yaw": 6.252972684245004, "pitch": null, "roll": null}, "v": 2.127451344576868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35163305946426265, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.013081104785278729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.9390829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333502294058957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1943453621147595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1263593409477504, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.9390829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.564888981594651, "y": -0.2000764957973855, "z": null, "yaw": 6.252972684245004, "pitch": null, "roll": null}, "v": 2.127451344576868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35163305946426265, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.013081104785278729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.9690828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333502294058957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1943453621147595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1258142022199102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.9690828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.9890828, "x": 10.79870417991751, "y": 4.792929119450943, "z": null, "yaw": -0.02953626362321651, "pitch": null, "roll": null}, "v": 2.1254516164805497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514480265640253, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.01306880901511379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.9890828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25288953804901415, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2013157563996724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1254516164805497, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.9890828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.798704179917509, "y": -0.20707088054905665, "z": null, "yaw": 6.253649043556369, "pitch": null, "roll": null}, "v": 2.1254516164805497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514480265640253, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.01306880901511379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.0090828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530195005178296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2013157563996724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1250340414377273, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.0090828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.798704179917509, "y": -0.20707088054905665, "z": null, "yaw": 6.253649043556369, "pitch": null, "roll": null}, "v": 2.1254516164805497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514480265640253, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.01306880901511379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.0290828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530195005178296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2013157563996724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1246334763699792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.0290828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.798704179917509, "y": -0.20707088054905665, "z": null, "yaw": 6.253649043556369, "pitch": null, "roll": null}, "v": 2.1254516164805497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514480265640253, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.01306880901511379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.0490828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530195005178296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2013157563996724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1242336519622387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.0490828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.798704179917509, "y": -0.20707088054905665, "z": null, "yaw": 6.253649043556369, "pitch": null, "roll": null}, "v": 2.1254516164805497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514480265640253, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.01306880901511379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.0690827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530195005178296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2013157563996724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1238345667810825, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.0690827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.798704179917509, "y": -0.20707088054905665, "z": null, "yaw": 6.253649043556369, "pitch": null, "roll": null}, "v": 2.1254516164805497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514480265640253, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.01306880901511379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.0890827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530195005178296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2013157563996724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.123436219396093, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.0890827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.0990827, "x": 11.032292593177704, "y": 4.786106739397997, "z": null, "yaw": -0.02878571468773155, "pitch": null, "roll": null}, "v": 2.1232373219309753, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35124323334895496, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014630415724003863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.1090827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25270388739237304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2150920898485726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1230386083798503, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.1090827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.032292593177704, "y": -0.21389326060200275, "z": null, "yaw": 6.254399592491855, "pitch": null, "roll": null}, "v": 2.1232373219309753, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35124323334895496, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014630415724003863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.1290827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25279227689127737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2150920898485726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1226022989050652, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.1290827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.032292593177704, "y": -0.21389326060200275, "z": null, "yaw": 6.254399592491855, "pitch": null, "roll": null}, "v": 2.1232373219309753, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35124323334895496, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014630415724003863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.1490827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25279227689127737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2150920898485726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.122177839410682, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.1490827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.032292593177704, "y": -0.21389326060200275, "z": null, "yaw": 6.254399592491855, "pitch": null, "roll": null}, "v": 2.1232373219309753, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35124323334895496, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014630415724003863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.1690826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25279227689127737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2150920898485726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1217541643424793, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.1690826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.032292593177704, "y": -0.21389326060200275, "z": null, "yaw": 6.254399592491855, "pitch": null, "roll": null}, "v": 2.1232373219309753, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35124323334895496, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014630415724003863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.1890826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25279227689127737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2150920898485726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1213312721790243, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.1890826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.2090826, "x": 11.265637983431096, "y": 4.77946831411495, "z": null, "yaw": -0.028027746789834596, "pitch": null, "roll": null}, "v": 2.1209091614020936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.351028014779298, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014614373260894377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.2090826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25324859477747996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2328716954350258, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1209091614020936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.2090826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.2656379834310965, "y": -0.22053168588505034, "z": null, "yaw": 6.255157560389752, "pitch": null, "roll": null}, "v": 2.1209091614020936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.351028014779298, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014614373260894377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.2290826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530952344090079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2328716954350258, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1205448438760173, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.2290826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.2656379834310965, "y": -0.22053168588505034, "z": null, "yaw": 6.255157560389752, "pitch": null, "roll": null}, "v": 2.1209091614020936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.351028014779298, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014614373260894377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.2490826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530952344090079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2328716954350258, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.120162038201464, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.2490826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.2656379834310965, "y": -0.22053168588505034, "z": null, "yaw": 6.255157560389752, "pitch": null, "roll": null}, "v": 2.1209091614020936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.351028014779298, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014614373260894377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.2690825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530952344090079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2328716954350258, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1197799396644026, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.2690825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.2656379834310965, "y": -0.22053168588505034, "z": null, "yaw": 6.255157560389752, "pitch": null, "roll": null}, "v": 2.1209091614020936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.351028014779298, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014614373260894377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.2890825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530952344090079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2328716954350258, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119398546900202, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.2890825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.2656379834310965, "y": -0.22053168588505034, "z": null, "yaw": 6.255157560389752, "pitch": null, "roll": null}, "v": 2.1209091614020936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.351028014779298, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014614373260894377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.3090825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530952344090079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2328716954350258, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1190178585470734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.3090825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.3190825, "x": 11.498745235178198, "y": 4.773013492349493, "z": null, "yaw": -0.027269778891937643, "pitch": null, "roll": null}, "v": 2.1188277780998788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35083570043747064, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014600031245200765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.3290825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505153023462759, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.148705227759269, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118637873246067, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.3290825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.498745235178198, "y": -0.22698650765050665, "z": null, "yaw": 6.255915528287648, "pitch": null, "roll": null}, "v": 2.1188277780998788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35083570043747064, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014600031245200765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.3490825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25131191592108887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.148705227759269, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117936247071652, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.3490825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.498745235178198, "y": -0.22698650765050665, "z": null, "yaw": 6.255915528287648, "pitch": null, "roll": null}, "v": 2.1188277780998788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35083570043747064, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014600031245200765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.3690825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25131191592108887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.148705227759269, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117335447090131, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.3690825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.498745235178198, "y": -0.22698650765050665, "z": null, "yaw": 6.255915528287648, "pitch": null, "roll": null}, "v": 2.1188277780998788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35083570043747064, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014600031245200765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.3890824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25131191592108887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.148705227759269, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1167357562703524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.3890824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.498745235178198, "y": -0.22698650765050665, "z": null, "yaw": 6.255915528287648, "pitch": null, "roll": null}, "v": 2.1188277780998788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35083570043747064, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014600031245200765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.4090824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25131191592108887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.148705227759269, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.116137172420862, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.4090824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.4290824, "x": 11.731569238083926, "y": 4.76674310988472, "z": null, "yaw": -0.02651181099404069, "pitch": null, "roll": null}, "v": 2.1155396933550468, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35053206660936, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014577374311726697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.4290824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2535888401903464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2221937543772068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11538367520085, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.4290824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.731569238083926, "y": -0.23325689011528006, "z": null, "yaw": 6.256673496185545, "pitch": null, "roll": null}, "v": 2.1155396933550468, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35053206660936, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014577374311726697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.4390824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25286211918832247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2221937543772068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11538367520085, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.4390824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.731569238083926, "y": -0.23325689011528006, "z": null, "yaw": 6.256673496185545, "pitch": null, "roll": null}, "v": 2.1155396933550468, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35053206660936, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014577374311726697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.4690824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25286211918832247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2221937543772068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1147803498460815, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.4690824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.731569238083926, "y": -0.23325689011528006, "z": null, "yaw": 6.256673496185545, "pitch": null, "roll": null}, "v": 2.1155396933550468, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35053206660936, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014577374311726697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.4890823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25286211918832247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2221937543772068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1143790604768538, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.4890823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.731569238083926, "y": -0.23325689011528006, "z": null, "yaw": 6.256673496185545, "pitch": null, "roll": null}, "v": 2.1155396933550468, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35053206660936, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014577374311726697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.5090823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25286211918832247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2221937543772068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1139785114624488, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.5090823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.731569238083926, "y": -0.23325689011528006, "z": null, "yaw": 6.256673496185545, "pitch": null, "roll": null}, "v": 2.1155396933550468, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35053206660936, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014577374311726697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.5290823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25286211918832247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2221937543772068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11357870137281, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.5290823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.5390823, "x": 11.964093006505637, "y": 4.760657191119084, "z": null, "yaw": -0.025753843096143737, "pitch": null, "roll": null}, "v": 2.113379072978704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503326647099785, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.01456248630368297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.5490823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25243300322061557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1950346124705062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1131796287808746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.5490823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 7.964093006505637, "y": -0.23934280888091575, "z": null, "yaw": 6.257431464083442, "pitch": null, "roll": null}, "v": 2.113379072978704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503326647099785, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.01456248630368297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.5690823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25255713194694007, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1950346124705062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112727677510324, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.5690823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 7.964093006505637, "y": -0.23934280888091575, "z": null, "yaw": 6.257431464083442, "pitch": null, "roll": null}, "v": 2.113379072978704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503326647099785, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.01456248630368297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.5890822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25255713194694007, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1950346124705062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1122920687007767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.5890822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 7.964093006505637, "y": -0.23934280888091575, "z": null, "yaw": 6.257431464083442, "pitch": null, "roll": null}, "v": 2.113379072978704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503326647099785, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.01456248630368297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.6090822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25255713194694007, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1950346124705062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111857263201547, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.6090822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 7.964093006505637, "y": -0.23934280888091575, "z": null, "yaw": 6.257431464083442, "pitch": null, "roll": null}, "v": 2.113379072978704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503326647099785, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.01456248630368297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.6290822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25255713194694007, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1950346124705062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1114232594556546, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.6290822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.6490822, "x": 12.196370433155991, "y": 4.754753894408984, "z": null, "yaw": -0.024995875198246784, "pitch": null, "roll": null}, "v": 2.1109900559094092, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501122929569546, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014546024501446122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.6490822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2544948686038667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2703169854615255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1109900559094092, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.6490822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.196370433155991, "y": -0.24524610559101578, "z": null, "yaw": 6.258189431981339, "pitch": null, "roll": null}, "v": 2.1109900559094092, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501122929569546, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014546024501446122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.6690822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538783069066766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2703169854615255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1107997564122343, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.6690822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.196370433155991, "y": -0.24524610559101578, "z": null, "yaw": 6.258189431981339, "pitch": null, "roll": null}, "v": 2.1109900559094092, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501122929569546, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014546024501446122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.6890821} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538783069066766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2703169854615255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1105327730525048, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.6890821} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.196370433155991, "y": -0.24524610559101578, "z": null, "yaw": 6.258189431981339, "pitch": null, "roll": null}, "v": 2.1109900559094092, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501122929569546, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014546024501446122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.7090821} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538783069066766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2703169854615255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110266281847101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.7090821} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.196370433155991, "y": -0.24524610559101578, "z": null, "yaw": 6.258189431981339, "pitch": null, "roll": null}, "v": 2.1109900559094092, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501122929569546, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014546024501446122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.729082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538783069066766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2703169854615255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110000281860397, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.729082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.196370433155991, "y": -0.24524610559101578, "z": null, "yaw": 6.258189431981339, "pitch": null, "roll": null}, "v": 2.1109900559094092, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501122929569546, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014546024501446122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.749082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538783069066766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2703169854615255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1097347721586486, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.749082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.759082, "x": 12.428442919754117, "y": 4.749038887642488, "z": null, "yaw": -0.024163568994927845, "pitch": null, "roll": null}, "v": 2.109602200873351, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998432450296446, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104703850863364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.769082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25260805876863096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2222551159996506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1094697518099887, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.769082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.428442919754117, "y": -0.25096111235751195, "z": null, "yaw": 6.259021738184658, "pitch": null, "roll": null}, "v": 2.109602200873351, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998432450296446, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104703850863364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.789082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529986131451381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2222551159996506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1090465120540665, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.789082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.428442919754117, "y": -0.25096111235751195, "z": null, "yaw": 6.259021738184658, "pitch": null, "roll": null}, "v": 2.109602200873351, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998432450296446, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104703850863364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.809082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529986131451381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2222551159996506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108672849046091, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.809082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.428442919754117, "y": -0.25096111235751195, "z": null, "yaw": 6.259021738184658, "pitch": null, "roll": null}, "v": 2.109602200873351, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998432450296446, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104703850863364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.829082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529986131451381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2222551159996506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1082998745708337, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.829082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.428442919754117, "y": -0.25096111235751195, "z": null, "yaw": 6.259021738184658, "pitch": null, "roll": null}, "v": 2.109602200873351, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998432450296446, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104703850863364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.849082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529986131451381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2222551159996506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107927587303946, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.849082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.869082, "x": 12.660332101796328, "y": 4.743523073727132, "z": null, "yaw": -0.023323828961066707, "pitch": null, "roll": null}, "v": 2.1075559859238275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34979572163422495, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016089083045308816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.869082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25243057350229997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1689258842677388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1075559859238275, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.869082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.660332101796328, "y": -0.25647692627286833, "z": null, "yaw": 6.25986147821852, "pitch": null, "roll": null}, "v": 2.1075559859238275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34979572163422495, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016089083045308816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.889082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525986558574533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1689258842677388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106893457684487, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.889082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.660332101796328, "y": -0.25647692627286833, "z": null, "yaw": 6.25986147821852, "pitch": null, "roll": null}, "v": 2.1075559859238275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34979572163422495, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016089083045308816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.909082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525986558574533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1689258842677388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106683526942532, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.909082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.660332101796328, "y": -0.25647692627286833, "z": null, "yaw": 6.25986147821852, "pitch": null, "roll": null}, "v": 2.1075559859238275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34979572163422495, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016089083045308816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.929082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525986558574533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1689258842677388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1062642455355265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.929082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.660332101796328, "y": -0.25647692627286833, "z": null, "yaw": 6.25986147821852, "pitch": null, "roll": null}, "v": 2.1075559859238275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34979572163422495, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016089083045308816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.949082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525986558574533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1689258842677388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1058457363186265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.949082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.660332101796328, "y": -0.25647692627286833, "z": null, "yaw": 6.25986147821852, "pitch": null, "roll": null}, "v": 2.1075559859238275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34979572163422495, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016089083045308816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.9690819} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525986558574533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1689258842677388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105427997799663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.9690819} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.9790819, "x": 12.891983971707562, "y": 4.738207536213969, "z": null, "yaw": -0.02248408892720557, "pitch": null, "roll": null}, "v": 2.105219417086462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495804587951018, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016071245678085107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.9890819} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25474076460660716, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237528335222172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105011028489602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.9890819} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 8.891983971707562, "y": -0.2617924637860307, "z": null, "yaw": 6.260701218252381, "pitch": null, "roll": null}, "v": 2.105219417086462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495804587951018, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016071245678085107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.0090818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25406059203458453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237528335222172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1048624671945317, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.0090818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 8.891983971707562, "y": -0.2617924637860307, "z": null, "yaw": 6.260701218252381, "pitch": null, "roll": null}, "v": 2.105219417086462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495804587951018, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016071245678085107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.0290818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25406059203458453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237528335222172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104512722994321, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.0290818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 8.891983971707562, "y": -0.2617924637860307, "z": null, "yaw": 6.260701218252381, "pitch": null, "roll": null}, "v": 2.105219417086462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495804587951018, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016071245678085107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.0490818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25406059203458453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237528335222172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104396356254861, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.0490818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 8.891983971707562, "y": -0.2617924637860307, "z": null, "yaw": 6.260701218252381, "pitch": null, "roll": null}, "v": 2.105219417086462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495804587951018, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016071245678085107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.0690818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25406059203458453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237528335222172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1041639441577695, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.0690818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.0890818, "x": 13.123435475612741, "y": 4.733091062421746, "z": null, "yaw": -0.02164434889334443, "pitch": null, "roll": null}, "v": 2.1039319598943664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494618949133678, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061417229484332, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.0890818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253562120474135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2168565299008323, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103784973474866, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.0890818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.123435475612741, "y": -0.26690893757825407, "z": null, "yaw": 6.261540958286242, "pitch": null, "roll": null}, "v": 2.1039319598943664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494618949133678, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061417229484332, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.1090817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537119647409344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2168565299008323, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1036381223963003, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.1090817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.123435475612741, "y": -0.26690893757825407, "z": null, "yaw": 6.261540958286242, "pitch": null, "roll": null}, "v": 2.1039319598943664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494618949133678, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061417229484332, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.1290817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537119647409344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2168565299008323, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103363547657126, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.1290817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.123435475612741, "y": -0.26690893757825407, "z": null, "yaw": 6.261540958286242, "pitch": null, "roll": null}, "v": 2.1039319598943664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494618949133678, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061417229484332, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.1490817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537119647409344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2168565299008323, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103089478279686, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.1490817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.123435475612741, "y": -0.26690893757825407, "z": null, "yaw": 6.261540958286242, "pitch": null, "roll": null}, "v": 2.1039319598943664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494618949133678, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061417229484332, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.1690817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537119647409344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2168565299008323, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1028159133038162, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.1690817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.123435475612741, "y": -0.26690893757825407, "z": null, "yaw": 6.261540958286242, "pitch": null, "roll": null}, "v": 2.1039319598943664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494618949133678, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061417229484332, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.1890817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537119647409344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2168565299008323, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1025428517712874, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.1890817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.1990817, "x": 13.354738432921286, "y": 4.728172195951682, "z": null, "yaw": -0.020804608859483292, "pitch": null, "roll": null}, "v": 2.1024065094973565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493214567866364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01604977194068398, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.2090816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25390723699865614, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1873271797318827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1022702927257986, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.2090816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.354738432921286, "y": -0.27182780404831774, "z": null, "yaw": 6.262380698320103, "pitch": null, "roll": null}, "v": 2.1024065094973565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493214567866364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01604977194068398, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.2290816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253839192467168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1873271797318827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102022633011809, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.2290816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.354738432921286, "y": -0.27182780404831774, "z": null, "yaw": 6.262380698320103, "pitch": null, "roll": null}, "v": 2.1024065094973565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493214567866364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01604977194068398, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.2490816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253839192467168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1873271797318827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1017669273361284, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.2490816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.354738432921286, "y": -0.27182780404831774, "z": null, "yaw": 6.262380698320103, "pitch": null, "roll": null}, "v": 2.1024065094973565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493214567866364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01604977194068398, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.2690816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253839192467168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1873271797318827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101511692129556, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.2690816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.354738432921286, "y": -0.27182780404831774, "z": null, "yaw": 6.262380698320103, "pitch": null, "roll": null}, "v": 2.1024065094973565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493214567866364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01604977194068398, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.2890816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253839192467168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1873271797318827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101256926500437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.2890816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.3090816, "x": 13.585884505922996, "y": 4.723450853649149, "z": null, "yaw": -0.019964868825622154, "pitch": null, "roll": null}, "v": 2.1010026295589004, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34919225197207915, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01603905472080165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.3090816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25583138615915735, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.255843596491743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1010026295589004, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.3090816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.585884505922996, "y": -0.2765491463508507, "z": null, "yaw": 6.263220438353964, "pitch": null, "roll": null}, "v": 2.1010026295589004, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34919225197207915, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01603905472080165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.3290815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552023649772644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.255843596491743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1009559398721476, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.3290815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.585884505922996, "y": -0.2765491463508507, "z": null, "yaw": 6.263220438353964, "pitch": null, "roll": null}, "v": 2.1010026295589004, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34919225197207915, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01603905472080165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.3490815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552023649772644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.255843596491743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100914208127162, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.3490815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.585884505922996, "y": -0.2765491463508507, "z": null, "yaw": 6.263220438353964, "pitch": null, "roll": null}, "v": 2.1010026295589004, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34919225197207915, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01603905472080165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.3690815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552023649772644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.255843596491743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100830859804537, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.3690815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.585884505922996, "y": -0.2765491463508507, "z": null, "yaw": 6.263220438353964, "pitch": null, "roll": null}, "v": 2.1010026295589004, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34919225197207915, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01603905472080165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.3890815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552023649772644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.255843596491743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1007476648006485, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.3890815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.585884505922996, "y": -0.2765491463508507, "z": null, "yaw": 6.263220438353964, "pitch": null, "roll": null}, "v": 2.1010026295589004, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34919225197207915, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01603905472080165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.4090815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552023649772644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.255843596491743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1006646228307004, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.4090815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.4190814, "x": 13.816935004920976, "y": 4.718925571147037, "z": null, "yaw": -0.019125128791761016, "pitch": null, "roll": null}, "v": 2.100623159144603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3491573345245767, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016036157843542093, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.4290814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25406665563568187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1957863488103657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1005817336104364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.4290814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 9.816935004920976, "y": -0.2810744288529632, "z": null, "yaw": 6.264060178387825, "pitch": null, "roll": null}, "v": 2.100623159144603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3491573345245767, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016036157843542093, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.4490814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25441981916410333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1957863488103657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100357098498893, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.4490814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 9.816935004920976, "y": -0.2810744288529632, "z": null, "yaw": 6.264060178387825, "pitch": null, "roll": null}, "v": 2.100623159144603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3491573345245767, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016036157843542093, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.4690814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25441981916410333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1957863488103657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1001770016959442, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.4690814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 9.816935004920976, "y": -0.2810744288529632, "z": null, "yaw": 6.264060178387825, "pitch": null, "roll": null}, "v": 2.100623159144603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3491573345245767, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016036157843542093, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.4890814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25441981916410333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1957863488103657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0999972361346604, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.4890814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 9.816935004920976, "y": -0.2810744288529632, "z": null, "yaw": 6.264060178387825, "pitch": null, "roll": null}, "v": 2.100623159144603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3491573345245767, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016036157843542093, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.5090814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25441981916410333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1957863488103657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0998178011928874, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.5090814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.5290813, "x": 14.047914550342588, "y": 4.714595707703617, "z": null, "yaw": -0.018285388757899878, "pitch": null, "roll": null}, "v": 2.0996386962496865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490667613603752, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028642453499255, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.5290813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562437743147492, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2658300597120653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0996632645307547, "gear": 1, "accelerator_pedal_position": 0.2562437743147492, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.5290813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.047914550342588, "y": -0.2854042922963833, "z": null, "yaw": 6.264899918421686, "pitch": null, "roll": null}, "v": 2.0996386962496865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490667613603752, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028642453499255, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.5490813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556692592952809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2658300597120653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0996878102107193, "gear": 1, "accelerator_pedal_position": 0.2562437743147492, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.5490813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.047914550342588, "y": -0.2854042922963833, "z": null, "yaw": 6.264899918421686, "pitch": null, "roll": null}, "v": 2.0996386962496865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490667613603752, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028642453499255, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.5690813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556692592952809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2658300597120653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0996650525049874, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.5690813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.047914550342588, "y": -0.2854042922963833, "z": null, "yaw": 6.264899918421686, "pitch": null, "roll": null}, "v": 2.0996386962496865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490667613603752, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028642453499255, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.5890813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556692592952809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2658300597120653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099642336651178, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.5890813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.047914550342588, "y": -0.2854042922963833, "z": null, "yaw": 6.264899918421686, "pitch": null, "roll": null}, "v": 2.0996386962496865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490667613603752, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028642453499255, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.6090813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556692592952809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2658300597120653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0996196625721173, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.6090813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.047914550342588, "y": -0.2854042922963833, "z": null, "yaw": 6.264899918421686, "pitch": null, "roll": null}, "v": 2.0996386962496865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490667613603752, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028642453499255, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.6290812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556692592952809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2658300597120653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099597030190776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.6290812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.6390812, "x": 14.278838361300004, "y": 4.710460877294299, "z": null, "yaw": -0.01744564872403874, "pitch": null, "roll": null}, "v": 2.0995857296127167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490618888405695, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602823810617632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.6490812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532075678172948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1136629252580543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099574439430266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.6490812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.278838361300004, "y": -0.28953912270570115, "z": null, "yaw": 6.265739658455548, "pitch": null, "roll": null}, "v": 2.0995857296127167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490618888405695, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602823810617632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.6690812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25397660328239413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1136629252580543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0992443203105466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.6690812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.278838361300004, "y": -0.28953912270570115, "z": null, "yaw": 6.265739658455548, "pitch": null, "roll": null}, "v": 2.0995857296127167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490618888405695, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602823810617632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.6890812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25397660328239413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1136629252580543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0990108934640097, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.6890812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.278838361300004, "y": -0.28953912270570115, "z": null, "yaw": 6.265739658455548, "pitch": null, "roll": null}, "v": 2.0995857296127167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490618888405695, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602823810617632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.7090812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25397660328239413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1136629252580543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0987778958384755, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.7090812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.278838361300004, "y": -0.28953912270570115, "z": null, "yaw": 6.265739658455548, "pitch": null, "roll": null}, "v": 2.0995857296127167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490618888405695, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602823810617632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.7290812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25397660328239413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1136629252580543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098545326622995, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.7290812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.7490811, "x": 14.509697345387606, "y": 4.70652111887258, "z": null, "yaw": -0.0166059086901776, "pitch": null, "roll": null}, "v": 2.09831318500823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894484147420535, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018523500273947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.7490811} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25604962148469773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1792737637433677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09831318500823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.7490811} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.509697345387606, "y": -0.29347888112742027, "z": null, "yaw": 6.266579398489409, "pitch": null, "roll": null}, "v": 2.09831318500823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894484147420535, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018523500273947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.769081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553959504995795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1792737637433677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098340478308227, "gear": 1, "accelerator_pedal_position": 0.25604962148469773, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.769081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.509697345387606, "y": -0.29347888112742027, "z": null, "yaw": 6.266579398489409, "pitch": null, "roll": null}, "v": 2.09831318500823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894484147420535, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018523500273947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.789081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553959504995795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1792737637433677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098286050129155, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.789081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.509697345387606, "y": -0.29347888112742027, "z": null, "yaw": 6.266579398489409, "pitch": null, "roll": null}, "v": 2.09831318500823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894484147420535, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018523500273947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.809081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553959504995795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1792737637433677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098231722014879, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.809081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.509697345387606, "y": -0.29347888112742027, "z": null, "yaw": 6.266579398489409, "pitch": null, "roll": null}, "v": 2.09831318500823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894484147420535, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018523500273947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.829081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553959504995795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1792737637433677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098177493780254, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.829081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.509697345387606, "y": -0.29347888112742027, "z": null, "yaw": 6.266579398489409, "pitch": null, "roll": null}, "v": 2.09831318500823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894484147420535, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018523500273947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.849081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553959504995795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1792737637433677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0981233652404803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.849081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.859081, "x": 14.740474224886462, "y": 4.702776616223692, "z": null, "yaw": -0.015766168656316464, "pitch": null, "roll": null}, "v": 2.098096338298507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489248993627414, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01601686809242517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.869081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2571616067168739, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2523231330276907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098069336211103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.869081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 10.740474224886462, "y": -0.2972233837763083, "z": null, "yaw": 6.26741913852327, "pitch": null, "roll": null}, "v": 2.098096338298507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489248993627414, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01601686809242517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.889081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566088416809752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2523231330276907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098236012051933, "gear": 1, "accelerator_pedal_position": 0.2571616067168739, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.889081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 10.740474224886462, "y": -0.2972233837763083, "z": null, "yaw": 6.26741913852327, "pitch": null, "roll": null}, "v": 2.098096338298507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489248993627414, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01601686809242517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.909081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566088416809752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2523231330276907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0983333176133345, "gear": 1, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.909081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 10.740474224886462, "y": -0.2972233837763083, "z": null, "yaw": 6.26741913852327, "pitch": null, "roll": null}, "v": 2.098096338298507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489248993627414, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01601686809242517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.929081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566088416809752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2523231330276907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0984304442806203, "gear": 1, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.929081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 10.740474224886462, "y": -0.2972233837763083, "z": null, "yaw": 6.26741913852327, "pitch": null, "roll": null}, "v": 2.098096338298507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489248993627414, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01601686809242517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.949081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566088416809752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2523231330276907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0985273923789114, "gear": 1, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.949081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.969081, "x": 14.971262572664498, "y": 4.699225784328202, "z": null, "yaw": -0.014926428622455308, "pitch": null, "roll": null}, "v": 2.0986241622327517, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "acceleration": 0.0048318186513860995, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020897500501674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.969081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25655252886272134, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2279626041404486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0986241622327517, "gear": 1, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.969081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 10.971262572664498, "y": -0.3007742156717983, "z": null, "yaw": 6.2682588785571305, "pitch": null, "roll": null}, "v": 2.0986241622327517, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "acceleration": 0.0048318186513860995, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020897500501674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.989081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565725537561534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2279626041404486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0987137183008793, "gear": 1, "accelerator_pedal_position": 0.25655252886272134, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.989081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 10.971262572664498, "y": -0.3007742156717983, "z": null, "yaw": 6.2682588785571305, "pitch": null, "roll": null}, "v": 2.0986241622327517, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "acceleration": 0.0048318186513860995, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020897500501674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.009081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565725537561534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2279626041404486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0988056116690372, "gear": 1, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.009081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 10.971262572664498, "y": -0.3007742156717983, "z": null, "yaw": 6.2682588785571305, "pitch": null, "roll": null}, "v": 2.0986241622327517, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "acceleration": 0.0048318186513860995, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020897500501674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.0290809} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565725537561534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2279626041404486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0988973360758827, "gear": 1, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.0290809} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 10.971262572664498, "y": -0.3007742156717983, "z": null, "yaw": 6.2682588785571305, "pitch": null, "roll": null}, "v": 2.0986241622327517, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "acceleration": 0.0048318186513860995, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020897500501674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.0490808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565725537561534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2279626041404486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098988891828715, "gear": 1, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.0490808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 10.971262572664498, "y": -0.3007742156717983, "z": null, "yaw": 6.2682588785571305, "pitch": null, "roll": null}, "v": 2.0986241622327517, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "acceleration": 0.0048318186513860995, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020897500501674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.0690808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565725537561534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2279626041404486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0990802792342884, "gear": 1, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.0690808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.0790808, "x": 15.202111824689917, "y": 4.695867911657978, "z": null, "yaw": -0.01408668858859415, "pitch": null, "roll": null}, "v": 2.099125909902564, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "acceleration": 0.004558869624587847, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602472784236747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.0890808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25380877012667535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0401400900379085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09917149859881, "gear": 1, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.0890808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.202111824689917, "y": -0.30413208834202177, "z": null, "yaw": 6.269098618590992, "pitch": null, "roll": null}, "v": 2.099125909902564, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "acceleration": 0.004558869624587847, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602472784236747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.1090808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546747605535079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0401400900379085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0989172361617836, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.1090808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.202111824689917, "y": -0.30413208834202177, "z": null, "yaw": 6.269098618590992, "pitch": null, "roll": null}, "v": 2.099125909902564, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "acceleration": 0.004558869624587847, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602472784236747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.1290808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546747605535079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0401400900379085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098771640270581, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.1290808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.202111824689917, "y": -0.30413208834202177, "z": null, "yaw": 6.269098618590992, "pitch": null, "roll": null}, "v": 2.099125909902564, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "acceleration": 0.004558869624587847, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602472784236747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.1490808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546747605535079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0401400900379085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098553748222009, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.1490808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.202111824689917, "y": -0.30413208834202177, "z": null, "yaw": 6.269098618590992, "pitch": null, "roll": null}, "v": 2.099125909902564, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "acceleration": 0.004558869624587847, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602472784236747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.1690807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546747605535079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0401400900379085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098481251099075, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.1690807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.1890807, "x": 15.432956577504482, "y": 4.692703982342059, "z": null, "yaw": -0.013246948554732994, "pitch": null, "roll": null}, "v": 2.0983364568184073, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894698170105265, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018701157280005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.1890807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2567337463148242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0991627643194117, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0983364568184073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.1890807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.432956577504482, "y": -0.3072960176579409, "z": null, "yaw": 6.269938358624853, "pitch": null, "roll": null}, "v": 2.0983364568184073, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894698170105265, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018701157280005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.2090807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608668235764875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0991627643194117, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098449183614001, "gear": 1, "accelerator_pedal_position": 0.2567337463148242, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.2090807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.432956577504482, "y": -0.3072960176579409, "z": null, "yaw": 6.269938358624853, "pitch": null, "roll": null}, "v": 2.0983364568184073, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894698170105265, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018701157280005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.2290807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608668235764875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0991627643194117, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098480857358115, "gear": 1, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.2290807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.432956577504482, "y": -0.3072960176579409, "z": null, "yaw": 6.269938358624853, "pitch": null, "roll": null}, "v": 2.0983364568184073, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894698170105265, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018701157280005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.2490807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608668235764875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0991627643194117, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098512472868678, "gear": 1, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.2490807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.432956577504482, "y": -0.3072960176579409, "z": null, "yaw": 6.269938358624853, "pitch": null, "roll": null}, "v": 2.0983364568184073, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894698170105265, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018701157280005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.2690806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608668235764875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0991627643194117, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098544030252355, "gear": 1, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.2690806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.432956577504482, "y": -0.3072960176579409, "z": null, "yaw": 6.269938358624853, "pitch": null, "roll": null}, "v": 2.0983364568184073, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894698170105265, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018701157280005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.2890806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608668235764875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0991627643194117, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098575529615617, "gear": 1, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.2890806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.2990806, "x": 15.6637708791411, "y": 4.689734336903604, "z": null, "yaw": -0.012407208520871836, "pitch": null, "roll": null}, "v": 2.0985912575728123, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "acceleration": 0.0015713491930536283, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020646306317565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.3090806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257841451525215, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1647948084021835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098606971064743, "gear": 1, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.3090806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.6637708791411, "y": -0.3102656630963958, "z": null, "yaw": 6.270778098658714, "pitch": null, "roll": null}, "v": 2.0985912575728123, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "acceleration": 0.0015713491930536283, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020646306317565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.3290806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572942574936421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1647948084021835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0988575999815438, "gear": 1, "accelerator_pedal_position": 0.257841451525215, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.3290806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.6637708791411, "y": -0.3102656630963958, "z": null, "yaw": 6.270778098658714, "pitch": null, "roll": null}, "v": 2.0985912575728123, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "acceleration": 0.0015713491930536283, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020646306317565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.3490806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572942574936421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1647948084021835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0990394002766055, "gear": 1, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.3490806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.6637708791411, "y": -0.3102656630963958, "z": null, "yaw": 6.270778098658714, "pitch": null, "roll": null}, "v": 2.0985912575728123, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "acceleration": 0.0015713491930536283, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020646306317565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.3590806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572942574936421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1647948084021835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0991301750294284, "gear": 1, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.3590806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.6637708791411, "y": -0.3102656630963958, "z": null, "yaw": 6.270778098658714, "pitch": null, "roll": null}, "v": 2.0985912575728123, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "acceleration": 0.0015713491930536283, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020646306317565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.3790805} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572942574936421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1647948084021835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0994924398303825, "gear": 1, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.3790805} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.6637708791411, "y": -0.3102656630963958, "z": null, "yaw": 6.270778098658714, "pitch": null, "roll": null}, "v": 2.0985912575728123, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "acceleration": 0.0015713491930536283, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020646306317565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.3990805} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572942574936421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1647948084021835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0995827978533295, "gear": 1, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.3990805} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.4090805, "x": 15.894647508316831, "y": 4.686957802080887, "z": null, "yaw": -0.01156746848701068, "pitch": null, "roll": null}, "v": 2.0995827978533295, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "acceleration": 0.00902749019218041, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028215725124258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.4290805} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2588158048693522, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2383079516814433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099948470206269, "gear": 1, "accelerator_pedal_position": 0.2588158048693522, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.4290805} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 11.894647508316831, "y": -0.31304219791911336, "z": null, "yaw": 6.271617838692576, "pitch": null, "roll": null}, "v": 2.0995827978533295, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "acceleration": 0.00902749019218041, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028215725124258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.4490805} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25834488118572274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2383079516814433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100133505417748, "gear": 1, "accelerator_pedal_position": 0.2588158048693522, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.4490805} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 11.894647508316831, "y": -0.31304219791911336, "z": null, "yaw": 6.271617838692576, "pitch": null, "roll": null}, "v": 2.0995827978533295, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "acceleration": 0.00902749019218041, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028215725124258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.4690804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25834488118572274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2383079516814433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100444226908196, "gear": 1, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.4690804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 11.894647508316831, "y": -0.31304219791911336, "z": null, "yaw": 6.271617838692576, "pitch": null, "roll": null}, "v": 2.0995827978533295, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "acceleration": 0.00902749019218041, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028215725124258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.4890804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25834488118572274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2383079516814433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1007543768885855, "gear": 1, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.4890804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 11.894647508316831, "y": -0.31304219791911336, "z": null, "yaw": 6.271617838692576, "pitch": null, "roll": null}, "v": 2.0995827978533295, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "acceleration": 0.00902749019218041, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028215725124258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.5090804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25834488118572274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2383079516814433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1010639563716347, "gear": 1, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.5090804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.5190804, "x": 16.12566466057755, "y": 4.684373602851725, "z": null, "yaw": -0.010727728453149522, "pitch": null, "roll": null}, "v": 2.10121853249268, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "acceleration": 0.015443387573226108, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016040702923864586, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.5290804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25755060135269126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644981061528523, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1013729663684124, "gear": 1, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.5290804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.125664660577549, "y": -0.3156263971482751, "z": null, "yaw": 6.272457578726437, "pitch": null, "roll": null}, "v": 2.10121853249268, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "acceleration": 0.015443387573226108, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016040702923864586, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.5490804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25780633900291117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644981061528523, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101582168595217, "gear": 1, "accelerator_pedal_position": 0.25755060135269126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.5490804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.125664660577549, "y": -0.3156263971482751, "z": null, "yaw": 6.272457578726437, "pitch": null, "roll": null}, "v": 2.10121853249268, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "acceleration": 0.015443387573226108, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016040702923864586, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.5690804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25780633900291117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644981061528523, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1018229384350375, "gear": 1, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.5690804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.125664660577549, "y": -0.3156263971482751, "z": null, "yaw": 6.272457578726437, "pitch": null, "roll": null}, "v": 2.10121853249268, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "acceleration": 0.015443387573226108, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016040702923864586, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.5890803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25780633900291117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644981061528523, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1020632652925326, "gear": 1, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.5890803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.125664660577549, "y": -0.3156263971482751, "z": null, "yaw": 6.272457578726437, "pitch": null, "roll": null}, "v": 2.10121853249268, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "acceleration": 0.015443387573226108, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016040702923864586, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.6090803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25780633900291117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644981061528523, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102303149959635, "gear": 1, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.6090803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.6290803, "x": 16.356853206070472, "y": 4.681981644211641, "z": null, "yaw": -0.009887988419288365, "pitch": null, "roll": null}, "v": 2.1025425932269473, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "acceleration": 0.011955635543512366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016050810803917567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.6290803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2586503480495873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1928159931384612, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1025425932269473, "gear": 1, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.6290803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.356853206070472, "y": -0.31801835578835913, "z": null, "yaw": 6.273297318760298, "pitch": null, "roll": null}, "v": 2.1025425932269473, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "acceleration": 0.011955635543512366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016050810803917567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.6490803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25839268822292316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1928159931384612, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1028870484556945, "gear": 1, "accelerator_pedal_position": 0.2586503480495873, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.6490803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.356853206070472, "y": -0.31801835578835913, "z": null, "yaw": 6.273297318760298, "pitch": null, "roll": null}, "v": 2.1025425932269473, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "acceleration": 0.011955635543512366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016050810803917567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.6690803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25839268822292316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1928159931384612, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1031986771397433, "gear": 1, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.6690803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.356853206070472, "y": -0.31801835578835913, "z": null, "yaw": 6.273297318760298, "pitch": null, "roll": null}, "v": 2.1025425932269473, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "acceleration": 0.011955635543512366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016050810803917567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.6890802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25839268822292316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1928159931384612, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1036650451305223, "gear": 1, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.6890802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.356853206070472, "y": -0.31801835578835913, "z": null, "yaw": 6.273297318760298, "pitch": null, "roll": null}, "v": 2.1025425932269473, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "acceleration": 0.011955635543512366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016050810803917567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.6990802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25839268822292316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1928159931384612, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103820214959679, "gear": 1, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.6990802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.356853206070472, "y": -0.31801835578835913, "z": null, "yaw": 6.273297318760298, "pitch": null, "roll": null}, "v": 2.1025425932269473, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "acceleration": 0.011955635543512366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016050810803917567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.7290802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25839268822292316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1928159931384612, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1041301261275596, "gear": 1, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.7290802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.7390802, "x": 16.588211153110645, "y": 4.679782235821813, "z": null, "yaw": -0.009048248385427208, "pitch": null, "roll": null}, "v": 2.104284867719661, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "acceleration": 0.015459909962147078, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01606411132793126, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.7490802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25708464477874277, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.165179340273655, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1044394668192825, "gear": 1, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.7490802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 12.588211153110645, "y": -0.3202177641781869, "z": null, "yaw": 6.274137058794159, "pitch": null, "roll": null}, "v": 2.104284867719661, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "acceleration": 0.015459909962147078, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01606411132793126, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.7690802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575014290386362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.165179340273655, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1045848079031257, "gear": 1, "accelerator_pedal_position": 0.25708464477874277, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.7690802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 12.588211153110645, "y": -0.3202177641781869, "z": null, "yaw": 6.274137058794159, "pitch": null, "roll": null}, "v": 2.104284867719661, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "acceleration": 0.015459909962147078, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01606411132793126, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.7890801} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575014290386362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.165179340273655, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104781955461264, "gear": 1, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.7890801} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 12.588211153110645, "y": -0.3202177641781869, "z": null, "yaw": 6.274137058794159, "pitch": null, "roll": null}, "v": 2.104284867719661, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "acceleration": 0.015459909962147078, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01606411132793126, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.8090801} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575014290386362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.165179340273655, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1049787400618922, "gear": 1, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.8090801} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 12.588211153110645, "y": -0.3202177641781869, "z": null, "yaw": 6.274137058794159, "pitch": null, "roll": null}, "v": 2.104284867719661, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "acceleration": 0.015459909962147078, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01606411132793126, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.82908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575014290386362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.165179340273655, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1051751623577495, "gear": 1, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.82908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.84908, "x": 16.81972916386827, "y": 4.67777573161186, "z": null, "yaw": -0.00820850835156605, "pitch": null, "roll": null}, "v": 2.105371223000458, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "acceleration": 0.009789490475068885, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016072404564479278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.84908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25424480020580936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1332937022274265, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105371223000458, "gear": 1, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.84908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 12.81972916386827, "y": -0.32222426838813956, "z": null, "yaw": 6.27497679882802, "pitch": null, "roll": null}, "v": 2.105371223000458, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "acceleration": 0.009789490475068885, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016072404564479278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.86908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25526749986586617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1332937022274265, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1051600315110734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.86908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 12.81972916386827, "y": -0.32222426838813956, "z": null, "yaw": 6.27497679882802, "pitch": null, "roll": null}, "v": 2.105371223000458, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "acceleration": 0.009789490475068885, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016072404564479278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.88908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25526749986586617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1332937022274265, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105077007462487, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.88908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 12.81972916386827, "y": -0.32222426838813956, "z": null, "yaw": 6.27497679882802, "pitch": null, "roll": null}, "v": 2.105371223000458, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "acceleration": 0.009789490475068885, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016072404564479278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.90908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25526749986586617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1332937022274265, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1049941362770177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.90908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 12.81972916386827, "y": -0.32222426838813956, "z": null, "yaw": 6.27497679882802, "pitch": null, "roll": null}, "v": 2.105371223000458, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "acceleration": 0.009789490475068885, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016072404564479278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.92908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25526749986586617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1332937022274265, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1048288513591853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.92908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 12.81972916386827, "y": -0.32222426838813956, "z": null, "yaw": 6.27497679882802, "pitch": null, "roll": null}, "v": 2.105371223000458, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "acceleration": 0.009789490475068885, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016072404564479278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.94908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25526749986586617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1332937022274265, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104787625225771, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.94908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.95908, "x": 17.051277916417405, "y": 4.675963402734362, "z": null, "yaw": -0.007368768317704893, "pitch": null, "roll": null}, "v": 2.104787625225771, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.349540690734324, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016067949378887673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.97908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25677733422837073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.191766330514595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104811742407016, "gear": 1, "accelerator_pedal_position": 0.25677733422837073, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.97908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.051277916417405, "y": -0.32403659726563827, "z": null, "yaw": 6.275816538861881, "pitch": null, "roll": null}, "v": 2.104787625225771, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.349540690734324, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016067949378887673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.99908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563028231648702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.191766330514595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104811742407016, "gear": 1, "accelerator_pedal_position": 0.25677733422837073, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.99908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.051277916417405, "y": -0.32403659726563827, "z": null, "yaw": 6.275816538861881, "pitch": null, "roll": null}, "v": 2.104787625225771, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.349540690734324, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016067949378887673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.01908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563028231648702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.191766330514595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104858715425812, "gear": 1, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.01908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.051277916417405, "y": -0.32403659726563827, "z": null, "yaw": 6.275816538861881, "pitch": null, "roll": null}, "v": 2.104787625225771, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.349540690734324, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016067949378887673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.03908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563028231648702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.191766330514595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104905601963025, "gear": 1, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.03908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.051277916417405, "y": -0.32403659726563827, "z": null, "yaw": 6.275816538861881, "pitch": null, "roll": null}, "v": 2.104787625225771, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.349540690734324, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016067949378887673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.05908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563028231648702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.191766330514595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104952402176995, "gear": 1, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.05908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.0690799, "x": 17.28280398584204, "y": 4.6743456898181925, "z": null, "yaw": -0.006529028283843736, "pitch": null, "roll": null}, "v": 2.104975769962168, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "acceleration": 0.0023346263610519724, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016069385675863242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.0790799} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25378760901170117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1499019082593922, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1048652401029653, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.0790799} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.28280398584204, "y": -0.32565431018180746, "z": null, "yaw": 6.276656278895742, "pitch": null, "roll": null}, "v": 2.104975769962168, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "acceleration": 0.0023346263610519724, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016069385675863242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.0990798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2545744803347327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1499019082593922, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104731487278246, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.0990798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.28280398584204, "y": -0.32565431018180746, "z": null, "yaw": 6.276656278895742, "pitch": null, "roll": null}, "v": 2.104975769962168, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "acceleration": 0.0023346263610519724, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016069385675863242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.1190798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2545744803347327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1499019082593922, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104562664679474, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.1190798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.28280398584204, "y": -0.32565431018180746, "z": null, "yaw": 6.276656278895742, "pitch": null, "roll": null}, "v": 2.104975769962168, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "acceleration": 0.0023346263610519724, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016069385675863242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.1390798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2545744803347327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1499019082593922, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.10439415288207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.1390798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.28280398584204, "y": -0.32565431018180746, "z": null, "yaw": 6.276656278895742, "pitch": null, "roll": null}, "v": 2.104975769962168, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "acceleration": 0.0023346263610519724, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016069385675863242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.1590798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2545744803347327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1499019082593922, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1042259513024977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.1590798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.1790798, "x": 17.51430292254529, "y": 4.672922564474975, "z": null, "yaw": -0.005689288249982579, "pitch": null, "roll": null}, "v": 2.104058059358356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34947350613942635, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062379872831246, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.1790798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25628814684213386, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.216906073013514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104058059358356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.1790798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 13.51430292254529, "y": -0.327077435525025, "z": null, "yaw": 6.277496018929604, "pitch": null, "roll": null}, "v": 2.104058059358356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34947350613942635, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062379872831246, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.1990798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574840009068744, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.216906073013514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104104586159704, "gear": 1, "accelerator_pedal_position": 0.25628814684213386, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.1990798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 13.51430292254529, "y": -0.327077435525025, "z": null, "yaw": 6.277496018929604, "pitch": null, "roll": null}, "v": 2.104058059358356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34947350613942635, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062379872831246, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.2290797} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574840009068744, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.216906073013514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1040626325582203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.2290797} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 13.51430292254529, "y": -0.327077435525025, "z": null, "yaw": 6.277496018929604, "pitch": null, "roll": null}, "v": 2.104058059358356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34947350613942635, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062379872831246, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.2390797} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574840009068744, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.216906073013514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1040521682914366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.2390797} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 13.51430292254529, "y": -0.327077435525025, "z": null, "yaw": 6.277496018929604, "pitch": null, "roll": null}, "v": 2.104058059358356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34947350613942635, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062379872831246, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.2690797} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574840009068744, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.216906073013514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104031268655825, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.2690797} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.2890797, "x": 17.745746689569607, "y": 4.6716941442061, "z": null, "yaw": -0.0048495482161214215, "pitch": null, "roll": null}, "v": 2.1040104074915673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494691183229067, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062016098465512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.2890797} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553113747691821, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.227349110988929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1039349817132167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.2890797} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 13.745746689569607, "y": -0.32830585579390004, "z": null, "yaw": 6.278335758963465, "pitch": null, "roll": null}, "v": 2.1040104074915673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494691183229067, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062016098465512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.3090796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554477258807253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.227349110988929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1039349817132167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.3090796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 13.745746689569607, "y": -0.32830585579390004, "z": null, "yaw": 6.278335758963465, "pitch": null, "roll": null}, "v": 2.1040104074915673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494691183229067, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062016098465512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.3290796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554477258807253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.227349110988929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103789555450413, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.3290796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 13.745746689569607, "y": -0.32830585579390004, "z": null, "yaw": 6.278335758963465, "pitch": null, "roll": null}, "v": 2.1040104074915673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494691183229067, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062016098465512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.3590796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554477258807253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.227349110988929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103789555450413, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.3590796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 13.745746689569607, "y": -0.32830585579390004, "z": null, "yaw": 6.278335758963465, "pitch": null, "roll": null}, "v": 2.1040104074915673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494691183229067, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062016098465512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.3890796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554477258807253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.227349110988929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103702620666414, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.3890796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.3990796, "x": 17.977167884735906, "y": 4.670660180023287, "z": null, "yaw": -0.004009808182260264, "pitch": null, "roll": null}, "v": 2.1036736957520064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494381149695894, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605944564094205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.4090796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2560561745725128, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2237390571578228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103644797469856, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.4090796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 13.977167884735906, "y": -0.32933981997671324, "z": null, "yaw": 6.279175498997326, "pitch": null, "roll": null}, "v": 2.1036736957520064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494381149695894, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605944564094205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.4290795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25586448406298123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2237390571578228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1036631017766236, "gear": 1, "accelerator_pedal_position": 0.2560561745725128, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.4290795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 13.977167884735906, "y": -0.32933981997671324, "z": null, "yaw": 6.279175498997326, "pitch": null, "roll": null}, "v": 2.1036736957520064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494381149695894, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605944564094205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.4490795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25586448406298123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2237390571578228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1036574221094955, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.4490795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 13.977167884735906, "y": -0.32933981997671324, "z": null, "yaw": 6.279175498997326, "pitch": null, "roll": null}, "v": 2.1036736957520064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494381149695894, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605944564094205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.4690795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25586448406298123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2237390571578228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103651752896452, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.4690795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 13.977167884735906, "y": -0.32933981997671324, "z": null, "yaw": 6.279175498997326, "pitch": null, "roll": null}, "v": 2.1036736957520064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494381149695894, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605944564094205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.4890795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25586448406298123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2237390571578228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103646094118239, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.4890795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.5090795, "x": 18.208568333558958, "y": 4.669820630336017, "z": null, "yaw": -0.003170068148399107, "pitch": null, "roll": null}, "v": 2.1036404457556364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34943505353797155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605919181045953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.5090795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564481292951369, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.175716579196709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1036404457556364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.5090795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.208568333558958, "y": -0.3301793696639832, "z": null, "yaw": 6.280015239031187, "pitch": null, "roll": null}, "v": 2.1036404457556364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34943505353797155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605919181045953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.5290794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562655869688233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.175716579196709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103707729857208, "gear": 1, "accelerator_pedal_position": 0.2564481292951369, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.5290794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.208568333558958, "y": -0.3301793696639832, "z": null, "yaw": 6.280015239031187, "pitch": null, "roll": null}, "v": 2.1036404457556364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34943505353797155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605919181045953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.5490794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562655869688233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.175716579196709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1037520828276564, "gear": 1, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.5490794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.208568333558958, "y": -0.3301793696639832, "z": null, "yaw": 6.280015239031187, "pitch": null, "roll": null}, "v": 2.1036404457556364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34943505353797155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605919181045953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.5690794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562655869688233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.175716579196709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103796354159871, "gear": 1, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.5690794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.208568333558958, "y": -0.3301793696639832, "z": null, "yaw": 6.280015239031187, "pitch": null, "roll": null}, "v": 2.1036404457556364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34943505353797155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605919181045953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.5890794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562655869688233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.175716579196709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1038405440033356, "gear": 1, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.5890794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.208568333558958, "y": -0.3301793696639832, "z": null, "yaw": 6.280015239031187, "pitch": null, "roll": null}, "v": 2.1036404457556364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34943505353797155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605919181045953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.6090794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562655869688233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.175716579196709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1038846525072628, "gear": 1, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.6090794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.6190794, "x": 18.43998223845049, "y": 4.66917536348668, "z": null, "yaw": -0.00233032811453795, "pitch": null, "roll": null}, "v": 2.103906676303455, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "acceleration": 0.002200351714030213, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061224214543528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.6290793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2568546890621573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.127978206109691, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103928679820595, "gear": 1, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.6290793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 14.43998223845049, "y": -0.33082463651332006, "z": null, "yaw": 6.280854979065048, "pitch": null, "roll": null}, "v": 2.103906676303455, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "acceleration": 0.002200351714030213, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061224214543528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.6490793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25667182020324947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.127978206109691, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104046229951075, "gear": 1, "accelerator_pedal_position": 0.2568546890621573, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.6490793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 14.43998223845049, "y": -0.33082463651332006, "z": null, "yaw": 6.280854979065048, "pitch": null, "roll": null}, "v": 2.103906676303455, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "acceleration": 0.002200351714030213, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061224214543528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.6690793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25667182020324947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.127978206109691, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1041407156170773, "gear": 1, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.6690793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 14.43998223845049, "y": -0.33082463651332006, "z": null, "yaw": 6.280854979065048, "pitch": null, "roll": null}, "v": 2.103906676303455, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "acceleration": 0.002200351714030213, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061224214543528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.6890793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25667182020324947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.127978206109691, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104235027353968, "gear": 1, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.6890793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 14.43998223845049, "y": -0.33082463651332006, "z": null, "yaw": 6.280854979065048, "pitch": null, "roll": null}, "v": 2.103906676303455, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "acceleration": 0.002200351714030213, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061224214543528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.7090793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25667182020324947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.127978206109691, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1043291654783594, "gear": 1, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.7090793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.7290792, "x": 18.671436928797736, "y": 4.668724347852609, "z": null, "yaw": -0.0014905880806767927, "pitch": null, "roll": null}, "v": 2.1044231303063, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "acceleration": 0.004691752641312441, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016065166824560228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.7290792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25834135963645427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.188473534275868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1044231303063, "gear": 1, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.7290792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.671436928797736, "y": -0.33127565214739096, "z": null, "yaw": 6.281694719098909, "pitch": null, "roll": null}, "v": 2.1044231303063, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "acceleration": 0.004691752641312441, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016065166824560228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.7490792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578220060624571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.188473534275868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1047255184895355, "gear": 1, "accelerator_pedal_position": 0.25834135963645427, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.7490792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.671436928797736, "y": -0.33127565214739096, "z": null, "yaw": 6.281694719098909, "pitch": null, "roll": null}, "v": 2.1044231303063, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "acceleration": 0.004691752641312441, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016065166824560228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.7690792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578220060624571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.188473534275868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1049624606701776, "gear": 1, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.7690792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.671436928797736, "y": -0.33127565214739096, "z": null, "yaw": 6.281694719098909, "pitch": null, "roll": null}, "v": 2.1044231303063, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "acceleration": 0.004691752641312441, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016065166824560228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.7890792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578220060624571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.188473534275868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105198966613473, "gear": 1, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.7890792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.671436928797736, "y": -0.33127565214739096, "z": null, "yaw": 6.281694719098909, "pitch": null, "roll": null}, "v": 2.1044231303063, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "acceleration": 0.004691752641312441, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016065166824560228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.8090792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578220060624571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.188473534275868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1054350371002206, "gear": 1, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.8090792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.671436928797736, "y": -0.33127565214739096, "z": null, "yaw": 6.281694719098909, "pitch": null, "roll": null}, "v": 2.1044231303063, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "acceleration": 0.004691752641312441, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016065166824560228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.8290792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578220060624571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.188473534275868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1056706729099046, "gear": 1, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.8290792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.8390791, "x": 18.902994629275767, "y": 4.668467586454433, "z": null, "yaw": -0.000650848046815636, "pitch": null, "roll": null}, "v": 2.105788328054078, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "acceleration": 0.011754676661964891, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016075588744587012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.8490791} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2583602179808584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094912395586726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1059058748206976, "gear": 1, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.8490791} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 14.902994629275767, "y": -0.33153241354556684, "z": null, "yaw": 6.282534459132771, "pitch": null, "roll": null}, "v": 2.105788328054078, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "acceleration": 0.011754676661964891, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016075588744587012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.869079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581983135301749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094912395586726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1062078891114404, "gear": 1, "accelerator_pedal_position": 0.2583602179808584, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.869079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 14.902994629275767, "y": -0.33153241354556684, "z": null, "yaw": 6.282534459132771, "pitch": null, "roll": null}, "v": 2.105788328054078, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "acceleration": 0.011754676661964891, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016075588744587012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.889079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581983135301749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094912395586726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106489118477401, "gear": 1, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.889079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 14.902994629275767, "y": -0.33153241354556684, "z": null, "yaw": 6.282534459132771, "pitch": null, "roll": null}, "v": 2.105788328054078, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "acceleration": 0.011754676661964891, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016075588744587012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.909079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581983135301749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094912395586726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106769829897966, "gear": 1, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.909079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 14.902994629275767, "y": -0.33153241354556684, "z": null, "yaw": 6.282534459132771, "pitch": null, "roll": null}, "v": 2.105788328054078, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "acceleration": 0.011754676661964891, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016075588744587012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.929079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581983135301749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094912395586726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.10705002429554, "gear": 1, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.929079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.949079, "x": 19.134708074566767, "y": 4.668405233105053, "z": null, "yaw": 0.00018889198704552008, "pitch": null, "roll": null}, "v": 2.1073297025910027, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "acceleration": 0.013964589679820172, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016087355598276374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.949079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596708166654187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1518318584506897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1073297025910027, "gear": 1, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.949079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.134708074566767, "y": -0.3315947668949466, "z": null, "yaw": 0.00018889198704552008, "pitch": null, "roll": null}, "v": 2.1073297025910027, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "acceleration": 0.013964589679820172, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016087355598276374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.969079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592177595713767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1518318584506897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107792843788357, "gear": 1, "accelerator_pedal_position": 0.2596708166654187, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.969079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.134708074566767, "y": -0.3315947668949466, "z": null, "yaw": 0.00018889198704552008, "pitch": null, "roll": null}, "v": 2.1073297025910027, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "acceleration": 0.013964589679820172, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016087355598276374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.989079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592177595713767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1518318584506897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108198525736394, "gear": 1, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.989079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.134708074566767, "y": -0.3315947668949466, "z": null, "yaw": 0.00018889198704552008, "pitch": null, "roll": null}, "v": 2.1073297025910027, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "acceleration": 0.013964589679820172, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016087355598276374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.009079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592177595713767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1518318584506897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1086034602602943, "gear": 1, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.009079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.134708074566767, "y": -0.3315947668949466, "z": null, "yaw": 0.00018889198704552008, "pitch": null, "roll": null}, "v": 2.1073297025910027, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "acceleration": 0.013964589679820172, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016087355598276374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.029079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592177595713767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1518318584506897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.109007648671545, "gear": 1, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.029079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.134708074566767, "y": -0.3315947668949466, "z": null, "yaw": 0.00018889198704552008, "pitch": null, "roll": null}, "v": 2.1073297025910027, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "acceleration": 0.013964589679820172, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016087355598276374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.049079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592177595713767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1518318584506897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1094110922795792, "gear": 1, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.049079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.059079, "x": 19.3666311963349, "y": 4.668537583902912, "z": null, "yaw": 0.0010286320209066762, "pitch": null, "roll": null}, "v": 2.1096125351910273, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "acceleration": 0.020125720075201914, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104782743047684, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.069079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601446398849194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0525976065196636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1098137923917792, "gear": 1, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.069079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 15.3666311963349, "y": -0.3314624160970876, "z": null, "yaw": 0.0010286320209066762, "pitch": null, "roll": null}, "v": 2.1096125351910273, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "acceleration": 0.020125720075201914, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104782743047684, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.089079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259865509972032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0525976065196636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110331556940684, "gear": 1, "accelerator_pedal_position": 0.2601446398849194, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.089079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 15.3666311963349, "y": -0.3314624160970876, "z": null, "yaw": 0.0010286320209066762, "pitch": null, "roll": null}, "v": 2.1096125351910273, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "acceleration": 0.020125720075201914, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104782743047684, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.109079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259865509972032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0525976065196636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1108134919778747, "gear": 1, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.109079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 15.3666311963349, "y": -0.3314624160970876, "z": null, "yaw": 0.0010286320209066762, "pitch": null, "roll": null}, "v": 2.1096125351910273, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "acceleration": 0.020125720075201914, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104782743047684, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.1290789} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259865509972032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0525976065196636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111294538603082, "gear": 1, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.1290789} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 15.3666311963349, "y": -0.3314624160970876, "z": null, "yaw": 0.0010286320209066762, "pitch": null, "roll": null}, "v": 2.1096125351910273, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "acceleration": 0.020125720075201914, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104782743047684, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.1490788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259865509972032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0525976065196636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1117746983615087, "gear": 1, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.1490788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.1690788, "x": 19.598819852072186, "y": 4.668865067561588, "z": null, "yaw": 0.0018683720547678334, "pitch": null, "roll": null}, "v": 2.11225397279602, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "acceleration": 0.023930570229473258, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01612494747853731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.1690788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609872063633647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0279960980718108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11225397279602, "gear": 1, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.1690788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.598819852072186, "y": -0.3311349324384123, "z": null, "yaw": 0.0018683720547678334, "pitch": null, "roll": null}, "v": 2.11225397279602, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "acceleration": 0.023930570229473258, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01612494747853731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.1890788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26064885551172434, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0279960980718108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112872510822859, "gear": 1, "accelerator_pedal_position": 0.2609872063633647, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.1890788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.598819852072186, "y": -0.3311349324384123, "z": null, "yaw": 0.0018683720547678334, "pitch": null, "roll": null}, "v": 2.11225397279602, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "acceleration": 0.023930570229473258, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01612494747853731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.2090788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26064885551172434, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0279960980718108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1134476337740034, "gear": 1, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.2090788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.598819852072186, "y": -0.3311349324384123, "z": null, "yaw": 0.0018683720547678334, "pitch": null, "roll": null}, "v": 2.11225397279602, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "acceleration": 0.023930570229473258, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01612494747853731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.2290788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26064885551172434, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0279960980718108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1140216959279963, "gear": 1, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.2290788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.598819852072186, "y": -0.3311349324384123, "z": null, "yaw": 0.0018683720547678334, "pitch": null, "roll": null}, "v": 2.11225397279602, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "acceleration": 0.023930570229473258, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01612494747853731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.2490788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26064885551172434, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0279960980718108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.114594699109688, "gear": 1, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.2490788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.598819852072186, "y": -0.3311349324384123, "z": null, "yaw": 0.0018683720547678334, "pitch": null, "roll": null}, "v": 2.11225397279602, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "acceleration": 0.023930570229473258, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01612494747853731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.2690787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26064885551172434, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0279960980718108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1151666451412923, "gear": 1, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.2690787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.2790787, "x": 19.83132930344762, "y": 4.669388255796627, "z": null, "yaw": 0.0027081120886289904, "pitch": null, "roll": null}, "v": 2.1154522222945324, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "acceleration": 0.028531354785441665, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01614936291619347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.2890787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2618136974141813, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0782560407773343, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1157375358423867, "gear": 1, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.2890787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 15.831329303447621, "y": -0.3306117442033729, "z": null, "yaw": 0.0027081120886289904, "pitch": null, "roll": null}, "v": 2.1154522222945324, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "acceleration": 0.028531354785441665, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01614936291619347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.3090787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146444034402816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0782560407773343, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1164529110554873, "gear": 1, "accelerator_pedal_position": 0.2618136974141813, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.3090787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 15.831329303447621, "y": -0.3306117442033729, "z": null, "yaw": 0.0027081120886289904, "pitch": null, "roll": null}, "v": 2.1154522222945324, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "acceleration": 0.028531354785441665, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01614936291619347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.3290787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146444034402816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0782560407773343, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117123328953032, "gear": 1, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.3290787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 15.831329303447621, "y": -0.3306117442033729, "z": null, "yaw": 0.0027081120886289904, "pitch": null, "roll": null}, "v": 2.1154522222945324, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "acceleration": 0.028531354785441665, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01614936291619347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.3490787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146444034402816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0782560407773343, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1177925093063297, "gear": 1, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.3490787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 15.831329303447621, "y": -0.3306117442033729, "z": null, "yaw": 0.0027081120886289904, "pitch": null, "roll": null}, "v": 2.1154522222945324, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "acceleration": 0.028531354785441665, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01614936291619347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.3690786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146444034402816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0782560407773343, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118460454220762, "gear": 1, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.3690786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.3890786, "x": 20.064210997905523, "y": 4.670107847043696, "z": null, "yaw": 0.0035478521224901476, "pitch": null, "roll": null}, "v": 2.1191271657988153, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "acceleration": 0.03328939441196993, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016177417436036415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.3890786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625168046955354, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9157615482225673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1191271657988153, "gear": 1, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.3890786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.064210997905523, "y": -0.3298921529563037, "z": null, "yaw": 0.0035478521224901476, "pitch": null, "roll": null}, "v": 2.1191271657988153, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "acceleration": 0.03328939441196993, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016177417436036415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.4090786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26220490890996306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9157615482225673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119924130916648, "gear": 1, "accelerator_pedal_position": 0.2625168046955354, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.4090786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.064210997905523, "y": -0.3298921529563037, "z": null, "yaw": 0.0035478521224901476, "pitch": null, "roll": null}, "v": 2.1191271657988153, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "acceleration": 0.03328939441196993, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016177417436036415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.4290786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26220490890996306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9157615482225673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1206806550510247, "gear": 1, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.4290786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.064210997905523, "y": -0.3298921529563037, "z": null, "yaw": 0.0035478521224901476, "pitch": null, "roll": null}, "v": 2.1191271657988153, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "acceleration": 0.03328939441196993, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016177417436036415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.4490786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26220490890996306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9157615482225673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1214357816261273, "gear": 1, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.4490786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.064210997905523, "y": -0.3298921529563037, "z": null, "yaw": 0.0035478521224901476, "pitch": null, "roll": null}, "v": 2.1191271657988153, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "acceleration": 0.03328939441196993, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016177417436036415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.4690785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26220490890996306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9157615482225673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1221895129957455, "gear": 1, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.4690785} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.064210997905523, "y": -0.3298921529563037, "z": null, "yaw": 0.0035478521224901476, "pitch": null, "roll": null}, "v": 2.1191271657988153, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "acceleration": 0.03328939441196993, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016177417436036415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.4890785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26220490890996306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9157615482225673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1229418515105833, "gear": 1, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.4890785} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.4990785, "x": 20.2975248353152, "y": 4.671024702565715, "z": null, "yaw": 0.004387592156351304, "pitch": null, "roll": null}, "v": 2.123317499181211, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "acceleration": 0.037530033704916976, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01620940644236753, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.5090785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26320729959271955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9506380807604925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.12369279951826, "gear": 1, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.5090785} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 16.2975248353152, "y": -0.328975297434285, "z": null, "yaw": 0.004387592156351304, "pitch": null, "roll": null}, "v": 2.123317499181211, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "acceleration": 0.037530033704916976, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01620940644236753, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.5290785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26291341677388086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9506380807604925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124986026258664, "gear": 1, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.5290785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26291341677388086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9506380807604925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124986026258664, "gear": 1, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.5390785} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 16.2975248353152, "y": -0.328975297434285, "z": null, "yaw": 0.004387592156351304, "pitch": null, "roll": null}, "v": 2.123317499181211, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "acceleration": 0.037530033704916976, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01620940644236753, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.5690784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26291341677388086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9506380807604925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1262389833965774, "gear": 1, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.5690784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 16.2975248353152, "y": -0.328975297434285, "z": null, "yaw": 0.004387592156351304, "pitch": null, "roll": null}, "v": 2.123317499181211, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "acceleration": 0.037530033704916976, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01620940644236753, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.5890784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26291341677388086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9506380807604925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127488466020853, "gear": 1, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.5890784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.6090784, "x": 20.531315927187865, "y": 4.6721397642586515, "z": null, "yaw": 0.0052273321902124616, "pitch": null, "roll": null}, "v": 2.127904189618905, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "acceleration": 0.04153388295383309, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.0162444212385808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.6090784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26374389775248497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9572684270061307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127904189618905, "gear": 1, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.6090784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.531315927187865, "y": -0.3278602357413485, "z": null, "yaw": 0.0052273321902124616, "pitch": null, "roll": null}, "v": 2.127904189618905, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "acceleration": 0.04153388295383309, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.0162444212385808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.6290784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263505588535452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9572684270061307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1288382449064835, "gear": 1, "accelerator_pedal_position": 0.26374389775248497, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.6290784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.531315927187865, "y": -0.3278602357413485, "z": null, "yaw": 0.0052273321902124616, "pitch": null, "roll": null}, "v": 2.127904189618905, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "acceleration": 0.04153388295383309, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.0162444212385808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.6490784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263505588535452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9572684270061307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1297407967833837, "gear": 1, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.6490784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.531315927187865, "y": -0.3278602357413485, "z": null, "yaw": 0.0052273321902124616, "pitch": null, "roll": null}, "v": 2.127904189618905, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "acceleration": 0.04153388295383309, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.0162444212385808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.6690784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263505588535452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9572684270061307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1306416780830375, "gear": 1, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.6690784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.531315927187865, "y": -0.3278602357413485, "z": null, "yaw": 0.0052273321902124616, "pitch": null, "roll": null}, "v": 2.127904189618905, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "acceleration": 0.04153388295383309, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.0162444212385808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.6890783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263505588535452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9572684270061307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1315408915731138, "gear": 1, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.6890783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.531315927187865, "y": -0.3278602357413485, "z": null, "yaw": 0.0052273321902124616, "pitch": null, "roll": null}, "v": 2.127904189618905, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "acceleration": 0.04153388295383309, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.0162444212385808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.7090783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263505588535452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9572684270061307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.132438440017958, "gear": 1, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.7090783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.7190783, "x": 20.76563261632459, "y": 4.673454105882934, "z": null, "yaw": 0.006067072224073619, "pitch": null, "roll": null}, "v": 2.1328865907113683, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "acceleration": 0.04477354672264272, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016282456890054392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.7290783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26459284138618827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9603808717669758, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133334326178595, "gear": 1, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.7290783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 16.76563261632459, "y": -0.326545894117066, "z": null, "yaw": 0.006067072224073619, "pitch": null, "roll": null}, "v": 2.1328865907113683, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "acceleration": 0.04477354672264272, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016282456890054392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.7490783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26427614514974146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9603808717669758, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1343643964424497, "gear": 1, "accelerator_pedal_position": 0.26459284138618827, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.7490783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 16.76563261632459, "y": -0.326545894117066, "z": null, "yaw": 0.006067072224073619, "pitch": null, "roll": null}, "v": 2.1328865907113683, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "acceleration": 0.04477354672264272, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016282456890054392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.7690783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26427614514974146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9603808717669758, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1353529895274166, "gear": 1, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.7690783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 16.76563261632459, "y": -0.326545894117066, "z": null, "yaw": 0.006067072224073619, "pitch": null, "roll": null}, "v": 2.1328865907113683, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "acceleration": 0.04477354672264272, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016282456890054392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.7890782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26427614514974146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9603808717669758, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1363397505685606, "gear": 1, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.7890782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 16.76563261632459, "y": -0.326545894117066, "z": null, "yaw": 0.006067072224073619, "pitch": null, "roll": null}, "v": 2.1328865907113683, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "acceleration": 0.04477354672264272, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016282456890054392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.8090782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26427614514974146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9603808717669758, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1373246825716965, "gear": 1, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.8090782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.8290782, "x": 21.000515792780938, "y": 4.674968876592769, "z": null, "yaw": 0.006906812257934776, "pitch": null, "roll": null}, "v": 2.1383077885392305, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "acceleration": 0.049086915773647155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01632384231594109, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.8290782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654521715359147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9326463875378538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1383077885392305, "gear": 1, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.8290782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.000515792780938, "y": -0.32503112340723117, "z": null, "yaw": 0.006906812257934776, "pitch": null, "roll": null}, "v": 2.1383077885392305, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "acceleration": 0.049086915773647155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01632384231594109, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.8490782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2651097935551703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9326463875378538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.139436006576022, "gear": 1, "accelerator_pedal_position": 0.2654521715359147, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.8490782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.000515792780938, "y": -0.32503112340723117, "z": null, "yaw": 0.006906812257934776, "pitch": null, "roll": null}, "v": 2.1383077885392305, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "acceleration": 0.049086915773647155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01632384231594109, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.8690782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2651097935551703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9326463875378538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1405193546035366, "gear": 1, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.8690782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.000515792780938, "y": -0.32503112340723117, "z": null, "yaw": 0.006906812257934776, "pitch": null, "roll": null}, "v": 2.1383077885392305, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "acceleration": 0.049086915773647155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01632384231594109, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.8890781} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2651097935551703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9326463875378538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1416006927625366, "gear": 1, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.8890781} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.000515792780938, "y": -0.32503112340723117, "z": null, "yaw": 0.006906812257934776, "pitch": null, "roll": null}, "v": 2.1383077885392305, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "acceleration": 0.049086915773647155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01632384231594109, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.9090781} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2651097935551703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9326463875378538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.143218938630687, "gear": 1, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.9090781} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.000515792780938, "y": -0.32503112340723117, "z": null, "yaw": 0.006906812257934776, "pitch": null, "roll": null}, "v": 2.1383077885392305, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "acceleration": 0.049086915773647155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01632384231594109, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.929078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2651097935551703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9326463875378538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1442952663789723, "gear": 1, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.929078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.939078, "x": 21.23602524136425, "y": 4.676685466127454, "z": null, "yaw": 0.007746552291795933, "pitch": null, "roll": null}, "v": 2.1442952663789723, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "acceleration": 0.053741424506712876, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016369550723612798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.949078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2656776351041094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8959803662682757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1448326806240394, "gear": 1, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.949078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 17.23602524136425, "y": -0.32331453387254605, "z": null, "yaw": 0.007746552291795933, "pitch": null, "roll": null}, "v": 2.1442952663789723, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "acceleration": 0.053741424506712876, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016369550723612798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.969078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655279742119838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8959803662682757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.145976959107878, "gear": 1, "accelerator_pedal_position": 0.2656776351041094, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.969078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 17.23602524136425, "y": -0.32331453387254605, "z": null, "yaw": 0.007746552291795933, "pitch": null, "roll": null}, "v": 2.1442952663789723, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "acceleration": 0.053741424506712876, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016369550723612798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.989078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655279742119838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8959803662682757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.147100413275037, "gear": 1, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.989078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 17.23602524136425, "y": -0.32331453387254605, "z": null, "yaw": 0.007746552291795933, "pitch": null, "roll": null}, "v": 2.1442952663789723, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "acceleration": 0.053741424506712876, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016369550723612798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.009078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655279742119838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8959803662682757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1482217802170864, "gear": 1, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.009078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 17.23602524136425, "y": -0.32331453387254605, "z": null, "yaw": 0.007746552291795933, "pitch": null, "roll": null}, "v": 2.1442952663789723, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "acceleration": 0.053741424506712876, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016369550723612798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.029078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655279742119838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8959803662682757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.151016088102442, "gear": 1, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.029078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.049078, "x": 21.47219798369533, "y": 4.678605227221576, "z": null, "yaw": 0.00858629232565709, "pitch": null, "roll": null}, "v": 2.1504582659225018, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "acceleration": 0.055782217994029604, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01641659906402525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.059078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26650163816048533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8616705296229272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.151016088102442, "gear": 1, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.059078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 17.47219798369533, "y": -0.3213947727784241, "z": null, "yaw": 0.00858629232565709, "pitch": null, "roll": null}, "v": 2.1504582659225018, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "acceleration": 0.055782217994029604, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01641659906402525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.079078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266226009776751, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8616705296229272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1522518276920053, "gear": 1, "accelerator_pedal_position": 0.26650163816048533, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.079078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 17.47219798369533, "y": -0.3213947727784241, "z": null, "yaw": 0.00858629232565709, "pitch": null, "roll": null}, "v": 2.1504582659225018, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "acceleration": 0.055782217994029604, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01641659906402525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.099078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266226009776751, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8616705296229272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.153450831398111, "gear": 1, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.099078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 17.47219798369533, "y": -0.3213947727784241, "z": null, "yaw": 0.00858629232565709, "pitch": null, "roll": null}, "v": 2.1504582659225018, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "acceleration": 0.055782217994029604, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01641659906402525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.119078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266226009776751, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8616705296229272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.154647604484552, "gear": 1, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.119078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 17.47219798369533, "y": -0.3213947727784241, "z": null, "yaw": 0.00858629232565709, "pitch": null, "roll": null}, "v": 2.1504582659225018, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "acceleration": 0.055782217994029604, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01641659906402525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.139078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266226009776751, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8616705296229272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.156438589526503, "gear": 1, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.139078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.159078, "x": 21.70906730956616, "y": 4.680729576878797, "z": null, "yaw": 0.009426032359518248, "pitch": null, "roll": null}, "v": 2.1570344731037467, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "acceleration": 0.05953286026792659, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01646680183167122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.159078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26742567748428814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8045939456125569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1570344731037467, "gear": 1, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.159078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.70906730956616, "y": -0.31927042312120335, "z": null, "yaw": 0.009426032359518248, "pitch": null, "roll": null}, "v": 2.1570344731037467, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "acceleration": 0.05953286026792659, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01646680183167122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.1790779} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.267081385100242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8045939456125569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1583744643982774, "gear": 1, "accelerator_pedal_position": 0.26742567748428814, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.1790779} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.70906730956616, "y": -0.31927042312120335, "z": null, "yaw": 0.009426032359518248, "pitch": null, "roll": null}, "v": 2.1570344731037467, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "acceleration": 0.05953286026792659, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01646680183167122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.1990778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.267081385100242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8045939456125569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1596689436657903, "gear": 1, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.1990778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.70906730956616, "y": -0.31927042312120335, "z": null, "yaw": 0.009426032359518248, "pitch": null, "roll": null}, "v": 2.1570344731037467, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "acceleration": 0.05953286026792659, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01646680183167122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.2190778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.267081385100242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8045939456125569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.160961011487112, "gear": 1, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.2190778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.70906730956616, "y": -0.31927042312120335, "z": null, "yaw": 0.009426032359518248, "pitch": null, "roll": null}, "v": 2.1570344731037467, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "acceleration": 0.05953286026792659, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01646680183167122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.2390778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.267081385100242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8045939456125569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.162894600123189, "gear": 1, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.2390778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.70906730956616, "y": -0.31927042312120335, "z": null, "yaw": 0.009426032359518248, "pitch": null, "roll": null}, "v": 2.1570344731037467, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "acceleration": 0.05953286026792659, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01646680183167122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.2590778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.267081385100242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8045939456125569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.163537928086768, "gear": 1, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.2590778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.2690778, "x": 21.946689576017263, "y": 4.683060241686394, "z": null, "yaw": 0.010265772393379405, "pitch": null, "roll": null}, "v": 2.164180656054863, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "acceleration": 0.06421284495334861, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01652135579451984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.2790778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26821920246773806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7550669954905098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.165535427497547, "gear": 1, "accelerator_pedal_position": 0.26821920246773806, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.2790778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 17.946689576017263, "y": -0.3169397583136062, "z": null, "yaw": 0.010265772393379405, "pitch": null, "roll": null}, "v": 2.164180656054863, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "acceleration": 0.06421284495334861, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01652135579451984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.2990777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26789693988342356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7550669954905098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.166247405569257, "gear": 1, "accelerator_pedal_position": 0.26821920246773806, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.2990777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 17.946689576017263, "y": -0.3169397583136062, "z": null, "yaw": 0.010265772393379405, "pitch": null, "roll": null}, "v": 2.164180656054863, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "acceleration": 0.06421284495334861, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01652135579451984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.3190777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26789693988342356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7550669954905098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.167629105000766, "gear": 1, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.3190777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 17.946689576017263, "y": -0.3169397583136062, "z": null, "yaw": 0.010265772393379405, "pitch": null, "roll": null}, "v": 2.164180656054863, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "acceleration": 0.06421284495334861, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01652135579451984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.3390777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26789693988342356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7550669954905098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.169008226123013, "gear": 1, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.3390777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 17.946689576017263, "y": -0.3169397583136062, "z": null, "yaw": 0.010265772393379405, "pitch": null, "roll": null}, "v": 2.164180656054863, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "acceleration": 0.06421284495334861, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01652135579451984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.3590777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26789693988342356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7550669954905098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.170384772986796, "gear": 1, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.3590777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.3790777, "x": 22.185114401325777, "y": 4.685599017464579, "z": null, "yaw": 0.011105512427240562, "pitch": null, "roll": null}, "v": 2.171758749639611, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "acceleration": 0.06860257612305454, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01657920696327856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.3790777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26878618647485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7191865282891233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.171758749639611, "gear": 1, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.3790777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 18.185114401325777, "y": -0.31440098253542104, "z": null, "yaw": 0.011105512427240562, "pitch": null, "roll": null}, "v": 2.171758749639611, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "acceleration": 0.06860257612305454, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01657920696327856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.3990777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26854367106728266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7191865282891233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.173241264012313, "gear": 1, "accelerator_pedal_position": 0.26878618647485, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.3990777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 18.185114401325777, "y": -0.31440098253542104, "z": null, "yaw": 0.011105512427240562, "pitch": null, "roll": null}, "v": 2.171758749639611, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "acceleration": 0.06860257612305454, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01657920696327856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.4190776} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26854367106728266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7191865282891233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1754144145035745, "gear": 1, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.4190776} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 18.185114401325777, "y": -0.31440098253542104, "z": null, "yaw": 0.011105512427240562, "pitch": null, "roll": null}, "v": 2.171758749639611, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "acceleration": 0.06860257612305454, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01657920696327856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.4390776} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26854367106728266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7191865282891233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.178302477534404, "gear": 1, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.4390776} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 18.185114401325777, "y": -0.31440098253542104, "z": null, "yaw": 0.011105512427240562, "pitch": null, "roll": null}, "v": 2.171758749639611, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "acceleration": 0.06860257612305454, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01657920696327856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.4690776} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26854367106728266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7191865282891233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.178302477534404, "gear": 1, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.4690776} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.4890776, "x": 22.424393363773532, "y": 4.688347847556337, "z": null, "yaw": 0.01194525246110172, "pitch": null, "roll": null}, "v": 2.1797424595691806, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "acceleration": 0.07189804929157051, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016640154607338514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.4890776} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2691529180980447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7124279571080151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1804995180015188, "gear": 1, "accelerator_pedal_position": 0.2691529180980447, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.4890776} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.424393363773532, "y": -0.3116521524436626, "z": null, "yaw": 0.01194525246110172, "pitch": null, "roll": null}, "v": 2.1797424595691806, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "acceleration": 0.07189804929157051, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016640154607338514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.5090775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689998581371078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7124279571080151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1812558678088454, "gear": 1, "accelerator_pedal_position": 0.2691529180980447, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.5090775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.424393363773532, "y": -0.3116521524436626, "z": null, "yaw": 0.01194525246110172, "pitch": null, "roll": null}, "v": 2.1797424595691806, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "acceleration": 0.07189804929157051, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016640154607338514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.5290775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689998581371078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7124279571080151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.182747320206295, "gear": 1, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.5290775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.424393363773532, "y": -0.3116521524436626, "z": null, "yaw": 0.01194525246110172, "pitch": null, "roll": null}, "v": 2.1797424595691806, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "acceleration": 0.07189804929157051, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016640154607338514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.5490775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689998581371078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7124279571080151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1842359804963865, "gear": 1, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.5490775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.424393363773532, "y": -0.3116521524436626, "z": null, "yaw": 0.01194525246110172, "pitch": null, "roll": null}, "v": 2.1797424595691806, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "acceleration": 0.07189804929157051, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016640154607338514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.5690775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689998581371078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7124279571080151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.185721853020119, "gear": 1, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.5690775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.424393363773532, "y": -0.3116521524436626, "z": null, "yaw": 0.01194525246110172, "pitch": null, "roll": null}, "v": 2.1797424595691806, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "acceleration": 0.07189804929157051, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016640154607338514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.5890775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689998581371078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7124279571080151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1872049421153394, "gear": 1, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.5890775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.5990775, "x": 22.66455855678383, "y": 4.691308565051115, "z": null, "yaw": 0.012784992494962876, "pitch": null, "roll": null}, "v": 2.1879454442319695, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "acceleration": 0.0739807884759709, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01670277619477936, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.6090775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27058927897965923, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.660149257051786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1886852521167293, "gear": 1, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.6090775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 18.66455855678383, "y": -0.3086914349488854, "z": null, "yaw": 0.012784992494962876, "pitch": null, "roll": null}, "v": 2.1879454442319695, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "acceleration": 0.0739807884759709, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01670277619477936, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.6290774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013100616599517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.660149257051786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.190361371791763, "gear": 1, "accelerator_pedal_position": 0.27058927897965923, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.6290774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 18.66455855678383, "y": -0.3086914349488854, "z": null, "yaw": 0.012784992494962876, "pitch": null, "roll": null}, "v": 2.1879454442319695, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "acceleration": 0.0739807884759709, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01670277619477936, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.6490774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013100616599517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.660149257051786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1919770913510797, "gear": 1, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.6490774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 18.66455855678383, "y": -0.3086914349488854, "z": null, "yaw": 0.012784992494962876, "pitch": null, "roll": null}, "v": 2.1879454442319695, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "acceleration": 0.0739807884759709, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01670277619477936, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.6690774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013100616599517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.660149257051786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1935897802264455, "gear": 1, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.6690774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 18.66455855678383, "y": -0.3086914349488854, "z": null, "yaw": 0.012784992494962876, "pitch": null, "roll": null}, "v": 2.1879454442319695, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "acceleration": 0.0739807884759709, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01670277619477936, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.6890774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013100616599517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.660149257051786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.195199443062843, "gear": 1, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.6890774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.7090774, "x": 22.90565398542263, "y": 4.694483245851452, "z": null, "yaw": 0.013624732528824034, "pitch": null, "roll": null}, "v": 2.196806084502393, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "acceleration": 0.08021891458328273, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01677041832533133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.7090774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710401300451377, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6020421417641109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.196806084502393, "gear": 1, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.7090774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 18.90565398542263, "y": -0.30551675414854795, "z": null, "yaw": 0.013624732528824034, "pitch": null, "roll": null}, "v": 2.196806084502393, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "acceleration": 0.08021891458328273, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01677041832533133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.7290773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2707976061275563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6020421417641109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1985232962850576, "gear": 1, "accelerator_pedal_position": 0.2710401300451377, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.7290773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 18.90565398542263, "y": -0.30551675414854795, "z": null, "yaw": 0.013624732528824034, "pitch": null, "roll": null}, "v": 2.196806084502393, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "acceleration": 0.08021891458328273, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01677041832533133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.7490773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2707976061275563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6020421417641109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.200206981291696, "gear": 1, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.7490773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 18.90565398542263, "y": -0.30551675414854795, "z": null, "yaw": 0.013624732528824034, "pitch": null, "roll": null}, "v": 2.196806084502393, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "acceleration": 0.08021891458328273, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01677041832533133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.7690773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2707976061275563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6020421417641109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.201887502602306, "gear": 1, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.7690773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 18.90565398542263, "y": -0.30551675414854795, "z": null, "yaw": 0.013624732528824034, "pitch": null, "roll": null}, "v": 2.196806084502393, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "acceleration": 0.08021891458328273, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01677041832533133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.7890773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2707976061275563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6020421417641109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2044023631714564, "gear": 1, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.7890773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 18.90565398542263, "y": -0.30551675414854795, "z": null, "yaw": 0.013624732528824034, "pitch": null, "roll": null}, "v": 2.196806084502393, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "acceleration": 0.08021891458328273, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01677041832533133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.7990773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2707976061275563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6020421417641109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2044023631714564, "gear": 1, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.7990773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.8190773, "x": 23.147744578853096, "y": 4.697874363902222, "z": null, "yaw": 0.014464472562685191, "pitch": null, "roll": null}, "v": 2.2060749963041597, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "acceleration": 0.08351361958883496, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016841177200879257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.8290772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727714806946578, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5298673068854388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.206910132500048, "gear": 1, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.8290772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 19.147744578853096, "y": -0.3021256360977782, "z": null, "yaw": 0.014464472562685191, "pitch": null, "roll": null}, "v": 2.2060749963041597, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "acceleration": 0.08351361958883496, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016841177200879257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.8490772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.272198221754291, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5298673068854388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2088246653182715, "gear": 1, "accelerator_pedal_position": 0.2727714806946578, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.8490772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 19.147744578853096, "y": -0.3021256360977782, "z": null, "yaw": 0.014464472562685191, "pitch": null, "roll": null}, "v": 2.2060749963041597, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "acceleration": 0.08351361958883496, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016841177200879257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.8690772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.272198221754291, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5298673068854388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2106639705025364, "gear": 1, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.8690772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 19.147744578853096, "y": -0.3021256360977782, "z": null, "yaw": 0.014464472562685191, "pitch": null, "roll": null}, "v": 2.2060749963041597, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "acceleration": 0.08351361958883496, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016841177200879257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.8890772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.272198221754291, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5298673068854388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2124998119180748, "gear": 1, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.8890772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 19.147744578853096, "y": -0.3021256360977782, "z": null, "yaw": 0.014464472562685191, "pitch": null, "roll": null}, "v": 2.2060749963041597, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "acceleration": 0.08351361958883496, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016841177200879257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.9090772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.272198221754291, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5298673068854388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2143321947403445, "gear": 1, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.9090772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.9290771, "x": 23.390889414743697, "y": 4.701484476732939, "z": null, "yaw": 0.015304212596546348, "pitch": null, "roll": null}, "v": 2.2161611241426686, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "acceleration": 0.0913171284755721, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016918174703903232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.9290771} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727416792699258, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5134641937581695, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2161611241426686, "gear": 1, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.9290771} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.390889414743697, "y": -0.2985155232670609, "z": null, "yaw": 0.015304212596546348, "pitch": null, "roll": null}, "v": 2.2161611241426686, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "acceleration": 0.0913171284755721, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016918174703903232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.9490771} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726193656551126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5134641937581695, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.21805450544143, "gear": 1, "accelerator_pedal_position": 0.2727416792699258, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.9490771} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.390889414743697, "y": -0.2985155232670609, "z": null, "yaw": 0.015304212596546348, "pitch": null, "roll": null}, "v": 2.2161611241426686, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "acceleration": 0.0913171284755721, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016918174703903232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.969077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726193656551126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5134641937581695, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2199290335670305, "gear": 1, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.969077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.390889414743697, "y": -0.2985155232670609, "z": null, "yaw": 0.015304212596546348, "pitch": null, "roll": null}, "v": 2.2161611241426686, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "acceleration": 0.0913171284755721, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016918174703903232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.989077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726193656551126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5134641937581695, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.22180002465837, "gear": 1, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.989077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.390889414743697, "y": -0.2985155232670609, "z": null, "yaw": 0.015304212596546348, "pitch": null, "roll": null}, "v": 2.2161611241426686, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "acceleration": 0.0913171284755721, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016918174703903232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.009077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726193656551126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5134641937581695, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2236674839898716, "gear": 1, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.009077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.390889414743697, "y": -0.2985155232670609, "z": null, "yaw": 0.015304212596546348, "pitch": null, "roll": null}, "v": 2.2161611241426686, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "acceleration": 0.0913171284755721, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016918174703903232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.029077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726193656551126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5134641937581695, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.225531416833927, "gear": 1, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.029077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.039077, "x": 23.63515378414241, "y": 4.705316379210313, "z": null, "yaw": 0.016143952630407493, "pitch": null, "roll": null}, "v": 2.2264620624702234, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "acceleration": 0.09297659906475075, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016996812070266713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.049077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2777700552682761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35407772775433866, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.227391828460871, "gear": 1, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.049077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 19.63515378414241, "y": -0.29468362078968724, "z": null, "yaw": 0.016143952630407493, "pitch": null, "roll": null}, "v": 2.2264620624702234, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "acceleration": 0.09297659906475075, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016996812070266713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.069077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27620909768026675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35407772775433866, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.229892255903829, "gear": 1, "accelerator_pedal_position": 0.2777700552682761, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.069077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 19.63515378414241, "y": -0.29468362078968724, "z": null, "yaw": 0.016143952630407493, "pitch": null, "roll": null}, "v": 2.2264620624702234, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "acceleration": 0.09297659906475075, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016996812070266713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.089077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27620909768026675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35407772775433866, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.233341631736856, "gear": 1, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.089077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 19.63515378414241, "y": -0.29468362078968724, "z": null, "yaw": 0.016143952630407493, "pitch": null, "roll": null}, "v": 2.2264620624702234, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "acceleration": 0.09297659906475075, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016996812070266713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.109077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27620909768026675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35407772775433866, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.234489248041599, "gear": 1, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.109077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 19.63515378414241, "y": -0.29468362078968724, "z": null, "yaw": 0.016143952630407493, "pitch": null, "roll": null}, "v": 2.2264620624702234, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "acceleration": 0.09297659906475075, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016996812070266713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.129077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27620909768026675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35407772775433866, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2390688554804985, "gear": 1, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.129077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.149077, "x": 23.880658231328745, "y": 4.709373967027376, "z": null, "yaw": 0.01698369266426863, "pitch": null, "roll": null}, "v": 2.2390688554804985, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "acceleration": 0.11421912433181469, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017093052331987886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.149077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27609497515964787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3492332555259885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2390688554804985, "gear": 1, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.149077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 19.880658231328745, "y": -0.29062603297262424, "z": null, "yaw": 0.01698369266426863, "pitch": null, "roll": null}, "v": 2.2390688554804985, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "acceleration": 0.11421912433181469, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017093052331987886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.179077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2761903035043509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3492332555259885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.242470804141474, "gear": 1, "accelerator_pedal_position": 0.27609497515964787, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.179077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 19.880658231328745, "y": -0.29062603297262424, "z": null, "yaw": 0.01698369266426863, "pitch": null, "roll": null}, "v": 2.2390688554804985, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "acceleration": 0.11421912433181469, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017093052331987886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.199077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2761903035043509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3492332555259885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.24474530689628, "gear": 1, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.199077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 19.880658231328745, "y": -0.29062603297262424, "z": null, "yaw": 0.01698369266426863, "pitch": null, "roll": null}, "v": 2.2390688554804985, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "acceleration": 0.11421912433181469, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017093052331987886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.2190769} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2761903035043509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3492332555259885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2470154954418677, "gear": 1, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.2190769} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 19.880658231328745, "y": -0.29062603297262424, "z": null, "yaw": 0.01698369266426863, "pitch": null, "roll": null}, "v": 2.2390688554804985, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "acceleration": 0.11421912433181469, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017093052331987886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.2390769} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2761903035043509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3492332555259885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2492813759007757, "gear": 1, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.2390769} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.2590768, "x": 24.127542741543518, "y": 4.713661739800347, "z": null, "yaw": 0.01782343269812977, "pitch": null, "roll": null}, "v": 2.2515429543956538, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "acceleration": 0.11291779242752342, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017188279606946067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.2590768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2760666523850467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.34372825757861963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2515429543956538, "gear": 1, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.2590768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.127542741543518, "y": -0.2863382601996527, "z": null, "yaw": 0.01782343269812977, "pitch": null, "roll": null}, "v": 2.2515429543956538, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "acceleration": 0.11291779242752342, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017188279606946067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.2790768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27616448683921535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.34372825757861963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.253784788005214, "gear": 1, "accelerator_pedal_position": 0.2760666523850467, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.2790768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.127542741543518, "y": -0.2863382601996527, "z": null, "yaw": 0.01782343269812977, "pitch": null, "roll": null}, "v": 2.2515429543956538, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "acceleration": 0.11291779242752342, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017188279606946067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.2990768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27616448683921535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.34372825757861963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2560345847576424, "gear": 1, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.2990768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.127542741543518, "y": -0.2863382601996527, "z": null, "yaw": 0.01782343269812977, "pitch": null, "roll": null}, "v": 2.2515429543956538, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "acceleration": 0.11291779242752342, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017188279606946067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.3190768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27616448683921535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.34372825757861963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.258280104007127, "gear": 1, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.3190768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.127542741543518, "y": -0.2863382601996527, "z": null, "yaw": 0.01782343269812977, "pitch": null, "roll": null}, "v": 2.2515429543956538, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "acceleration": 0.11291779242752342, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017188279606946067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.3390768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27616448683921535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.34372825757861963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.260521351870432, "gear": 1, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.3390768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.127542741543518, "y": -0.2863382601996527, "z": null, "yaw": 0.01782343269812977, "pitch": null, "roll": null}, "v": 2.2515429543956538, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "acceleration": 0.11291779242752342, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017188279606946067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.3590767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27616448683921535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.34372825757861963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262758334464191, "gear": 1, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.3590767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.3690767, "x": 24.375788551839143, "y": 4.718181681299291, "z": null, "yaw": 0.018663172731990908, "pitch": null, "roll": null}, "v": 2.263875228196391, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "acceleration": 0.11158297084686364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017282424188937124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.3790767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2791923640399333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2510895976343659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2649910579048598, "gear": 1, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.3790767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 20.375788551839143, "y": -0.28181831870070884, "z": null, "yaw": 0.018663172731990908, "pitch": null, "roll": null}, "v": 2.263875228196391, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "acceleration": 0.11158297084686364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017282424188937124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.3990767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27830482520397126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2510895976343659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267597832565395, "gear": 1, "accelerator_pedal_position": 0.2791923640399333, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.3990767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 20.375788551839143, "y": -0.28181831870070884, "z": null, "yaw": 0.018663172731990908, "pitch": null, "roll": null}, "v": 2.263875228196391, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "acceleration": 0.11158297084686364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017282424188937124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.4190767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27830482520397126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2510895976343659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.270088749606413, "gear": 1, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.4190767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 20.375788551839143, "y": -0.28181831870070884, "z": null, "yaw": 0.018663172731990908, "pitch": null, "roll": null}, "v": 2.263875228196391, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "acceleration": 0.11158297084686364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017282424188937124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.4390767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27830482520397126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2510895976343659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2750563406620423, "gear": 1, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.4390767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 20.375788551839143, "y": -0.28181831870070884, "z": null, "yaw": 0.018663172731990908, "pitch": null, "roll": null}, "v": 2.263875228196391, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "acceleration": 0.11158297084686364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017282424188937124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.4590766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27830482520397126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2510895976343659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2775330278506005, "gear": 1, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.4590766} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.4790766, "x": 24.625450928566682, "y": 4.722937149327967, "z": null, "yaw": 0.019502912765852046, "pitch": null, "roll": null}, "v": 2.2775330278506005, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "acceleration": 0.12365693920278703, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01738668783570162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.4890766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27785772154930394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.24100555304958743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2787695972426283, "gear": 1, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.4890766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27785772154930394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.24100555304958743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.279977040953107, "gear": 1, "accelerator_pedal_position": 0.27785772154930394, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.4990766} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 20.625450928566682, "y": -0.2770628506720332, "z": null, "yaw": 0.019502912765852046, "pitch": null, "roll": null}, "v": 2.2775330278506005, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "acceleration": 0.12365693920278703, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01738668783570162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.5290766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2780625988969056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.24100555304958743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2848080871017373, "gear": 1, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.5290766} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 20.625450928566682, "y": -0.2770628506720332, "z": null, "yaw": 0.019502912765852046, "pitch": null, "roll": null}, "v": 2.2775330278506005, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "acceleration": 0.12365693920278703, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01738668783570162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.5390766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2780625988969056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.24100555304958743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2848080871017373, "gear": 1, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.5390766} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 20.625450928566682, "y": -0.2770628506720332, "z": null, "yaw": 0.019502912765852046, "pitch": null, "roll": null}, "v": 2.2775330278506005, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "acceleration": 0.12365693920278703, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01738668783570162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.5590765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2780625988969056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.24100555304958743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.287235871925668, "gear": 1, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.5590765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 20.625450928566682, "y": -0.2770628506720332, "z": null, "yaw": 0.019502912765852046, "pitch": null, "roll": null}, "v": 2.2775330278506005, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "acceleration": 0.12365693920278703, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01738668783570162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.5790765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2780625988969056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.24100555304958743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2908688397001153, "gear": 1, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.5790765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.5890765, "x": 24.87659743430749, "y": 4.7279318603681, "z": null, "yaw": 0.020342652799713184, "pitch": null, "roll": null}, "v": 2.2908688397001153, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "acceleration": 0.1208670007135646, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017488493427465963, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.5990765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2776584686384961, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2295771930015559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.292077509707251, "gear": 1, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.5990765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 20.87659743430749, "y": -0.2720681396318998, "z": null, "yaw": 0.020342652799713184, "pitch": null, "roll": null}, "v": 2.2908688397001153, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "acceleration": 0.1208670007135646, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017488493427465963, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.6190765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27784856067238617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2295771930015559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2944408836853007, "gear": 1, "accelerator_pedal_position": 0.2776584686384961, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.6190765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 20.87659743430749, "y": -0.2720681396318998, "z": null, "yaw": 0.020342652799713184, "pitch": null, "roll": null}, "v": 2.2908688397001153, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "acceleration": 0.1208670007135646, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017488493427465963, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.6390765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27784856067238617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2295771930015559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.299201503683212, "gear": 1, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.6390765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 20.87659743430749, "y": -0.2720681396318998, "z": null, "yaw": 0.020342652799713184, "pitch": null, "roll": null}, "v": 2.2908688397001153, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "acceleration": 0.1208670007135646, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017488493427465963, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.6590765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27784856067238617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2295771930015559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.299201503683212, "gear": 1, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.6590765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 20.87659743430749, "y": -0.2720681396318998, "z": null, "yaw": 0.020342652799713184, "pitch": null, "roll": null}, "v": 2.2908688397001153, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "acceleration": 0.1208670007135646, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017488493427465963, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.6790764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27784856067238617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2295771930015559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3027599898174986, "gear": 1, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.6790764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.6990764, "x": 25.1291935858373, "y": 4.7331676015448, "z": null, "yaw": 0.021182392833574322, "pitch": null, "roll": null}, "v": 2.3039438745075436, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "acceleration": 0.11827473670822797, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017588308247210742, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.6990764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2777135956283312, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20476266596205814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3039438745075436, "gear": 1, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.6990764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.1291935858373, "y": -0.26683239845520035, "z": null, "yaw": 0.021182392833574322, "pitch": null, "roll": null}, "v": 2.3039438745075436, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "acceleration": 0.11827473670822797, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017588308247210742, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.7190764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778184985284826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20476266596205814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3062913702074628, "gear": 1, "accelerator_pedal_position": 0.2777135956283312, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.7190764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.1291935858373, "y": -0.26683239845520035, "z": null, "yaw": 0.021182392833574322, "pitch": null, "roll": null}, "v": 2.3039438745075436, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "acceleration": 0.11827473670822797, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017588308247210742, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.7390764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778184985284826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20476266596205814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3086474620865416, "gear": 1, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.7390764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.1291935858373, "y": -0.26683239845520035, "z": null, "yaw": 0.021182392833574322, "pitch": null, "roll": null}, "v": 2.3039438745075436, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "acceleration": 0.11827473670822797, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017588308247210742, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.7590764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778184985284826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20476266596205814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.310999024853581, "gear": 1, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.7590764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.1291935858373, "y": -0.26683239845520035, "z": null, "yaw": 0.021182392833574322, "pitch": null, "roll": null}, "v": 2.3039438745075436, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "acceleration": 0.11827473670822797, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017588308247210742, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.7790763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778184985284826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20476266596205814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.313346065004011, "gear": 1, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.7790763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.1291935858373, "y": -0.26683239845520035, "z": null, "yaw": 0.021182392833574322, "pitch": null, "roll": null}, "v": 2.3039438745075436, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "acceleration": 0.11827473670822797, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017588308247210742, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.7990763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778184985284826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20476266596205814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3156885890335235, "gear": 1, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.7990763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.8090763, "x": 25.383214697320167, "y": 4.738646284291756, "z": null, "yaw": 0.02202213286743546, "pitch": null, "roll": null}, "v": 2.3168581595328988, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "acceleration": 0.11684439051242962, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017686895903069693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.8190763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.278927772249075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15432646379466586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3180266034380232, "gear": 1, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.8190763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 21.383214697320167, "y": -0.2613537157082444, "z": null, "yaw": 0.02202213286743546, "pitch": null, "roll": null}, "v": 2.3168581595328988, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "acceleration": 0.11684439051242962, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017686895903069693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.8390763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2786432469146606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15432646379466586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3204987071056076, "gear": 1, "accelerator_pedal_position": 0.278927772249075, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.8390763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 21.383214697320167, "y": -0.2613537157082444, "z": null, "yaw": 0.02202213286743546, "pitch": null, "roll": null}, "v": 2.3168581595328988, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "acceleration": 0.11684439051242962, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017686895903069693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.8590763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2786432469146606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15432646379466586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3229304984547863, "gear": 1, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.8590763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 21.383214697320167, "y": -0.2613537157082444, "z": null, "yaw": 0.02202213286743546, "pitch": null, "roll": null}, "v": 2.3168581595328988, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "acceleration": 0.11684439051242962, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017686895903069693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.8790762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2786432469146606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15432646379466586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.325357601313377, "gear": 1, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.8790762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 21.383214697320167, "y": -0.2613537157082444, "z": null, "yaw": 0.02202213286743546, "pitch": null, "roll": null}, "v": 2.3168581595328988, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "acceleration": 0.11684439051242962, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017686895903069693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.8990762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2786432469146606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15432646379466586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.327780022365589, "gear": 1, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.8990762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.9190762, "x": 25.638671898580018, "y": 4.744370564604746, "z": null, "yaw": 0.022861872901296598, "pitch": null, "roll": null}, "v": 2.3301977682963644, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "acceleration": 0.12071218840807674, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017788730480476304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.9190762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28001125116388387, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10331760234166865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3301977682963644, "gear": 1, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.9190762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.638671898580018, "y": -0.25562943539525396, "z": null, "yaw": 0.022861872901296598, "pitch": null, "roll": null}, "v": 2.3301977682963644, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "acceleration": 0.12071218840807674, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017788730480476304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.9390762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27964809357379516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10331760234166865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3327817637044674, "gear": 1, "accelerator_pedal_position": 0.28001125116388387, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.9390762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.638671898580018, "y": -0.25562943539525396, "z": null, "yaw": 0.022861872901296598, "pitch": null, "roll": null}, "v": 2.3301977682963644, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "acceleration": 0.12071218840807674, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017788730480476304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.9590762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27964809357379516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10331760234166865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.335315394284956, "gear": 1, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.9590762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.638671898580018, "y": -0.25562943539525396, "z": null, "yaw": 0.022861872901296598, "pitch": null, "roll": null}, "v": 2.3301977682963644, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "acceleration": 0.12071218840807674, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017788730480476304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.9790761} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27964809357379516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10331760234166865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3391066597835106, "gear": 1, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.9790761} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.638671898580018, "y": -0.25562943539525396, "z": null, "yaw": 0.022861872901296598, "pitch": null, "roll": null}, "v": 2.3301977682963644, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "acceleration": 0.12071218840807674, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017788730480476304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.9990761} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27964809357379516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10331760234166865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3403679703053966, "gear": 1, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.9990761} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.638671898580018, "y": -0.25562943539525396, "z": null, "yaw": 0.022861872901296598, "pitch": null, "roll": null}, "v": 2.3301977682963644, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "acceleration": 0.12071218840807674, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017788730480476304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.019076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27964809357379516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10331760234166865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3428869295662405, "gear": 1, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.019076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.029076, "x": 25.895624948068637, "y": 4.750344253801164, "z": null, "yaw": 0.023701612935157736, "pitch": null, "roll": null}, "v": 2.3441445800333462, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "acceleration": 0.12564321771355524, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017895200445569654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.039076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28064524525226947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06105401635280549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3467185489418356, "gear": 1, "accelerator_pedal_position": 0.28064524525226947, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.039076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 21.895624948068637, "y": -0.2496557461988358, "z": null, "yaw": 0.023701612935157736, "pitch": null, "roll": null}, "v": 2.3441445800333462, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "acceleration": 0.12564321771355524, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017895200445569654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.059076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2804010983083767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06105401635280549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3480348087008367, "gear": 1, "accelerator_pedal_position": 0.28064524525226947, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.059076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 21.895624948068637, "y": -0.2496557461988358, "z": null, "yaw": 0.023701612935157736, "pitch": null, "roll": null}, "v": 2.3441445800333462, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "acceleration": 0.12564321771355524, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017895200445569654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.079076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2804010983083767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06105401635280549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3519302018940897, "gear": 1, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.079076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 21.895624948068637, "y": -0.2496557461988358, "z": null, "yaw": 0.023701612935157736, "pitch": null, "roll": null}, "v": 2.3441445800333462, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "acceleration": 0.12564321771355524, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017895200445569654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.099076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2804010983083767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06105401635280549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.353226147869958, "gear": 1, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.099076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 21.895624948068637, "y": -0.2496557461988358, "z": null, "yaw": 0.023701612935157736, "pitch": null, "roll": null}, "v": 2.3441445800333462, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "acceleration": 0.12564321771355524, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017895200445569654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.119076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2804010983083767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06105401635280549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3558142674994453, "gear": 1, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.119076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.139076, "x": 26.15411859962384, "y": 4.756570950254567, "z": null, "yaw": 0.024541352969018874, "pitch": null, "roll": null}, "v": 2.3583973632681583, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "acceleration": 0.1289666150332442, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018004006197171622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.139076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28143948003705305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.01818852090329962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3583973632681583, "gear": 1, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.139076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.15411859962384, "y": -0.24342904974543256, "z": null, "yaw": 0.024541352969018874, "pitch": null, "roll": null}, "v": 2.3583973632681583, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "acceleration": 0.1289666150332442, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018004006197171622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.159076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811841296929932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.01818852090329962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3611051768984104, "gear": 1, "accelerator_pedal_position": 0.28143948003705305, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.159076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.15411859962384, "y": -0.24342904974543256, "z": null, "yaw": 0.024541352969018874, "pitch": null, "roll": null}, "v": 2.3583973632681583, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "acceleration": 0.1289666150332442, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018004006197171622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.179076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811841296929932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.01818852090329962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.363775825361594, "gear": 1, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.179076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.15411859962384, "y": -0.24342904974543256, "z": null, "yaw": 0.024541352969018874, "pitch": null, "roll": null}, "v": 2.3583973632681583, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "acceleration": 0.1289666150332442, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018004006197171622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.199076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811841296929932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.01818852090329962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3664412812906015, "gear": 1, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.199076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.15411859962384, "y": -0.24342904974543256, "z": null, "yaw": 0.024541352969018874, "pitch": null, "roll": null}, "v": 2.3583973632681583, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "acceleration": 0.1289666150332442, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018004006197171622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.219076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811841296929932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.01818852090329962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.369101551940781, "gear": 1, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.219076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.15411859962384, "y": -0.24342904974543256, "z": null, "yaw": 0.024541352969018874, "pitch": null, "roll": null}, "v": 2.3583973632681583, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "acceleration": 0.1289666150332442, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018004006197171622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.239076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811841296929932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.01818852090329962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.373082251395364, "gear": 1, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.239076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.249076, "x": 26.414198612209045, "y": 4.763054392756411, "z": null, "yaw": 0.025381093002880013, "pitch": null, "roll": null}, "v": 2.373082251395364, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "acceleration": 0.13243150429256245, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018116110637655145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.2590759} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27617212449492906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.034510731928342704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3744065664382896, "gear": 1, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.2590759} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 22.414198612209045, "y": -0.23694560724358915, "z": null, "yaw": 0.025381093002880013, "pitch": null, "roll": null}, "v": 2.373082251395364, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "acceleration": 0.13243150429256245, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018116110637655145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.2790759} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778098300378143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.034510731928342704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3764251296135535, "gear": 1, "accelerator_pedal_position": 0.27617212449492906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.2790759} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 22.414198612209045, "y": -0.23694560724358915, "z": null, "yaw": 0.025381093002880013, "pitch": null, "roll": null}, "v": 2.373082251395364, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "acceleration": 0.13243150429256245, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018116110637655145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.2990758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778098300378143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.034510731928342704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3786443711115455, "gear": 1, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.2990758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 22.414198612209045, "y": -0.23694560724358915, "z": null, "yaw": 0.025381093002880013, "pitch": null, "roll": null}, "v": 2.373082251395364, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "acceleration": 0.13243150429256245, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018116110637655145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.3190758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778098300378143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.034510731928342704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.380859284458605, "gear": 1, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.3190758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 22.414198612209045, "y": -0.23694560724358915, "z": null, "yaw": 0.025381093002880013, "pitch": null, "roll": null}, "v": 2.373082251395364, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "acceleration": 0.13243150429256245, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018116110637655145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.3390758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778098300378143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.034510731928342704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3830698761344755, "gear": 1, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.3390758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.3590758, "x": 26.675765076082964, "y": 4.769794658972169, "z": null, "yaw": 0.02622083303674115, "pitch": null, "roll": null}, "v": 2.385276152617737, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "acceleration": 0.11015220686298366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018209198883340372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.3590758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2724164025582796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06518162014874586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.385276152617737, "gear": 1, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.3590758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 22.675765076082964, "y": -0.23020534102783063, "z": null, "yaw": 0.02622083303674115, "pitch": null, "roll": null}, "v": 2.385276152617737, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "acceleration": 0.11015220686298366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018209198883340372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.3790758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741613460189438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06518162014874586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3868042713685034, "gear": 1, "accelerator_pedal_position": 0.2724164025582796, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.3790758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 22.675765076082964, "y": -0.23020534102783063, "z": null, "yaw": 0.02622083303674115, "pitch": null, "roll": null}, "v": 2.385276152617737, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "acceleration": 0.11015220686298366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018209198883340372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.3990757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741613460189438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06518162014874586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3885474160902747, "gear": 1, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.3990757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 22.675765076082964, "y": -0.23020534102783063, "z": null, "yaw": 0.02622083303674115, "pitch": null, "roll": null}, "v": 2.385276152617737, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "acceleration": 0.11015220686298366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018209198883340372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.4190757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741613460189438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06518162014874586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.390287154203802, "gear": 1, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.4190757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 22.675765076082964, "y": -0.23020534102783063, "z": null, "yaw": 0.02622083303674115, "pitch": null, "roll": null}, "v": 2.385276152617737, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "acceleration": 0.11015220686298366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018209198883340372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.4390757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741613460189438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06518162014874586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3920234911564977, "gear": 1, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.4390757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 22.675765076082964, "y": -0.23020534102783063, "z": null, "yaw": 0.02622083303674115, "pitch": null, "roll": null}, "v": 2.385276152617737, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "acceleration": 0.11015220686298366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018209198883340372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.4590757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741613460189438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06518162014874586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.393756432392221, "gear": 1, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.4590757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.4690757, "x": 26.938510823365796, "y": 4.776786082628924, "z": null, "yaw": 0.02706057307060229, "pitch": null, "roll": null}, "v": 2.394621631316447, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "acceleration": 0.08643520348089001, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01828054227060313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.4790757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2678198327747935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10873020970169016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.395485983351256, "gear": 1, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.4790757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 22.938510823365796, "y": -0.22321391737107632, "z": null, "yaw": 0.02706057307060229, "pitch": null, "roll": null}, "v": 2.394621631316447, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "acceleration": 0.08643520348089001, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01828054227060313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.4990757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2698472559060803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10873020970169016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.396419848427376, "gear": 1, "accelerator_pedal_position": 0.2678198327747935, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.4990757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 22.938510823365796, "y": -0.22321391737107632, "z": null, "yaw": 0.02706057307060229, "pitch": null, "roll": null}, "v": 2.394621631316447, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "acceleration": 0.08643520348089001, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01828054227060313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.5190756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2698472559060803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10873020970169016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3976051892370935, "gear": 1, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.5190756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 22.938510823365796, "y": -0.22321391737107632, "z": null, "yaw": 0.02706057307060229, "pitch": null, "roll": null}, "v": 2.394621631316447, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "acceleration": 0.08643520348089001, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01828054227060313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.5390756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2698472559060803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10873020970169016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3987882091920136, "gear": 1, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.5390756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 22.938510823365796, "y": -0.22321391737107632, "z": null, "yaw": 0.02706057307060229, "pitch": null, "roll": null}, "v": 2.394621631316447, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "acceleration": 0.08643520348089001, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01828054227060313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.5590756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2698472559060803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10873020970169016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.399968912276747, "gear": 1, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.5590756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.5790756, "x": 27.20215141180437, "y": 4.784022845082385, "z": null, "yaw": 0.027900313104463427, "pitch": null, "roll": null}, "v": 2.4011473024713865, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "acceleration": 0.05883290060777613, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018330359246208728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.5790756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26359426851997847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15870174788201433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4011473024713865, "gear": 1, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.5790756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 23.20215141180437, "y": -0.21597715491761527, "z": null, "yaw": 0.027900313104463427, "pitch": null, "roll": null}, "v": 2.4011473024713865, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "acceleration": 0.05883290060777613, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018330359246208728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.5990756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655802903636585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15870174788201433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.401542143444107, "gear": 1, "accelerator_pedal_position": 0.26359426851997847, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.5990756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 23.20215141180437, "y": -0.21597715491761527, "z": null, "yaw": 0.027900313104463427, "pitch": null, "roll": null}, "v": 2.4011473024713865, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "acceleration": 0.05883290060777613, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018330359246208728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.6190755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655802903636585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15870174788201433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.40218434172189, "gear": 1, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.6190755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 23.20215141180437, "y": -0.21597715491761527, "z": null, "yaw": 0.027900313104463427, "pitch": null, "roll": null}, "v": 2.4011473024713865, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "acceleration": 0.05883290060777613, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018330359246208728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.6390755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655802903636585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15870174788201433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4031452799622217, "gear": 1, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.6390755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 23.20215141180437, "y": -0.21597715491761527, "z": null, "yaw": 0.027900313104463427, "pitch": null, "roll": null}, "v": 2.4011473024713865, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "acceleration": 0.05883290060777613, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018330359246208728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.6590755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655802903636585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15870174788201433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4034649647463087, "gear": 1, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.6590755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 23.20215141180437, "y": -0.21597715491761527, "z": null, "yaw": 0.027900313104463427, "pitch": null, "roll": null}, "v": 2.4011473024713865, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "acceleration": 0.05883290060777613, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018330359246208728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.6790755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655802903636585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15870174788201433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4041033940942893, "gear": 1, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.6790755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.6890755, "x": 27.466324817989975, "y": 4.791496219096074, "z": null, "yaw": 0.028740053138324565, "pitch": null, "roll": null}, "v": 2.4044221392320213, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "acceleration": 0.031843249574973476, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018355359351047505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.6990755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25997619082543266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20854487637869124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4047405717277712, "gear": 1, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.6990755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 23.466324817989975, "y": -0.20850378090392585, "z": null, "yaw": 0.028740053138324565, "pitch": null, "roll": null}, "v": 2.4044221392320213, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "acceleration": 0.031843249574973476, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018355359351047505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.7190754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2617435289095187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20854487637869124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4046763310894845, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.7190754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 23.466324817989975, "y": -0.20850378090392585, "z": null, "yaw": 0.028740053138324565, "pitch": null, "roll": null}, "v": 2.4044221392320213, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "acceleration": 0.031843249574973476, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018355359351047505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.7390754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2617435289095187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20854487637869124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4048330253288444, "gear": 1, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.7390754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 23.466324817989975, "y": -0.20850378090392585, "z": null, "yaw": 0.028740053138324565, "pitch": null, "roll": null}, "v": 2.4044221392320213, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "acceleration": 0.031843249574973476, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018355359351047505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.7590754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2617435289095187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20854487637869124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4049894122978124, "gear": 1, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.7590754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 23.466324817989975, "y": -0.20850378090392585, "z": null, "yaw": 0.028740053138324565, "pitch": null, "roll": null}, "v": 2.4044221392320213, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "acceleration": 0.031843249574973476, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018355359351047505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.7790754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2617435289095187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20854487637869124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.405145492589154, "gear": 1, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.7790754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.7990754, "x": 27.73074736810815, "y": 4.799198850641209, "z": null, "yaw": 0.029579793172185703, "pitch": null, "roll": null}, "v": 2.40530126679453, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "acceleration": 0.007777250504331479, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018362070611130318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.7990754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25659435073529546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2578094738731477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.40530126679453, "gear": 1, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.7990754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.73074736810815, "y": -0.20080114935879134, "z": null, "yaw": 0.029579793172185703, "pitch": null, "roll": null}, "v": 2.40530126679453, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "acceleration": 0.007777250504331479, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018362070611130318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.8190753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582077819717016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2578094738731477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.404813403955747, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.8190753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.73074736810815, "y": -0.20080114935879134, "z": null, "yaw": 0.029579793172185703, "pitch": null, "roll": null}, "v": 2.40530126679453, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "acceleration": 0.007777250504331479, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018362070611130318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.8390753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582077819717016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2578094738731477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.404528077810472, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.8390753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.73074736810815, "y": -0.20080114935879134, "z": null, "yaw": 0.029579793172185703, "pitch": null, "roll": null}, "v": 2.40530126679453, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "acceleration": 0.007777250504331479, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018362070611130318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.8590753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582077819717016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2578094738731477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4042433111548367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.8590753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.73074736810815, "y": -0.20080114935879134, "z": null, "yaw": 0.029579793172185703, "pitch": null, "roll": null}, "v": 2.40530126679453, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "acceleration": 0.007777250504331479, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018362070611130318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.8790753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582077819717016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2578094738731477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.403959102859329, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.8790753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.73074736810815, "y": -0.20080114935879134, "z": null, "yaw": 0.029579793172185703, "pitch": null, "roll": null}, "v": 2.40530126679453, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "acceleration": 0.007777250504331479, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018362070611130318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.8990753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582077819717016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2578094738731477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.403675451796843, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.8990753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.9090753, "x": 27.995114181233742, "y": 4.807122033072656, "z": null, "yaw": 0.03041953320604684, "pitch": null, "roll": null}, "v": 2.4035338348764186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3779464406977784, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018348578035323387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.9190753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253463614756991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3086641940917309, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.403392356842672, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.9190753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 23.995114181233742, "y": -0.1928779669273437, "z": null, "yaw": 0.03041953320604684, "pitch": null, "roll": null}, "v": 2.4035338348764186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3779464406977784, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018348578035323387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.9390752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25493749975382324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3086641940917309, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4025170867369083, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.9390752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 23.995114181233742, "y": -0.1928779669273437, "z": null, "yaw": 0.03041953320604684, "pitch": null, "roll": null}, "v": 2.4035338348764186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3779464406977784, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018348578035323387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.9590752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25493749975382324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3086641940917309, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4018276775868794, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.9590752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 23.995114181233742, "y": -0.1928779669273437, "z": null, "yaw": 0.03041953320604684, "pitch": null, "roll": null}, "v": 2.4035338348764186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3779464406977784, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018348578035323387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.9790752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25493749975382324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3086641940917309, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.401139619567694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.9790752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 23.995114181233742, "y": -0.1928779669273437, "z": null, "yaw": 0.03041953320604684, "pitch": null, "roll": null}, "v": 2.4035338348764186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3779464406977784, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018348578035323387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.9990752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25493749975382324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3086641940917309, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4004529098420773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.9990752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.0190752, "x": 28.259192655593292, "y": 4.815258519363193, "z": null, "yaw": 0.03125927323990798, "pitch": null, "roll": null}, "v": 2.3997675455794254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775772200071343, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01831982618167077, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.0190752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2508561383182843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3622832606541105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3997675455794254, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.0190752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.259192655593292, "y": -0.18474148063680662, "z": null, "yaw": 0.03125927323990798, "pitch": null, "roll": null}, "v": 2.3997675455794254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775772200071343, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01831982618167077, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.0390751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25211310355648864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3622832606541105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3985736037239125, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.0390751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.259192655593292, "y": -0.18474148063680662, "z": null, "yaw": 0.03125927323990798, "pitch": null, "roll": null}, "v": 2.3997675455794254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775772200071343, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01831982618167077, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.059075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25211310355648864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3622832606541105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3975390440065234, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.059075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.259192655593292, "y": -0.18474148063680662, "z": null, "yaw": 0.03125927323990798, "pitch": null, "roll": null}, "v": 2.3997675455794254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775772200071343, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01831982618167077, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.079075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25211310355648864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3622832606541105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3965065101221636, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.079075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.259192655593292, "y": -0.18474148063680662, "z": null, "yaw": 0.03125927323990798, "pitch": null, "roll": null}, "v": 2.3997675455794254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775772200071343, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01831982618167077, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.099075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25211310355648864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3622832606541105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.395475997677687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.099075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.259192655593292, "y": -0.18474148063680662, "z": null, "yaw": 0.03125927323990798, "pitch": null, "roll": null}, "v": 2.3997675455794254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775772200071343, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01831982618167077, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.119075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25211310355648864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3622832606541105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.393934009628063, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.119075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.129075, "x": 28.522735786790708, "y": 4.8236000202147595, "z": null, "yaw": 0.032099013273769156, "pitch": null, "roll": null}, "v": 2.393934009628063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3770059009059421, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01827529296642234, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.139075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24644835598948361, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4183336214891365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3925544849131293, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.139075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 24.522735786790708, "y": -0.17639997978524047, "z": null, "yaw": 0.032099013273769156, "pitch": null, "roll": null}, "v": 2.393934009628063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3770059009059421, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01827529296642234, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.149075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24819002479104013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4183336214891365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3908239585431637, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.149075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 24.522735786790708, "y": -0.17639997978524047, "z": null, "yaw": 0.032099013273769156, "pitch": null, "roll": null}, "v": 2.393934009628063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3770059009059421, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01827529296642234, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.179075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24819002479104013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4183336214891365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3893144184370527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.179075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 24.522735786790708, "y": -0.17639997978524047, "z": null, "yaw": 0.032099013273769156, "pitch": null, "roll": null}, "v": 2.393934009628063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3770059009059421, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01827529296642234, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.199075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24819002479104013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4183336214891365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.388560755438259, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.199075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 24.522735786790708, "y": -0.17639997978524047, "z": null, "yaw": 0.032099013273769156, "pitch": null, "roll": null}, "v": 2.393934009628063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3770059009059421, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01827529296642234, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.219075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24819002479104013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4183336214891365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.387055639373501, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.219075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.239075, "x": 28.78551244520974, "y": 4.832138130915861, "z": null, "yaw": 0.03293875330763033, "pitch": null, "roll": null}, "v": 2.385553464331664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37618632652843126, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018211315881049857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.239075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24796643653463657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4808879218706883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3848034776158196, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.239075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.78551244520974, "y": -0.16786186908413914, "z": null, "yaw": 0.03293875330763033, "pitch": null, "roll": null}, "v": 2.385553464331664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37618632652843126, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018211315881049857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.259075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24799532916483064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4808879218706883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3840402493977417, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.38306202037943926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.259075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.78551244520974, "y": -0.16786186908413914, "z": null, "yaw": 0.03293875330763033, "pitch": null, "roll": null}, "v": 2.385553464331664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37618632652843126, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018211315881049857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.279075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24799532916483064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4808879218706883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.381760446959782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.38306202037943926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.279075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.78551244520974, "y": -0.16786186908413914, "z": null, "yaw": 0.03293875330763033, "pitch": null, "roll": null}, "v": 2.385553464331664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37618632652843126, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018211315881049857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.299075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24799532916483064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4808879218706883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3810019965264337, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.38306202037943926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.299075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.78551244520974, "y": -0.16786186908413914, "z": null, "yaw": 0.03293875330763033, "pitch": null, "roll": null}, "v": 2.385553464331664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37618632652843126, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018211315881049857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.3190749} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24799532916483064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4808879218706883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.379487316193387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.38306202037943926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.3190749} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.78551244520974, "y": -0.16786186908413914, "z": null, "yaw": 0.03293875330763033, "pitch": null, "roll": null}, "v": 2.385553464331664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37618632652843126, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018211315881049857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.3390749} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24799532916483064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4808879218706883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3779755909924987, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.38306202037943926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.3390749} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.3490748, "x": 29.047361193182127, "y": 4.840859987916795, "z": null, "yaw": 0.033713095542334405, "pitch": null, "roll": null}, "v": 2.3772208344786687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3753728306827281, "steering_wheel_angle": 0.38306202037943926, "front_wheel_angle": 0.01768099402969328, "heading_rate": 0.016420315574571968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.3590748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393898467048497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5355169979005797, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3764668142446435, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.38306202037943926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.3590748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 25.047361193182127, "y": -0.15914001208320538, "z": null, "yaw": 0.033713095542334405, "pitch": null, "roll": null}, "v": 2.3772208344786687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3753728306827281, "steering_wheel_angle": 0.38306202037943926, "front_wheel_angle": 0.01768099402969328, "heading_rate": 0.016420315574571968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.3790748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24516591833712323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5355169979005797, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.374454183440521, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3026910460343449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.3790748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 25.047361193182127, "y": -0.15914001208320538, "z": null, "yaw": 0.033713095542334405, "pitch": null, "roll": null}, "v": 2.3772208344786687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3753728306827281, "steering_wheel_angle": 0.38306202037943926, "front_wheel_angle": 0.01768099402969328, "heading_rate": 0.016420315574571968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.3990748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24516591833712323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5355169979005797, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.372598767284351, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3026910460343449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.3990748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 25.047361193182127, "y": -0.15914001208320538, "z": null, "yaw": 0.033713095542334405, "pitch": null, "roll": null}, "v": 2.3772208344786687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3753728306827281, "steering_wheel_angle": 0.38306202037943926, "front_wheel_angle": 0.01768099402969328, "heading_rate": 0.016420315574571968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.4190748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24516591833712323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5355169979005797, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3707469659895923, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3026910460343449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.4190748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 25.047361193182127, "y": -0.15914001208320538, "z": null, "yaw": 0.033713095542334405, "pitch": null, "roll": null}, "v": 2.3772208344786687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3753728306827281, "steering_wheel_angle": 0.38306202037943926, "front_wheel_angle": 0.01768099402969328, "heading_rate": 0.016420315574571968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.4390748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24516591833712323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5355169979005797, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.367976023514207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3026910460343449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.4390748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.4590747, "x": 29.308198643252975, "y": 4.8497360329938, "z": null, "yaw": 0.034349205762641145, "pitch": null, "roll": null}, "v": 2.3670541743537266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743821633609404, "steering_wheel_angle": 0.3026910460343449, "front_wheel_angle": 0.01395640901180994, "heading_rate": 0.012905359875882495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.4590747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23908296813808233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5911006262830726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3670541743537266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3026910460343449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.4590747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.308198643252975, "y": -0.15026396700620026, "z": null, "yaw": 0.034349205762641145, "pitch": null, "roll": null}, "v": 2.3670541743537266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743821633609404, "steering_wheel_angle": 0.3026910460343449, "front_wheel_angle": 0.01395640901180994, "heading_rate": 0.012905359875882495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.4790747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093435792305895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5911006262830726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3620885329748877, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2623805324665846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.4790747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.308198643252975, "y": -0.15026396700620026, "z": null, "yaw": 0.034349205762641145, "pitch": null, "roll": null}, "v": 2.3670541743537266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743821633609404, "steering_wheel_angle": 0.3026910460343449, "front_wheel_angle": 0.01395640901180994, "heading_rate": 0.012905359875882495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.4990747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093435792305895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5911006262830726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3620885329748877, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2623805324665846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.4990747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.308198643252975, "y": -0.15026396700620026, "z": null, "yaw": 0.034349205762641145, "pitch": null, "roll": null}, "v": 2.3670541743537266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743821633609404, "steering_wheel_angle": 0.3026910460343449, "front_wheel_angle": 0.01395640901180994, "heading_rate": 0.012905359875882495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.5190747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093435792305895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5911006262830726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.359728494625047, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2623805324665846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.5190747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.308198643252975, "y": -0.15026396700620026, "z": null, "yaw": 0.034349205762641145, "pitch": null, "roll": null}, "v": 2.3670541743537266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743821633609404, "steering_wheel_angle": 0.3026910460343449, "front_wheel_angle": 0.01395640901180994, "heading_rate": 0.012905359875882495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.5390747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093435792305895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5911006262830726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3573730422606833, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2623805324665846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.5390747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.308198643252975, "y": -0.15026396700620026, "z": null, "yaw": 0.034349205762641145, "pitch": null, "roll": null}, "v": 2.3670541743537266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743821633609404, "steering_wheel_angle": 0.3026910460343449, "front_wheel_angle": 0.01395640901180994, "heading_rate": 0.012905359875882495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.5590746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093435792305895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5911006262830726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.355022164752203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2623805324665846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.5590746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.5690746, "x": 29.567747256830724, "y": 4.858717859015007, "z": null, "yaw": 0.03487606685398633, "pitch": null, "roll": null}, "v": 2.353848438100371, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3730984466004941, "steering_wheel_angle": 0.2623805324665846, "front_wheel_angle": 0.0120913231299291, "heading_rate": 0.011118175450114204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.5790746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24238931045796372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6594204436138558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.352675851004557, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2623805324665846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.5790746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 25.567747256830724, "y": -0.14128214098499292, "z": null, "yaw": 0.03487606685398633, "pitch": null, "roll": null}, "v": 2.353848438100371, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3730984466004941, "steering_wheel_angle": 0.2623805324665846, "front_wheel_angle": 0.0120913231299291, "heading_rate": 0.011118175450114204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.5990746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418704516125933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6594204436138558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.350515870789282, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.18148031453007718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.5990746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 25.567747256830724, "y": -0.14128214098499292, "z": null, "yaw": 0.03487606685398633, "pitch": null, "roll": null}, "v": 2.353848438100371, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3730984466004941, "steering_wheel_angle": 0.2623805324665846, "front_wheel_angle": 0.0120913231299291, "heading_rate": 0.011118175450114204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.6190746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418704516125933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6594204436138558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3482952539112927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.18148031453007718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.6190746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 25.567747256830724, "y": -0.14128214098499292, "z": null, "yaw": 0.03487606685398633, "pitch": null, "roll": null}, "v": 2.353848438100371, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3730984466004941, "steering_wheel_angle": 0.2623805324665846, "front_wheel_angle": 0.0120913231299291, "heading_rate": 0.011118175450114204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.6390746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418704516125933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6594204436138558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3460789419207764, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.18148031453007718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.6390746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 25.567747256830724, "y": -0.14128214098499292, "z": null, "yaw": 0.03487606685398633, "pitch": null, "roll": null}, "v": 2.353848438100371, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3730984466004941, "steering_wheel_angle": 0.2623805324665846, "front_wheel_angle": 0.0120913231299291, "heading_rate": 0.011118175450114204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.6590745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418704516125933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6594204436138558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.343866924508414, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.18148031453007718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.6590745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.6790745, "x": 29.825900456715573, "y": 4.867774901671174, "z": null, "yaw": 0.03527154545501697, "pitch": null, "roll": null}, "v": 2.341659191396282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37191663725632096, "steering_wheel_angle": 0.18148031453007718, "front_wheel_angle": 0.00835424993395996, "heading_rate": 0.007641898936186072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.6790745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23983865750857716, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7218832841614157, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.341659191396282, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.18148031453007718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.6790745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.825900456715573, "y": -0.132225098328826, "z": null, "yaw": 0.03527154545501697, "pitch": null, "roll": null}, "v": 2.341659191396282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37191663725632096, "steering_wheel_angle": 0.18148031453007718, "front_wheel_angle": 0.00835424993395996, "heading_rate": 0.007641898936186072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.6990745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404145030764273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7218832841614157, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3392018810108035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14089634271035242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.6990745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.825900456715573, "y": -0.132225098328826, "z": null, "yaw": 0.03527154545501697, "pitch": null, "roll": null}, "v": 2.341659191396282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37191663725632096, "steering_wheel_angle": 0.18148031453007718, "front_wheel_angle": 0.00835424993395996, "heading_rate": 0.007641898936186072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.7190745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404145030764273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7218832841614157, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.336821271367257, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14089634271035242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.7190745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.825900456715573, "y": -0.132225098328826, "z": null, "yaw": 0.03527154545501697, "pitch": null, "roll": null}, "v": 2.341659191396282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37191663725632096, "steering_wheel_angle": 0.18148031453007718, "front_wheel_angle": 0.00835424993395996, "heading_rate": 0.007641898936186072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.7390745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404145030764273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7218832841614157, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3344452658957526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14089634271035242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.7390745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.825900456715573, "y": -0.132225098328826, "z": null, "yaw": 0.03527154545501697, "pitch": null, "roll": null}, "v": 2.341659191396282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37191663725632096, "steering_wheel_angle": 0.18148031453007718, "front_wheel_angle": 0.00835424993395996, "heading_rate": 0.007641898936186072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.7590744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404145030764273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7218832841614157, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3320738534346095, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14089634271035242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.7590744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.825900456715573, "y": -0.132225098328826, "z": null, "yaw": 0.03527154545501697, "pitch": null, "roll": null}, "v": 2.341659191396282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37191663725632096, "steering_wheel_angle": 0.18148031453007718, "front_wheel_angle": 0.00835424993395996, "heading_rate": 0.007641898936186072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.7790744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404145030764273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7218832841614157, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.329707022856815, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14089634271035242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.7790744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.7890744, "x": 30.082660758141525, "y": 4.876869217002136, "z": null, "yaw": 0.035557407832536796, "pitch": null, "roll": null}, "v": 2.3285253223064286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370646567881544, "steering_wheel_angle": 0.14089634271035242, "front_wheel_angle": 0.006482541627269961, "heading_rate": 0.005896474132694437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.7990744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22943087960732184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7538579894088178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.32734476306989, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14089634271035242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.7990744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 26.082660758141525, "y": -0.12313078299786362, "z": null, "yaw": 0.035557407832536796, "pitch": null, "roll": null}, "v": 2.3285253223064286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370646567881544, "steering_wheel_angle": 0.14089634271035242, "front_wheel_angle": 0.006482541627269961, "heading_rate": 0.005896474132694437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.8190744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23279976068148903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7538579894088178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3236147726447762, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1002334571097898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.8190744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 26.082660758141525, "y": -0.12313078299786362, "z": null, "yaw": 0.035557407832536796, "pitch": null, "roll": null}, "v": 2.3285253223064286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370646567881544, "steering_wheel_angle": 0.14089634271035242, "front_wheel_angle": 0.006482541627269961, "heading_rate": 0.005896474132694437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.8390744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23279976068148903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7538579894088178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.320312884034528, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1002334571097898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.8390744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 26.082660758141525, "y": -0.12313078299786362, "z": null, "yaw": 0.035557407832536796, "pitch": null, "roll": null}, "v": 2.3285253223064286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370646567881544, "steering_wheel_angle": 0.14089634271035242, "front_wheel_angle": 0.006482541627269961, "heading_rate": 0.005896474132694437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.8590744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23279976068148903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7538579894088178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3170173598996544, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1002334571097898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.8590744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 26.082660758141525, "y": -0.12313078299786362, "z": null, "yaw": 0.035557407832536796, "pitch": null, "roll": null}, "v": 2.3285253223064286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370646567881544, "steering_wheel_angle": 0.14089634271035242, "front_wheel_angle": 0.006482541627269961, "heading_rate": 0.005896474132694437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.8790743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23279976068148903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7538579894088178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.313728183630363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1002334571097898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.8790743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.8990743, "x": 30.337739563265007, "y": 4.885969168449787, "z": null, "yaw": 0.0357700968551492, "pitch": null, "roll": null}, "v": 2.310445338673953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36890384356369965, "steering_wheel_angle": 0.1002334571097898, "front_wheel_angle": 0.004609203461379754, "heading_rate": 0.004159917213673361, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.8990743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2346995491562875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8126228432467358, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.310445338673953, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1002334571097898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.8990743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.337739563265007, "y": -0.11403083155021321, "z": null, "yaw": 0.0357700968551492, "pitch": null, "roll": null}, "v": 2.310445338673953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36890384356369965, "steering_wheel_angle": 0.1002334571097898, "front_wheel_angle": 0.004609203461379754, "heading_rate": 0.004159917213673361, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.9190743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23401872859564002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8126228432467358, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.307406167896072, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018646035287163226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.9190743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.337739563265007, "y": -0.11403083155021321, "z": null, "yaw": 0.0357700968551492, "pitch": null, "roll": null}, "v": 2.310445338673953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36890384356369965, "steering_wheel_angle": 0.1002334571097898, "front_wheel_angle": 0.004609203461379754, "heading_rate": 0.004159917213673361, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.9390743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23401872859564002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8126228432467358, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3042877777722763, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018646035287163226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.9390743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.337739563265007, "y": -0.11403083155021321, "z": null, "yaw": 0.0357700968551492, "pitch": null, "roll": null}, "v": 2.310445338673953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36890384356369965, "steering_wheel_angle": 0.1002334571097898, "front_wheel_angle": 0.004609203461379754, "heading_rate": 0.004159917213673361, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.9590743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23401872859564002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8126228432467358, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3011753783988267, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018646035287163226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.9590743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.337739563265007, "y": -0.11403083155021321, "z": null, "yaw": 0.0357700968551492, "pitch": null, "roll": null}, "v": 2.310445338673953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36890384356369965, "steering_wheel_angle": 0.1002334571097898, "front_wheel_angle": 0.004609203461379754, "heading_rate": 0.004159917213673361, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.9790742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23401872859564002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8126228432467358, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.298068954393918, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018646035287163226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.9790742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.337739563265007, "y": -0.11403083155021321, "z": null, "yaw": 0.0357700968551492, "pitch": null, "roll": null}, "v": 2.310445338673953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36890384356369965, "steering_wheel_angle": 0.1002334571097898, "front_wheel_angle": 0.004609203461379754, "heading_rate": 0.004159917213673361, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.9990742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23401872859564002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8126228432467358, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.294968490427586, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018646035287163226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.9990742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.0090742, "x": 30.59087714125104, "y": 4.895036917933571, "z": null, "yaw": 0.03582888876619402, "pitch": null, "roll": null}, "v": 2.2934204886823943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3672687998132017, "steering_wheel_angle": 0.018646035287163226, "front_wheel_angle": 0.0008565139690646242, "heading_rate": 0.0007673231116619004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.0190742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23458828703352483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8553004495516543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2918739712214897, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018646035287163226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.0190742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 26.59087714125104, "y": -0.1049630820664289, "z": null, "yaw": 0.03582888876619402, "pitch": null, "roll": null}, "v": 2.2934204886823943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3672687998132017, "steering_wheel_angle": 0.018646035287163226, "front_wheel_angle": 0.0008565139690646242, "heading_rate": 0.0007673231116619004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.0390742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23432854766386252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8553004495516543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.288856542248648, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.0390742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 26.59087714125104, "y": -0.1049630820664289, "z": null, "yaw": 0.03582888876619402, "pitch": null, "roll": null}, "v": 2.2934204886823943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3672687998132017, "steering_wheel_angle": 0.018646035287163226, "front_wheel_angle": 0.0008565139690646242, "heading_rate": 0.0007673231116619004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.0590742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23432854766386252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8553004495516543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.28581243955374, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.0590742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 26.59087714125104, "y": -0.1049630820664289, "z": null, "yaw": 0.03582888876619402, "pitch": null, "roll": null}, "v": 2.2934204886823943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3672687998132017, "steering_wheel_angle": 0.018646035287163226, "front_wheel_angle": 0.0008565139690646242, "heading_rate": 0.0007673231116619004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.0790741} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23432854766386252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8553004495516543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2827741623979767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.0790741} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 26.59087714125104, "y": -0.1049630820664289, "z": null, "yaw": 0.03582888876619402, "pitch": null, "roll": null}, "v": 2.2934204886823943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3672687998132017, "steering_wheel_angle": 0.018646035287163226, "front_wheel_angle": 0.0008565139690646242, "heading_rate": 0.0007673231116619004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.0990741} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23432854766386252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8553004495516543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2797416959422607, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.0990741} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.119074, "x": 30.84215538640039, "y": 4.904041964420242, "z": null, "yaw": 0.03579964976111607, "pitch": null, "roll": null}, "v": 2.2767150253970527, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36567006433853966, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009089284392223138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.129074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23094750708295017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8523774919155308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2752038589826586, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.129074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.84215538640039, "y": -0.09595803557975824, "z": null, "yaw": 0.03579964976111607, "pitch": null, "roll": null}, "v": 2.2767150253970527, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36567006433853966, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009089284392223138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.129074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.84215538640039, "y": -0.09595803557975824, "z": null, "yaw": 0.03579964976111607, "pitch": null, "roll": null}, "v": 2.2767150253970527, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36567006433853966, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009089284392223138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.149074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23192414613108664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8523774919155308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2718854479603414, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.149074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.84215538640039, "y": -0.09595803557975824, "z": null, "yaw": 0.03579964976111607, "pitch": null, "roll": null}, "v": 2.2767150253970527, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36567006433853966, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009089284392223138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.169074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23192414613108664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8523774919155308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2685733690470635, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.169074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.84215538640039, "y": -0.09595803557975824, "z": null, "yaw": 0.03579964976111607, "pitch": null, "roll": null}, "v": 2.2767150253970527, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36567006433853966, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009089284392223138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.189074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23192414613108664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8523774919155308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2652676057741963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.189074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.84215538640039, "y": -0.09595803557975824, "z": null, "yaw": 0.03579964976111607, "pitch": null, "roll": null}, "v": 2.2767150253970527, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36567006433853966, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009089284392223138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.209074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23192414613108664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8523774919155308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.261968141729608, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.209074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.229074, "x": 31.091538107593223, "y": 4.912968617288109, "z": null, "yaw": 0.03575573467855233, "pitch": null, "roll": null}, "v": 2.2586749605574217, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3639498738023618, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009017263397960603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.229074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23374662829546075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8888953691604239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2586749605574217, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.229074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.091538107593223, "y": -0.08703138271189115, "z": null, "yaw": 0.03575573467855233, "pitch": null, "roll": null}, "v": 2.2586749605574217, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3639498738023618, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009017263397960603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.249074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2330910926624823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8888953691604239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.255615747856979, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06314509513433528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.249074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.091538107593223, "y": -0.08703138271189115, "z": null, "yaw": 0.03575573467855233, "pitch": null, "roll": null}, "v": 2.2586749605574217, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3639498738023618, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009017263397960603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.269074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2330910926624823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8888953691604239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2524804497021735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06314509513433528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.269074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.091538107593223, "y": -0.08703138271189115, "z": null, "yaw": 0.03575573467855233, "pitch": null, "roll": null}, "v": 2.2586749605574217, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3639498738023618, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009017263397960603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.289074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2330910926624823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8888953691604239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2493511098746213, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06314509513433528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.289074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.091538107593223, "y": -0.08703138271189115, "z": null, "yaw": 0.03575573467855233, "pitch": null, "roll": null}, "v": 2.2586749605574217, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3639498738023618, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009017263397960603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.309074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2330910926624823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8888953691604239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2462277131358555, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06314509513433528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.309074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.091538107593223, "y": -0.08703138271189115, "z": null, "yaw": 0.03575573467855233, "pitch": null, "roll": null}, "v": 2.2586749605574217, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3639498738023618, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009017263397960603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.329074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2330910926624823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8888953691604239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.241553728111109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06314509513433528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.329074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.339074, "x": 31.338980532388167, "y": 4.9218075041989255, "z": null, "yaw": 0.035638371293744635, "pitch": null, "roll": null}, "v": 2.241553728111109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36232331756564357, "steering_wheel_angle": -0.06314509513433528, "front_wheel_angle": -0.0029022921281251597, "heading_rate": -0.0025412742211940566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.349074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372700101387549, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9651153917644871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2399986882268577, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06314509513433528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.349074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 27.338980532388167, "y": -0.07819249580107446, "z": null, "yaw": 0.035638371293744635, "pitch": null, "roll": null}, "v": 2.241553728111109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36232331756564357, "steering_wheel_angle": -0.06314509513433528, "front_wheel_angle": -0.0029022921281251597, "heading_rate": -0.0025412742211940566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.3690739} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2358827697060381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9651153917644871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2374151469931594, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14497858869563646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.3690739} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 27.338980532388167, "y": -0.07819249580107446, "z": null, "yaw": 0.035638371293744635, "pitch": null, "roll": null}, "v": 2.241553728111109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36232331756564357, "steering_wheel_angle": -0.06314509513433528, "front_wheel_angle": -0.0029022921281251597, "heading_rate": -0.0025412742211940566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.3890738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2358827697060381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9651153917644871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.233289146468975, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14497858869563646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.3890738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 27.338980532388167, "y": -0.07819249580107446, "z": null, "yaw": 0.035638371293744635, "pitch": null, "roll": null}, "v": 2.241553728111109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36232331756564357, "steering_wheel_angle": -0.06314509513433528, "front_wheel_angle": -0.0029022921281251597, "heading_rate": -0.0025412742211940566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.4090738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2358827697060381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9651153917644871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.231916416961194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14497858869563646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.4090738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 27.338980532388167, "y": -0.07819249580107446, "z": null, "yaw": 0.035638371293744635, "pitch": null, "roll": null}, "v": 2.241553728111109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36232331756564357, "steering_wheel_angle": -0.06314509513433528, "front_wheel_angle": -0.0029022921281251597, "heading_rate": -0.0025412742211940566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.4290738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2358827697060381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9651153917644871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.227806017915935, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14497858869563646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.4290738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.4490738, "x": 31.58463638556982, "y": 4.930541546102588, "z": null, "yaw": 0.035388536495359654, "pitch": null, "roll": null}, "v": 2.2264384760482585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3608922066786938, "steering_wheel_angle": -0.14497858869563646, "front_wheel_angle": -0.0066707216039725015, "heading_rate": -0.005801629508852215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.4490738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23990853577486512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0464766659494806, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2264384760482585, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14497858869563646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.4490738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 27.58463638556982, "y": -0.06945845389741212, "z": null, "yaw": 0.035388536495359654, "pitch": null, "roll": null}, "v": 2.2264384760482585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3608922066786938, "steering_wheel_angle": -0.14497858869563646, "front_wheel_angle": -0.0066707216039725015, "heading_rate": -0.005801629508852215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.4690738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23857892746225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0464766659494806, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.224210252416436, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2268192194304395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.4690738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 27.58463638556982, "y": -0.06945845389741212, "z": null, "yaw": 0.035388536495359654, "pitch": null, "roll": null}, "v": 2.2264384760482585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3608922066786938, "steering_wheel_angle": -0.14497858869563646, "front_wheel_angle": -0.0066707216039725015, "heading_rate": -0.005801629508852215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.4890738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23857892746225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0464766659494806, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.218243367894741, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2268192194304395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.4890738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 27.58463638556982, "y": -0.06945845389741212, "z": null, "yaw": 0.035388536495359654, "pitch": null, "roll": null}, "v": 2.2264384760482585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3608922066786938, "steering_wheel_angle": -0.14497858869563646, "front_wheel_angle": -0.0066707216039725015, "heading_rate": -0.005801629508852215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.5190737} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23857892746225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0464766659494806, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2170533688132634, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2268192194304395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.5190737} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 27.58463638556982, "y": -0.06945845389741212, "z": null, "yaw": 0.035388536495359654, "pitch": null, "roll": null}, "v": 2.2264384760482585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3608922066786938, "steering_wheel_angle": -0.14497858869563646, "front_wheel_angle": -0.0066707216039725015, "heading_rate": -0.005801629508852215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.5490737} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23857892746225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0464766659494806, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2134901029987133, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2268192194304395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.5490737} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.5590737, "x": 31.828752100396937, "y": 4.939138980365528, "z": null, "yaw": 0.03496173063127122, "pitch": null, "roll": null}, "v": 2.2134901029987133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3596698895106682, "steering_wheel_angle": -0.2268192194304395, "front_wheel_angle": -0.010447630475150904, "heading_rate": -0.009033815666908487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.5690737} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24261774015171667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1304861721591302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.212304587069997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2268192194304395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.5690737} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 27.828752100396937, "y": -0.06086101963447188, "z": null, "yaw": 0.03496173063127122, "pitch": null, "roll": null}, "v": 2.2134901029987133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3596698895106682, "steering_wheel_angle": -0.2268192194304395, "front_wheel_angle": -0.010447630475150904, "heading_rate": -0.009033815666908487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.5890737} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24129449446026957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1304861721591302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.208416634048157, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.5890737} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 27.828752100396937, "y": -0.06086101963447188, "z": null, "yaw": 0.03496173063127122, "pitch": null, "roll": null}, "v": 2.2134901029987133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3596698895106682, "steering_wheel_angle": -0.2268192194304395, "front_wheel_angle": -0.010447630475150904, "heading_rate": -0.009033815666908487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.6090736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24129449446026957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1304861721591302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.208416634048157, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.6090736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 27.828752100396937, "y": -0.06086101963447188, "z": null, "yaw": 0.03496173063127122, "pitch": null, "roll": null}, "v": 2.2134901029987133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3596698895106682, "steering_wheel_angle": -0.2268192194304395, "front_wheel_angle": -0.010447630475150904, "heading_rate": -0.009033815666908487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.6390736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24129449446026957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1304861721591302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.20337107848732, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.6390736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 27.828752100396937, "y": -0.06086101963447188, "z": null, "yaw": 0.03496173063127122, "pitch": null, "roll": null}, "v": 2.2134901029987133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3596698895106682, "steering_wheel_angle": -0.2268192194304395, "front_wheel_angle": -0.010447630475150904, "heading_rate": -0.009033815666908487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.6590736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24129449446026957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1304861721591302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.20337107848732, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.6590736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.6690736, "x": 32.0715296456771, "y": 4.947570361488407, "z": null, "yaw": 0.034387075665919024, "pitch": null, "roll": null}, "v": 2.202364814440892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35862234848091723, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012245764625586885, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.6890736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24044630301081726, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1038620413109053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2003551246517445, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.6890736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 28.071529645677103, "y": -0.05242963851159299, "z": null, "yaw": 0.034387075665919024, "pitch": null, "roll": null}, "v": 2.202364814440892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35862234848091723, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012245764625586885, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.6990736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24065898592672935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1038620413109053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.199298684760137, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.6990736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 28.071529645677103, "y": -0.05242963851159299, "z": null, "yaw": 0.034387075665919024, "pitch": null, "roll": null}, "v": 2.202364814440892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35862234848091723, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012245764625586885, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.7190735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24065898592672935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1038620413109053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1972153557454166, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.7190735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 28.071529645677103, "y": -0.05242963851159299, "z": null, "yaw": 0.034387075665919024, "pitch": null, "roll": null}, "v": 2.202364814440892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35862234848091723, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012245764625586885, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.7390735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24065898592672935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1038620413109053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1940976961351137, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.7390735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 28.071529645677103, "y": -0.05242963851159299, "z": null, "yaw": 0.034387075665919024, "pitch": null, "roll": null}, "v": 2.202364814440892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35862234848091723, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012245764625586885, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.7590735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24065898592672935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1038620413109053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.193060427437448, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.7590735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.7790735, "x": 32.31308249056445, "y": 4.9558127625440465, "z": null, "yaw": 0.033775444886139885, "pitch": null, "roll": null}, "v": 2.190988810014791, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3575537601568399, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012182510857787736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.7790735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2399176657521917, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0706804667169607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.190988810014791, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.7790735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.313082490564447, "y": -0.04418723745595354, "z": null, "yaw": 0.033775444886139885, "pitch": null, "roll": null}, "v": 2.190988810014791, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3575537601568399, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012182510857787736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.7990735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24009589900738967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0706804667169607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1888284568087246, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.7990735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.313082490564447, "y": -0.04418723745595354, "z": null, "yaw": 0.033775444886139885, "pitch": null, "roll": null}, "v": 2.190988810014791, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3575537601568399, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012182510857787736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.8190734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24009589900738967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0706804667169607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.186694422692539, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.8190734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.313082490564447, "y": -0.04418723745595354, "z": null, "yaw": 0.033775444886139885, "pitch": null, "roll": null}, "v": 2.190988810014791, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3575537601568399, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012182510857787736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.8390734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24009589900738967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0706804667169607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.184564387782894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.8390734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.313082490564447, "y": -0.04418723745595354, "z": null, "yaw": 0.033775444886139885, "pitch": null, "roll": null}, "v": 2.190988810014791, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3575537601568399, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012182510857787736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.8590734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24009589900738967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0706804667169607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.182438342771258, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.8590734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.313082490564447, "y": -0.04418723745595354, "z": null, "yaw": 0.033775444886139885, "pitch": null, "roll": null}, "v": 2.190988810014791, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3575537601568399, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012182510857787736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.8790734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24009589900738967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0706804667169607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1792567360181256, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.8790734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.8890734, "x": 32.553367675768996, "y": 4.963864776056965, "z": null, "yaw": 0.033163814106360746, "pitch": null, "roll": null}, "v": 2.1792567360181256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35645443601571003, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012117277243542219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.8990734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24396543562785994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.142299607521185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1781981853459302, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.8990734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 28.553367675768996, "y": -0.03613522394303459, "z": null, "yaw": 0.033163814106360746, "pitch": null, "roll": null}, "v": 2.1792567360181256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35645443601571003, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012117277243542219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.9190733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427012383980342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.142299607521185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.176567520295043, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.9190733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 28.553367675768996, "y": -0.03613522394303459, "z": null, "yaw": 0.033163814106360746, "pitch": null, "roll": null}, "v": 2.1792567360181256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35645443601571003, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012117277243542219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.9390733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427012383980342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.142299607521185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1747819536835764, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.9390733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 28.553367675768996, "y": -0.03613522394303459, "z": null, "yaw": 0.033163814106360746, "pitch": null, "roll": null}, "v": 2.1792567360181256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35645443601571003, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012117277243542219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.9590733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427012383980342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.142299607521185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1729997246837733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.9590733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 28.553367675768996, "y": -0.03613522394303459, "z": null, "yaw": 0.033163814106360746, "pitch": null, "roll": null}, "v": 2.1792567360181256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35645443601571003, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012117277243542219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.9790733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427012383980342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.142299607521185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1712208257869694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.9790733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.9990733, "x": 32.79246247079454, "y": 4.97173048951879, "z": null, "yaw": 0.03255218332658161, "pitch": null, "roll": null}, "v": 2.1694452495056504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35553718938130885, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012062722633120242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.9990733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24142636323639471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1078380073892418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1694452495056504, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.9990733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.79246247079454, "y": -0.02826951048121007, "z": null, "yaw": 0.03255218332658161, "pitch": null, "roll": null}, "v": 2.1694452495056504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35553718938130885, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012062722633120242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.0190732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24177889962382787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1078380073892418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1675137033754073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.0190732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.79246247079454, "y": -0.02826951048121007, "z": null, "yaw": 0.03255218332658161, "pitch": null, "roll": null}, "v": 2.1694452495056504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35553718938130885, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012062722633120242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.0390732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24177889962382787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1078380073892418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1656298086263623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.0390732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.79246247079454, "y": -0.02826951048121007, "z": null, "yaw": 0.03255218332658161, "pitch": null, "roll": null}, "v": 2.1694452495056504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35553718938130885, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012062722633120242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.0590732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24177889962382787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1078380073892418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1637494284139036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.0590732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.79246247079454, "y": -0.02826951048121007, "z": null, "yaw": 0.03255218332658161, "pitch": null, "roll": null}, "v": 2.1694452495056504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35553718938130885, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012062722633120242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.0790732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24177889962382787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1078380073892418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1618725547677466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.0790732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.79246247079454, "y": -0.02826951048121007, "z": null, "yaw": 0.03255218332658161, "pitch": null, "roll": null}, "v": 2.1694452495056504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35553718938130885, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012062722633120242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.0990732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24177889962382787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1078380073892418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1599991797403786, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.0990732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.1090732, "x": 33.030455416387014, "y": 4.979414239872165, "z": null, "yaw": 0.03194055254680247, "pitch": null, "roll": null}, "v": 2.15906380173135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545687550860338, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012004998878598136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.1190732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2453101476203484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1814088138247745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1581292954069786, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.1190732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 29.030455416387014, "y": -0.020585760127834973, "z": null, "yaw": 0.03194055254680247, "pitch": null, "roll": null}, "v": 2.15906380173135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545687550860338, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012004998878598136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.1390731} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441582101514029, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1814088138247745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1567040942886204, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34959118768706327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.1390731} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 29.030455416387014, "y": -0.020585760127834973, "z": null, "yaw": 0.03194055254680247, "pitch": null, "roll": null}, "v": 2.15906380173135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545687550860338, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012004998878598136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.159073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441582101514029, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1814088138247745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.155137621691543, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34959118768706327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.159073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 29.030455416387014, "y": -0.020585760127834973, "z": null, "yaw": 0.03194055254680247, "pitch": null, "roll": null}, "v": 2.15906380173135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545687550860338, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012004998878598136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.179073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441582101514029, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1814088138247745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.153574064840105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34959118768706327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.179073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 29.030455416387014, "y": -0.020585760127834973, "z": null, "yaw": 0.03194055254680247, "pitch": null, "roll": null}, "v": 2.15906380173135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545687550860338, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012004998878598136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.199073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441582101514029, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1814088138247745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.152013417329669, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34959118768706327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.199073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.219073, "x": 33.267400193838746, "y": 4.986913325115141, "z": null, "yaw": 0.031262265984093325, "pitch": null, "roll": null}, "v": 2.1504556727729724, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35376737964426325, "steering_wheel_angle": -0.34959118768706327, "front_wheel_angle": -0.016128904298900893, "heading_rate": -0.013549805345395707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.219073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2473615911292718, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2607850755094827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1504556727729724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34959118768706327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.219073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.267400193838746, "y": -0.013086674884858596, "z": null, "yaw": 0.031262265984093325, "pitch": null, "roll": null}, "v": 2.1504556727729724, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35376737964426325, "steering_wheel_angle": -0.34959118768706327, "front_wheel_angle": -0.016128904298900893, "heading_rate": -0.013549805345395707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.239073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632046511898384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2607850755094827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1486594902688068, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.239073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.267400193838746, "y": -0.013086674884858596, "z": null, "yaw": 0.031262265984093325, "pitch": null, "roll": null}, "v": 2.1504556727729724, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35376737964426325, "steering_wheel_angle": -0.34959118768706327, "front_wheel_angle": -0.016128904298900893, "heading_rate": -0.013549805345395707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.259073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632046511898384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2607850755094827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1480185158330967, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.259073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.267400193838746, "y": -0.013086674884858596, "z": null, "yaw": 0.031262265984093325, "pitch": null, "roll": null}, "v": 2.1504556727729724, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35376737964426325, "steering_wheel_angle": -0.34959118768706327, "front_wheel_angle": -0.016128904298900893, "heading_rate": -0.013549805345395707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.279073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632046511898384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2607850755094827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.146099165342398, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.279073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.267400193838746, "y": -0.013086674884858596, "z": null, "yaw": 0.031262265984093325, "pitch": null, "roll": null}, "v": 2.1504556727729724, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35376737964426325, "steering_wheel_angle": -0.34959118768706327, "front_wheel_angle": -0.016128904298900893, "heading_rate": -0.013549805345395707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.299073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632046511898384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2607850755094827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.145460570666915, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.299073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.267400193838746, "y": -0.013086674884858596, "z": null, "yaw": 0.031262265984093325, "pitch": null, "roll": null}, "v": 2.1504556727729724, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35376737964426325, "steering_wheel_angle": -0.34959118768706327, "front_wheel_angle": -0.016128904298900893, "heading_rate": -0.013549805345395707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.319073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632046511898384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2607850755094827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.144185160745356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.319073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.329073, "x": 33.50349744868285, "y": 4.994209347695843, "z": null, "yaw": 0.030428123429082722, "pitch": null, "roll": null}, "v": 2.1435483442345635, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3531254122524356, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.016688749402990283, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.339073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24579733643905552, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2302523090001514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1429121191819758, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.339073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 29.50349744868285, "y": -0.0057906523041566516, "z": null, "yaw": 0.030428123429082722, "pitch": null, "roll": null}, "v": 2.1435483442345635, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3531254122524356, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.016688749402990283, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.359073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2459287158680808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2302523090001514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.141576080202177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.359073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 29.50349744868285, "y": -0.0057906523041566516, "z": null, "yaw": 0.030428123429082722, "pitch": null, "roll": null}, "v": 2.1435483442345635, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3531254122524356, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.016688749402990283, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.379073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2459287158680808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2302523090001514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1402589355871884, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.379073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 29.50349744868285, "y": -0.0057906523041566516, "z": null, "yaw": 0.030428123429082722, "pitch": null, "roll": null}, "v": 2.1435483442345635, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3531254122524356, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.016688749402990283, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.399073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2459287158680808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2302523090001514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.138944234768003, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.399073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 29.50349744868285, "y": -0.0057906523041566516, "z": null, "yaw": 0.030428123429082722, "pitch": null, "roll": null}, "v": 2.1435483442345635, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3531254122524356, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.016688749402990283, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.4190729} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2459287158680808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2302523090001514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.137631972519412, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.4190729} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.4390728, "x": 33.738820215381054, "y": 5.0012803550960765, "z": null, "yaw": 0.02957171053815513, "pitch": null, "roll": null}, "v": 2.1363221436297417, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35245483019511487, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.01663248929980485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.4390728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.249332681366634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3138341146792594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.135440041337928, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.4390728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 29.738820215381054, "y": 0.001280355096076491, "z": null, "yaw": 0.02957171053815513, "pitch": null, "roll": null}, "v": 2.1363221436297417, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35245483019511487, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.01663248929980485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.4590728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24823541232604446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3138341146792594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.135440041337928, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.4590728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 29.738820215381054, "y": 0.001280355096076491, "z": null, "yaw": 0.02957171053815513, "pitch": null, "roll": null}, "v": 2.1363221436297417, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35245483019511487, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.01663248929980485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.4790728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24823541232604446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3138341146792594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133406801979329, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.4790728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 29.738820215381054, "y": 0.001280355096076491, "z": null, "yaw": 0.02957171053815513, "pitch": null, "roll": null}, "v": 2.1363221436297417, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35245483019511487, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.01663248929980485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.4990728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24823541232604446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3138341146792594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.132899669390444, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.4990728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 29.738820215381054, "y": 0.001280355096076491, "z": null, "yaw": 0.02957171053815513, "pitch": null, "roll": null}, "v": 2.1363221436297417, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35245483019511487, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.01663248929980485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.5290728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24823541232604446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3138341146792594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131886813499659, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.5290728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.5490727, "x": 33.97344925528266, "y": 5.008122249336927, "z": null, "yaw": 0.028640945272488866, "pitch": null, "roll": null}, "v": 2.1308758334157445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35195010984513964, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018174443445816108, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.5490727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24306865107983722, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1336334305696467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1308758334157445, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.5490727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 29.97344925528266, "y": 0.00812224933692729, "z": null, "yaw": 0.028640945272488866, "pitch": null, "roll": null}, "v": 2.1308758334157445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35195010984513964, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018174443445816108, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.5690727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465802899385558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1336334305696467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.129221179140134, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.5690727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 29.97344925528266, "y": 0.00812224933692729, "z": null, "yaw": 0.028640945272488866, "pitch": null, "roll": null}, "v": 2.1308758334157445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35195010984513964, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018174443445816108, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.5890727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465802899385558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1336334305696467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127768167908988, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.5890727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 29.97344925528266, "y": 0.00812224933692729, "z": null, "yaw": 0.028640945272488866, "pitch": null, "roll": null}, "v": 2.1308758334157445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35195010984513964, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018174443445816108, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.6090727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465802899385558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1336334305696467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1263178453237965, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.6090727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 29.97344925528266, "y": 0.00812224933692729, "z": null, "yaw": 0.028640945272488866, "pitch": null, "roll": null}, "v": 2.1308758334157445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35195010984513964, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018174443445816108, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.6290727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465802899385558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1336334305696467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1248702055685142, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.6290727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 29.97344925528266, "y": 0.00812224933692729, "z": null, "yaw": 0.028640945272488866, "pitch": null, "roll": null}, "v": 2.1308758334157445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35195010984513964, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018174443445816108, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.6490726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465802899385558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1336334305696467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.123425242842523, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.6490726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.6590726, "x": 34.20733416786992, "y": 5.014723013834773, "z": null, "yaw": 0.027702744769348735, "pitch": null, "roll": null}, "v": 2.122703763557024, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35119390085604274, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018104743081696583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.6690726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24843115284706307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1962824257098796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1219829513605792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.6690726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 30.207334167869917, "y": 0.014723013834773369, "z": null, "yaw": 0.027702744769348735, "pitch": null, "roll": null}, "v": 2.122703763557024, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35119390085604274, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018104743081696583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.6890726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2472142403956109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1962824257098796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121014747871393, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.6890726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 30.207334167869917, "y": 0.014723013834773369, "z": null, "yaw": 0.027702744769348735, "pitch": null, "roll": null}, "v": 2.122703763557024, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35119390085604274, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018104743081696583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.7090726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2472142403956109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1962824257098796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11989628950972, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.7090726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 30.207334167869917, "y": 0.014723013834773369, "z": null, "yaw": 0.027702744769348735, "pitch": null, "roll": null}, "v": 2.122703763557024, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35119390085604274, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018104743081696583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.7290726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2472142403956109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1962824257098796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118779897182868, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.7290726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 30.207334167869917, "y": 0.014723013834773369, "z": null, "yaw": 0.027702744769348735, "pitch": null, "roll": null}, "v": 2.122703763557024, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35119390085604274, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018104743081696583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.7490726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2472142403956109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1962824257098796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117665566576121, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.7490726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.7690725, "x": 34.44043408423429, "y": 5.021082743776419, "z": null, "yaw": 0.026764544266208605, "pitch": null, "roll": null}, "v": 2.1165532933854907, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3506256431066842, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018052285134337667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.7690725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2504454779540754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2648629303549646, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1165532933854907, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.7690725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.44043408423429, "y": 0.021082743776418944, "z": null, "yaw": 0.026764544266208605, "pitch": null, "roll": null}, "v": 2.1165532933854907, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3506256431066842, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018052285134337667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.7890725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24940730264890654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2648629303549646, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.115846791566094, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.7890725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.44043408423429, "y": 0.021082743776418944, "z": null, "yaw": 0.026764544266208605, "pitch": null, "roll": null}, "v": 2.1165532933854907, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3506256431066842, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018052285134337667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.8090725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24940730264890654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2648629303549646, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1150118816187224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.8090725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.44043408423429, "y": 0.021082743776418944, "z": null, "yaw": 0.026764544266208605, "pitch": null, "roll": null}, "v": 2.1165532933854907, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3506256431066842, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018052285134337667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.8290725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24940730264890654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2648629303549646, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1141785122774697, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.8290725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.44043408423429, "y": 0.021082743776418944, "z": null, "yaw": 0.026764544266208605, "pitch": null, "roll": null}, "v": 2.1165532933854907, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3506256431066842, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018052285134337667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.8490725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24940730264890654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2648629303549646, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1133466804218792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.8490725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.44043408423429, "y": 0.021082743776418944, "z": null, "yaw": 0.026764544266208605, "pitch": null, "roll": null}, "v": 2.1165532933854907, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3506256431066842, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018052285134337667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.8690724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24940730264890654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2648629303549646, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1125163829387894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.8690724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.8790724, "x": 34.67295711456359, "y": 5.02720841099401, "z": null, "yaw": 0.025826343763068475, "pitch": null, "roll": null}, "v": 2.112101808616058, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502148309303952, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018014317995697648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.8890724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503275084745925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669554287891478, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111687616722311, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.8890724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 30.672957114563587, "y": 0.02720841099401028, "z": null, "yaw": 0.025826343763068475, "pitch": null, "roll": null}, "v": 2.112101808616058, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502148309303952, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018014317995697648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.9090724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25001940334324174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669554287891478, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1109753513601754, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.9090724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 30.672957114563587, "y": 0.02720841099401028, "z": null, "yaw": 0.025826343763068475, "pitch": null, "roll": null}, "v": 2.112101808616058, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502148309303952, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018014317995697648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.9290724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25001940334324174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669554287891478, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110225903753707, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.9290724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 30.672957114563587, "y": 0.02720841099401028, "z": null, "yaw": 0.025826343763068475, "pitch": null, "roll": null}, "v": 2.112101808616058, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502148309303952, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018014317995697648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.9490724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25001940334324174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669554287891478, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1094778376153323, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.9490724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 30.672957114563587, "y": 0.02720841099401028, "z": null, "yaw": 0.025826343763068475, "pitch": null, "roll": null}, "v": 2.112101808616058, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502148309303952, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018014317995697648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.9690723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25001940334324174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669554287891478, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1087311501748314, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.9690723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.9890723, "x": 34.90500668906021, "y": 5.033103747227124, "z": null, "yaw": 0.024888143259928344, "pitch": null, "roll": null}, "v": 2.1079858386683274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3498353348936785, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017979212495007914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.9890723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500482078098386, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2340188547404383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1079858386683274, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.9890723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 30.905006689060208, "y": 0.03310374722712428, "z": null, "yaw": 0.024888143259928344, "pitch": null, "roll": null}, "v": 2.1079858386683274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3498353348936785, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017979212495007914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.0090723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500202315938486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2340188547404383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107245499237596, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.0090723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 30.905006689060208, "y": 0.03310374722712428, "z": null, "yaw": 0.024888143259928344, "pitch": null, "roll": null}, "v": 2.1079858386683274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3498353348936785, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017979212495007914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.0290723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500202315938486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2340188547404383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1065030281872925, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.0290723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 30.905006689060208, "y": 0.03310374722712428, "z": null, "yaw": 0.024888143259928344, "pitch": null, "roll": null}, "v": 2.1079858386683274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3498353348936785, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017979212495007914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.0490723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500202315938486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2340188547404383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105761924639941, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.0490723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 30.905006689060208, "y": 0.03310374722712428, "z": null, "yaw": 0.024888143259928344, "pitch": null, "roll": null}, "v": 2.1079858386683274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3498353348936785, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017979212495007914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.0690722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500202315938486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2340188547404383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1050221858572455, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.0690722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 30.905006689060208, "y": 0.03310374722712428, "z": null, "yaw": 0.024888143259928344, "pitch": null, "roll": null}, "v": 2.1079858386683274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3498353348936785, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017979212495007914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.0890722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500202315938486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2340188547404383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104283809107166, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.0890722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.0990722, "x": 35.13661205810854, "y": 5.038770370663106, "z": null, "yaw": 0.023949942756788214, "pitch": null, "roll": null}, "v": 2.1039151306423007, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34946034530157116, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017944493037570144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.1090722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25271040872936124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.305298655788238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1035467916639004, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.1090722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 31.13661205810854, "y": 0.03877037066310596, "z": null, "yaw": 0.023949942756788214, "pitch": null, "roll": null}, "v": 2.1039151306423007, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34946034530157116, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017944493037570144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.1290722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25185097833142167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.305298655788238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103147248154903, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.1290722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 31.13661205810854, "y": 0.03877037066310596, "z": null, "yaw": 0.023949942756788214, "pitch": null, "roll": null}, "v": 2.1039151306423007, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34946034530157116, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017944493037570144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.1490722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25185097833142167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.305298655788238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1026410606351513, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.1490722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 31.13661205810854, "y": 0.03877037066310596, "z": null, "yaw": 0.023949942756788214, "pitch": null, "roll": null}, "v": 2.1039151306423007, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34946034530157116, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017944493037570144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.1690722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25185097833142167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.305298655788238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102135804631866, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.1690722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 31.13661205810854, "y": 0.03877037066310596, "z": null, "yaw": 0.023949942756788214, "pitch": null, "roll": null}, "v": 2.1039151306423007, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34946034530157116, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017944493037570144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.1890721} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25185097833142167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.305298655788238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101631478328749, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.1890721} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.209072, "x": 35.36783715951906, "y": 5.0442106183065, "z": null, "yaw": 0.023011742253648083, "pitch": null, "roll": null}, "v": 2.101128079913406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34920379607767627, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01792072201578718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.209072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25103713648692605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2314927356380632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101128079913406, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.209072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.367837159519063, "y": 0.04421061830649986, "z": null, "yaw": 0.023011742253648083, "pitch": null, "roll": null}, "v": 2.101128079913406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34920379607767627, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01792072201578718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.229072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512786347604748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2314927356380632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1005239241513456, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.229072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.367837159519063, "y": 0.04421061830649986, "z": null, "yaw": 0.023011742253648083, "pitch": null, "roll": null}, "v": 2.101128079913406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34920379607767627, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01792072201578718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.249072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512786347604748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2314927356380632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0999510530848586, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.249072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.367837159519063, "y": 0.04421061830649986, "z": null, "yaw": 0.023011742253648083, "pitch": null, "roll": null}, "v": 2.101128079913406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34920379607767627, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01792072201578718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.269072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512786347604748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2314927356380632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0993792356378536, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.269072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.367837159519063, "y": 0.04421061830649986, "z": null, "yaw": 0.023011742253648083, "pitch": null, "roll": null}, "v": 2.101128079913406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34920379607767627, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01792072201578718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.289072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512786347604748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2314927356380632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098808469741792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.289072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.367837159519063, "y": 0.04421061830649986, "z": null, "yaw": 0.023011742253648083, "pitch": null, "roll": null}, "v": 2.101128079913406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34920379607767627, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01792072201578718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.309072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512786347604748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2314927356380632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098238753332662, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.309072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.319072, "x": 35.59874199576605, "y": 5.049426584330255, "z": null, "yaw": 0.022073541750507953, "pitch": null, "roll": null}, "v": 2.0979542880419264, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489118363492314, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01789365244187187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.329072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25383552674264004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3008274736423704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.097670084350964, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.329072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 31.598741995766048, "y": 0.04942658433025482, "z": null, "yaw": 0.022073541750507953, "pitch": null, "roll": null}, "v": 2.0979542880419264, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489118363492314, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01789365244187187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.349072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25302189947833553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3008274736423704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0974219252991713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.349072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 31.598741995766048, "y": 0.04942658433025482, "z": null, "yaw": 0.022073541750507953, "pitch": null, "roll": null}, "v": 2.0979542880419264, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489118363492314, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01789365244187187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.369072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25302189947833553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3008274736423704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.097072565748265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.369072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 31.598741995766048, "y": 0.04942658433025482, "z": null, "yaw": 0.022073541750507953, "pitch": null, "roll": null}, "v": 2.0979542880419264, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489118363492314, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01789365244187187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.389072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25302189947833553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3008274736423704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096723848326719, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.389072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 31.598741995766048, "y": 0.04942658433025482, "z": null, "yaw": 0.022073541750507953, "pitch": null, "roll": null}, "v": 2.0979542880419264, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489118363492314, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01789365244187187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.409072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25302189947833553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3008274736423704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0963757718056693, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.409072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.429072, "x": 35.82936455629971, "y": 5.054419686825118, "z": null, "yaw": 0.021135341247367823, "pitch": null, "roll": null}, "v": 2.096028334958777, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487347645574395, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017877225804129735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.429072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25365480889740366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2985653671977035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096028334958777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.429072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 31.82936455629971, "y": 0.054419686825117886, "z": null, "yaw": 0.021135341247367823, "pitch": null, "roll": null}, "v": 2.096028334958777, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487347645574395, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017877225804129735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.449072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2534481709788729, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2985653671977035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0957606138799543, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.449072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 31.82936455629971, "y": 0.054419686825117886, "z": null, "yaw": 0.021135341247367823, "pitch": null, "roll": null}, "v": 2.096028334958777, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487347645574395, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017877225804129735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.4690719} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2534481709788729, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2985653671977035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095467566865461, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.4690719} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 31.82936455629971, "y": 0.054419686825117886, "z": null, "yaw": 0.021135341247367823, "pitch": null, "roll": null}, "v": 2.096028334958777, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487347645574395, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017877225804129735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.4890718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2534481709788729, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2985653671977035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0948830871217305, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.4890718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 31.82936455629971, "y": 0.054419686825117886, "z": null, "yaw": 0.021135341247367823, "pitch": null, "roll": null}, "v": 2.096028334958777, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487347645574395, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017877225804129735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.5090718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2534481709788729, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2985653671977035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0947373027494782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.5090718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 31.82936455629971, "y": 0.054419686825117886, "z": null, "yaw": 0.021135341247367823, "pitch": null, "roll": null}, "v": 2.096028334958777, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487347645574395, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017877225804129735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.5290718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2534481709788729, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2985653671977035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0944461357885276, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.5290718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.5390718, "x": 36.059800149762985, "y": 5.059192447236019, "z": null, "yaw": 0.020197140744227692, "pitch": null, "roll": null}, "v": 2.0944461357885276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34858935294662136, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017863731076333406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.5490718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2548167100852971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3259858802203757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.094155503690569, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.5490718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 32.059800149762985, "y": 0.05919244723601924, "z": null, "yaw": 0.020197140744227692, "pitch": null, "roll": null}, "v": 2.0944461357885276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34858935294662136, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017863731076333406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.5690718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25438177074883017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3259858802203757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0940363942383438, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.5690718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 32.059800149762985, "y": 0.05919244723601924, "z": null, "yaw": 0.020197140744227692, "pitch": null, "roll": null}, "v": 2.0944461357885276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34858935294662136, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017863731076333406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.5890718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25438177074883017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3259858802203757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0938631611233802, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.5890718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 32.059800149762985, "y": 0.05919244723601924, "z": null, "yaw": 0.020197140744227692, "pitch": null, "roll": null}, "v": 2.0944461357885276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34858935294662136, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017863731076333406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.6090717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25438177074883017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3259858802203757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0937766639208695, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.6090717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 32.059800149762985, "y": 0.05919244723601924, "z": null, "yaw": 0.020197140744227692, "pitch": null, "roll": null}, "v": 2.0944461357885276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34858935294662136, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017863731076333406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.6290717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25438177074883017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3259858802203757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0935176488384593, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.6290717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.6490717, "x": 36.290089571891365, "y": 5.0637416671326285, "z": null, "yaw": 0.01919943307295354, "pitch": null, "roll": null}, "v": 2.093431469071242, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484961266105399, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01941225411710648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.6490717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25421905879888973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.256028963738333, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093431469071242, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.6490717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.290089571891365, "y": 0.06374166713262852, "z": null, "yaw": 0.01919943307295354, "pitch": null, "roll": null}, "v": 2.093431469071242, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484961266105399, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01941225411710648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.6690717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542652449967241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.256028963738333, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093239017329979, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.6690717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.290089571891365, "y": 0.06374166713262852, "z": null, "yaw": 0.01919943307295354, "pitch": null, "roll": null}, "v": 2.093431469071242, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484961266105399, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01941225411710648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.6890717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542652449967241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.256028963738333, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093052689643725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.6890717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.290089571891365, "y": 0.06374166713262852, "z": null, "yaw": 0.01919943307295354, "pitch": null, "roll": null}, "v": 2.093431469071242, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484961266105399, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01941225411710648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.7090716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542652449967241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.256028963738333, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0928667041288618, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.7090716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.290089571891365, "y": 0.06374166713262852, "z": null, "yaw": 0.01919943307295354, "pitch": null, "roll": null}, "v": 2.093431469071242, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484961266105399, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01941225411710648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.7290716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542652449967241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.256028963738333, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.092681060143197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.7290716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.290089571891365, "y": 0.06374166713262852, "z": null, "yaw": 0.01919943307295354, "pitch": null, "roll": null}, "v": 2.093431469071242, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484961266105399, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01941225411710648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.7490716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542652449967241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.256028963738333, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0924957570457945, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.7490716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.7590716, "x": 36.52027485063812, "y": 5.068054883553334, "z": null, "yaw": 0.018179410213629132, "pitch": null, "roll": null}, "v": 2.0924032331302413, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34840167455665094, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402719351973755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.7690716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25221898015206917, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.089940982720259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0923107941969703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.7690716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 32.52027485063812, "y": 0.06805488355333367, "z": null, "yaw": 0.018179410213629132, "pitch": null, "roll": null}, "v": 2.0924032331302413, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34840167455665094, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402719351973755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.7890716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25285371572949444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.089940982720259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0918705053122624, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.7890716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 32.52027485063812, "y": 0.06805488355333367, "z": null, "yaw": 0.018179410213629132, "pitch": null, "roll": null}, "v": 2.0924032331302413, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34840167455665094, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402719351973755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.8090715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25285371572949444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.089940982720259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0915103302913747, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.8090715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 32.52027485063812, "y": 0.06805488355333367, "z": null, "yaw": 0.018179410213629132, "pitch": null, "roll": null}, "v": 2.0924032331302413, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34840167455665094, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402719351973755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.8290715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25285371572949444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.089940982720259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.091150816478657, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.8290715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 32.52027485063812, "y": 0.06805488355333367, "z": null, "yaw": 0.018179410213629132, "pitch": null, "roll": null}, "v": 2.0924032331302413, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34840167455665094, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402719351973755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.8490715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25285371572949444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.089940982720259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09079196260859, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.8490715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.8690715, "x": 36.75030606930743, "y": 5.072130507314262, "z": null, "yaw": 0.017159387354304723, "pitch": null, "roll": null}, "v": 2.0904337674182605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34822082173053803, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019384456624274883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.8690715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523969330641441, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0498231688508057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0904337674182605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.8690715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 32.75030606930743, "y": 0.07213050731426218, "z": null, "yaw": 0.017159387354304723, "pitch": null, "roll": null}, "v": 2.0904337674182605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34822082173053803, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019384456624274883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.8890715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25253063509342233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0498231688508057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0900191580234675, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.8890715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 32.75030606930743, "y": 0.07213050731426218, "z": null, "yaw": 0.017159387354304723, "pitch": null, "roll": null}, "v": 2.0904337674182605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34822082173053803, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019384456624274883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.9090714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25253063509342233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0498231688508057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.089423716274936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.9090714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 32.75030606930743, "y": 0.07213050731426218, "z": null, "yaw": 0.017159387354304723, "pitch": null, "roll": null}, "v": 2.0904337674182605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34822082173053803, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019384456624274883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.9290714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25253063509342233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0498231688508057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.089225599963524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.9290714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 32.75030606930743, "y": 0.07213050731426218, "z": null, "yaw": 0.017159387354304723, "pitch": null, "roll": null}, "v": 2.0904337674182605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34822082173053803, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019384456624274883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.9490714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25253063509342233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0498231688508057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0886323413945687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.9490714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 32.75030606930743, "y": 0.07213050731426218, "z": null, "yaw": 0.017159387354304723, "pitch": null, "roll": null}, "v": 2.0904337674182605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34822082173053803, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019384456624274883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.9690714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25253063509342233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0498231688508057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0884349514114584, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.9690714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.9790714, "x": 36.98011098646312, "y": 5.075967647464951, "z": null, "yaw": 0.016139364494980313, "pitch": null, "roll": null}, "v": 2.088237742574464, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3480192558238482, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019364093028453818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.9890714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25483523724761026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.094604966054896, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0880407147095643, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.9890714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 32.98011098646312, "y": 0.07596764746495133, "z": null, "yaw": 0.016139364494980313, "pitch": null, "roll": null}, "v": 2.088237742574464, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3480192558238482, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019364093028453818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.0090714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541049703002917, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.094604966054896, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0879351443036347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.0090714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 32.98011098646312, "y": 0.07596764746495133, "z": null, "yaw": 0.016139364494980313, "pitch": null, "roll": null}, "v": 2.088237742574464, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3480192558238482, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019364093028453818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.0290713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541049703002917, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.094604966054896, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087640352226534, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.0290713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 32.98011098646312, "y": 0.07596764746495133, "z": null, "yaw": 0.016139364494980313, "pitch": null, "roll": null}, "v": 2.088237742574464, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3480192558238482, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019364093028453818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.0490713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541049703002917, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.094604966054896, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087444274707433, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.0490713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 32.98011098646312, "y": 0.07596764746495133, "z": null, "yaw": 0.016139364494980313, "pitch": null, "roll": null}, "v": 2.088237742574464, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3480192558238482, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019364093028453818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.0690713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541049703002917, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.094604966054896, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087248556824996, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.0690713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.0890713, "x": 37.209732747748575, "y": 5.0795674378286595, "z": null, "yaw": 0.015119341635655915, "pitch": null, "roll": null}, "v": 2.087150832536555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34791952760440814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935401418222931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.0890713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25609078645813665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1432120604874951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0870531979042792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.0890713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.209732747748575, "y": 0.07956743782865949, "z": null, "yaw": 0.015119341635655915, "pitch": null, "roll": null}, "v": 2.087150832536555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34791952760440814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935401418222931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.1090713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25546523208769273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1432120604874951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087106310429217, "gear": 1, "accelerator_pedal_position": 0.25609078645813665, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.1090713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.209732747748575, "y": 0.07956743782865949, "z": null, "yaw": 0.015119341635655915, "pitch": null, "roll": null}, "v": 2.087150832536555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34791952760440814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935401418222931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.1290712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25546523208769273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1432120604874951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0870937330043797, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.1290712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.209732747748575, "y": 0.07956743782865949, "z": null, "yaw": 0.015119341635655915, "pitch": null, "roll": null}, "v": 2.087150832536555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34791952760440814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935401418222931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.1490712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25546523208769273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1432120604874951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0870560699200946, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.1490712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.209732747748575, "y": 0.07956743782865949, "z": null, "yaw": 0.015119341635655915, "pitch": null, "roll": null}, "v": 2.087150832536555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34791952760440814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935401418222931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.1690712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25546523208769273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1432120604874951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0870435385867165, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.1690712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.209732747748575, "y": 0.07956743782865949, "z": null, "yaw": 0.015119341635655915, "pitch": null, "roll": null}, "v": 2.087150832536555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34791952760440814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935401418222931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.1890712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25546523208769273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1432120604874951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087006013522499, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.1890712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.1990712, "x": 37.43928591044376, "y": 5.082931940743201, "z": null, "yaw": 0.014099318776331525, "pitch": null, "roll": null}, "v": 2.087006013522499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34790624168091566, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019352671284912925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.2090712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2571740645409922, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1961795172659186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086981054153958, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.2090712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 33.43928591044376, "y": 0.08293194074320098, "z": null, "yaw": 0.014099318776331525, "pitch": null, "roll": null}, "v": 2.087006013522499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34790624168091566, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019352671284912925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.2290711} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25663938975260137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1961795172659186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0871696466357452, "gear": 1, "accelerator_pedal_position": 0.2571740645409922, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.2290711} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 33.43928591044376, "y": 0.08293194074320098, "z": null, "yaw": 0.014099318776331525, "pitch": null, "roll": null}, "v": 2.087006013522499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34790624168091566, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019352671284912925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.2490711} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25663938975260137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1961795172659186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0872910895475583, "gear": 1, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.2490711} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 33.43928591044376, "y": 0.08293194074320098, "z": null, "yaw": 0.014099318776331525, "pitch": null, "roll": null}, "v": 2.087006013522499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34790624168091566, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019352671284912925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.269071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25663938975260137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1961795172659186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0874123097254724, "gear": 1, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.269071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 33.43928591044376, "y": 0.08293194074320098, "z": null, "yaw": 0.014099318776331525, "pitch": null, "roll": null}, "v": 2.087006013522499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34790624168091566, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019352671284912925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.289071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25663938975260137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1961795172659186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087472836415068, "gear": 1, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.289071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.309071, "x": 37.668859729520925, "y": 5.086062522024406, "z": null, "yaw": 0.013079295917007135, "pitch": null, "roll": null}, "v": 2.08759372324685, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "acceleration": 0.006036024258019523, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935812107903552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.309071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522366296833689, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0974386800922724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.08759372324685, "gear": 1, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.309071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 33.668859729520925, "y": 0.08606252202440601, "z": null, "yaw": 0.013079295917007135, "pitch": null, "roll": null}, "v": 2.08759372324685, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "acceleration": 0.006036024258019523, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935812107903552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.329071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25361518910959924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0974386800922724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086949877540551, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.329071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 33.668859729520925, "y": 0.08606252202440601, "z": null, "yaw": 0.013079295917007135, "pitch": null, "roll": null}, "v": 2.08759372324685, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "acceleration": 0.006036024258019523, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935812107903552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.349071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25361518910959924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0974386800922724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086821815941994, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.349071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 33.668859729520925, "y": 0.08606252202440601, "z": null, "yaw": 0.013079295917007135, "pitch": null, "roll": null}, "v": 2.08759372324685, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "acceleration": 0.006036024258019523, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935812107903552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.369071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25361518910959924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0974386800922724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0864383355869562, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.369071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 33.668859729520925, "y": 0.08606252202440601, "z": null, "yaw": 0.013079295917007135, "pitch": null, "roll": null}, "v": 2.08759372324685, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "acceleration": 0.006036024258019523, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935812107903552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.389071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25361518910959924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0974386800922724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086183267941681, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.389071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 33.668859729520925, "y": 0.08606252202440601, "z": null, "yaw": 0.013079295917007135, "pitch": null, "roll": null}, "v": 2.08759372324685, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "acceleration": 0.006036024258019523, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935812107903552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.409071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25361518910959924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0974386800922724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0860559095643163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.409071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.419071, "x": 37.89838302137313, "y": 5.088958276100554, "z": null, "yaw": 0.012059273057682745, "pitch": null, "roll": null}, "v": 2.0859286680031013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347807417480127, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934268112984769, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.429071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25620760526826764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1546471629310826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.08580154314765, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.429071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 33.89838302137313, "y": 0.08895827610055385, "z": null, "yaw": 0.012059273057682745, "pitch": null, "roll": null}, "v": 2.0859286680031013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347807417480127, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934268112984769, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.449071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25538983747173283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1546471629310826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.085906500075682, "gear": 1, "accelerator_pedal_position": 0.25620760526826764, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.449071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 33.89838302137313, "y": 0.08895827610055385, "z": null, "yaw": 0.012059273057682745, "pitch": null, "roll": null}, "v": 2.0859286680031013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347807417480127, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934268112984769, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.469071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25538983747173283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1546471629310826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0858741369223837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.469071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 33.89838302137313, "y": 0.08895827610055385, "z": null, "yaw": 0.012059273057682745, "pitch": null, "roll": null}, "v": 2.0859286680031013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347807417480127, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934268112984769, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.489071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25538983747173283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1546471629310826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0858579776043977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.489071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 33.89838302137313, "y": 0.08895827610055385, "z": null, "yaw": 0.012059273057682745, "pitch": null, "roll": null}, "v": 2.0859286680031013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347807417480127, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934268112984769, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.5090709} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25538983747173283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1546471629310826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.085809588521232, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.5090709} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.5290709, "x": 38.12781202998568, "y": 5.091618768893678, "z": null, "yaw": 0.011039250198358354, "pitch": null, "roll": null}, "v": 2.085793488404998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34779501918297684, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934142761820969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.5290709} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25755013613756705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2177953680762732, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0859124217217664, "gear": 1, "accelerator_pedal_position": 0.25755013613756705, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.5290709} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 34.12781202998568, "y": 0.09161876889367804, "z": null, "yaw": 0.011039250198358354, "pitch": null, "roll": null}, "v": 2.085793488404998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34779501918297684, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934142761820969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.5490708} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25687442244660397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2177953680762732, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086031245956394, "gear": 1, "accelerator_pedal_position": 0.25755013613756705, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.5490708} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 34.12781202998568, "y": 0.09161876889367804, "z": null, "yaw": 0.011039250198358354, "pitch": null, "roll": null}, "v": 2.085793488404998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34779501918297684, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934142761820969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.5690708} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25687442244660397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2177953680762732, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0861841420930394, "gear": 1, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.5690708} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 34.12781202998568, "y": 0.09161876889367804, "z": null, "yaw": 0.011039250198358354, "pitch": null, "roll": null}, "v": 2.085793488404998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34779501918297684, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934142761820969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.5890708} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25687442244660397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2177953680762732, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086489093812188, "gear": 1, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.5890708} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 34.12781202998568, "y": 0.09161876889367804, "z": null, "yaw": 0.011039250198358354, "pitch": null, "roll": null}, "v": 2.085793488404998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34779501918297684, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934142761820969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.6090708} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25687442244660397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2177953680762732, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086489093812188, "gear": 1, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.6090708} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.6390707, "x": 38.357286533327894, "y": 5.094045682387615, "z": null, "yaw": 0.010019227339033964, "pitch": null, "roll": null}, "v": 2.086717074101968, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "acceleration": 0.007585405112689569, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934999196842291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.6390707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25871437687264665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2880894359466672, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086717074101968, "gear": 1, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.6390707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.357286533327894, "y": 0.09404568238761524, "z": null, "yaw": 0.010019227339033964, "pitch": null, "roll": null}, "v": 2.086717074101968, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "acceleration": 0.007585405112689569, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934999196842291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.6590707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25814362654007567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2880894359466672, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.08709860142774, "gear": 1, "accelerator_pedal_position": 0.25871437687264665, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.6590707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.357286533327894, "y": 0.09404568238761524, "z": null, "yaw": 0.010019227339033964, "pitch": null, "roll": null}, "v": 2.086717074101968, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "acceleration": 0.007585405112689569, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934999196842291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.6790707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25814362654007567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2880894359466672, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0874081179835544, "gear": 1, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.6790707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.357286533327894, "y": 0.09404568238761524, "z": null, "yaw": 0.010019227339033964, "pitch": null, "roll": null}, "v": 2.086717074101968, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "acceleration": 0.007585405112689569, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934999196842291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.6990707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25814362654007567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2880894359466672, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0877170668579828, "gear": 1, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.6990707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.357286533327894, "y": 0.09404568238761524, "z": null, "yaw": 0.010019227339033964, "pitch": null, "roll": null}, "v": 2.086717074101968, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "acceleration": 0.007585405112689569, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934999196842291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.7190707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25814362654007567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2880894359466672, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0880254490540415, "gear": 1, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.7190707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.357286533327894, "y": 0.09404568238761524, "z": null, "yaw": 0.010019227339033964, "pitch": null, "roll": null}, "v": 2.086717074101968, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "acceleration": 0.007585405112689569, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934999196842291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.7390707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25814362654007567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2880894359466672, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.088333265573118, "gear": 1, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.7390707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.7490706, "x": 38.586906783510294, "y": 5.096239887755492, "z": null, "yaw": 0.008999204479709574, "pitch": null, "roll": null}, "v": 2.0884869620162765, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "acceleration": 0.015355539869539248, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01936640402415961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.7590706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25727974260888803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.271679626913811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.088640517414972, "gear": 1, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.7590706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 34.586906783510294, "y": 0.09623988775549197, "z": null, "yaw": 0.008999204479709574, "pitch": null, "roll": null}, "v": 2.0884869620162765, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "acceleration": 0.015355539869539248, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01936640402415961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.7790706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575578260610773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.271679626913811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0888392696383633, "gear": 1, "accelerator_pedal_position": 0.25727974260888803, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.7790706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 34.586906783510294, "y": 0.09623988775549197, "z": null, "yaw": 0.008999204479709574, "pitch": null, "roll": null}, "v": 2.0884869620162765, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "acceleration": 0.015355539869539248, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01936640402415961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.7990706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575578260610773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.271679626913811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0890724016964537, "gear": 1, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.7990706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 34.586906783510294, "y": 0.09623988775549197, "z": null, "yaw": 0.008999204479709574, "pitch": null, "roll": null}, "v": 2.0884869620162765, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "acceleration": 0.015355539869539248, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01936640402415961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.8190706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575578260610773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.271679626913811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.089305106012406, "gear": 1, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.8190706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 34.586906783510294, "y": 0.09623988775549197, "z": null, "yaw": 0.008999204479709574, "pitch": null, "roll": null}, "v": 2.0884869620162765, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "acceleration": 0.015355539869539248, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01936640402415961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.8390706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575578260610773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.271679626913811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0895373833493744, "gear": 1, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.8390706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.8590705, "x": 38.8166968120731, "y": 5.098201309732753, "z": null, "yaw": 0.007979181620385184, "pitch": null, "roll": null}, "v": 2.089769234469234, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "acceleration": 0.011576596624930102, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019378294453376868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.8590705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2574813448212617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2553519424699235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.089769234469234, "gear": 1, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.8590705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 34.8166968120731, "y": 0.09820130973275276, "z": null, "yaw": 0.007979181620385184, "pitch": null, "roll": null}, "v": 2.089769234469234, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "acceleration": 0.011576596624930102, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019378294453376868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.8790705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575111297407761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2553519424699235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0899911043656, "gear": 1, "accelerator_pedal_position": 0.2574813448212617, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.8790705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 34.8166968120731, "y": 0.09820130973275276, "z": null, "yaw": 0.007979181620385184, "pitch": null, "roll": null}, "v": 2.089769234469234, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "acceleration": 0.011576596624930102, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019378294453376868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.8990705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575111297407761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2553519424699235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.090216288507512, "gear": 1, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.8990705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 34.8166968120731, "y": 0.09820130973275276, "z": null, "yaw": 0.007979181620385184, "pitch": null, "roll": null}, "v": 2.089769234469234, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "acceleration": 0.011576596624930102, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019378294453376868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.9190705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575111297407761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2553519424699235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0904410593867118, "gear": 1, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.9190705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 34.8166968120731, "y": 0.09820130973275276, "z": null, "yaw": 0.007979181620385184, "pitch": null, "roll": null}, "v": 2.089769234469234, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "acceleration": 0.011576596624930102, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019378294453376868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.9390705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575111297407761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2553519424699235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.090889364308648, "gear": 1, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.9390705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 34.8166968120731, "y": 0.09820130973275276, "z": null, "yaw": 0.007979181620385184, "pitch": null, "roll": null}, "v": 2.089769234469234, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "acceleration": 0.011576596624930102, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019378294453376868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.9590704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575111297407761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2553519424699235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.090889364308648, "gear": 1, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.9590704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.9690704, "x": 39.046626467485424, "y": 5.099929375170972, "z": null, "yaw": 0.006959158761060786, "pitch": null, "roll": null}, "v": 2.091001183401914, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "acceleration": 0.01117164221987288, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019389718235857358, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.9890704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25786128498159916, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418659815005195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0913579097248784, "gear": 1, "accelerator_pedal_position": 0.25786128498159916, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.9890704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 35.046626467485424, "y": 0.099929375170972, "z": null, "yaw": 0.006959158761060786, "pitch": null, "roll": null}, "v": 2.091001183401914, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "acceleration": 0.01117164221987288, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019389718235857358, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.0090704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577575165209648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418659815005195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0914911832907093, "gear": 1, "accelerator_pedal_position": 0.25786128498159916, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.0090704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 35.046626467485424, "y": 0.099929375170972, "z": null, "yaw": 0.006959158761060786, "pitch": null, "roll": null}, "v": 2.091001183401914, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "acceleration": 0.01117164221987288, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019389718235857358, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.0290704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577575165209648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418659815005195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0917443982801314, "gear": 1, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.0290704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 35.046626467485424, "y": 0.099929375170972, "z": null, "yaw": 0.006959158761060786, "pitch": null, "roll": null}, "v": 2.091001183401914, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "acceleration": 0.01117164221987288, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019389718235857358, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.0490704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577575165209648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418659815005195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0919971484101114, "gear": 1, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.0490704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 35.046626467485424, "y": 0.099929375170972, "z": null, "yaw": 0.006959158761060786, "pitch": null, "roll": null}, "v": 2.091001183401914, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "acceleration": 0.01117164221987288, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019389718235857358, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.0690703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577575165209648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418659815005195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0922494345085103, "gear": 1, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.0690703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.0790703, "x": 39.27669951101676, "y": 5.101423825534585, "z": null, "yaw": 0.005939135901736386, "pitch": null, "roll": null}, "v": 2.0923754038041964, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "acceleration": 0.012585359761372317, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402461292439888, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.0890703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25735803948042624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1899135225011024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09250125740181, "gear": 1, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.0890703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 35.27669951101676, "y": 0.10142382553458518, "z": null, "yaw": 0.005939135901736386, "pitch": null, "roll": null}, "v": 2.0923754038041964, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "acceleration": 0.012585359761372317, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402461292439888, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.1090703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25748918613331495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1899135225011024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0927027062180983, "gear": 1, "accelerator_pedal_position": 0.25735803948042624, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.1090703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 35.27669951101676, "y": 0.10142382553458518, "z": null, "yaw": 0.005939135901736386, "pitch": null, "roll": null}, "v": 2.0923754038041964, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "acceleration": 0.012585359761372317, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402461292439888, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.1290703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25748918613331495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1899135225011024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.092920170933069, "gear": 1, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.1290703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 35.27669951101676, "y": 0.10142382553458518, "z": null, "yaw": 0.005939135901736386, "pitch": null, "roll": null}, "v": 2.0923754038041964, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "acceleration": 0.012585359761372317, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402461292439888, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.1490703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25748918613331495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1899135225011024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093137236317032, "gear": 1, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.1490703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 35.27669951101676, "y": 0.10142382553458518, "z": null, "yaw": 0.005939135901736386, "pitch": null, "roll": null}, "v": 2.0923754038041964, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "acceleration": 0.012585359761372317, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402461292439888, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.1690702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25748918613331495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1899135225011024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0933539030844424, "gear": 1, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.1690702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.1890702, "x": 39.50691745660158, "y": 5.1026843829960296, "z": null, "yaw": 0.004919113042411986, "pitch": null, "roll": null}, "v": 2.093570171948545, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "acceleration": 0.010798544087064488, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019413540299883777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.1890702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547308114617358, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0514419178423036, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093570171948545, "gear": 1, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.1890702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 35.50691745660158, "y": 0.10268438299602956, "z": null, "yaw": 0.004919113042411986, "pitch": null, "roll": null}, "v": 2.093570171948545, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "acceleration": 0.010798544087064488, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019413540299883777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.2090702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25559829165294345, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0514419178423036, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093441405173029, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.2090702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 35.50691745660158, "y": 0.10268438299602956, "z": null, "yaw": 0.004919113042411986, "pitch": null, "roll": null}, "v": 2.093570171948545, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "acceleration": 0.010798544087064488, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019413540299883777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.2290702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25559829165294345, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0514419178423036, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093421260098859, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.2290702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 35.50691745660158, "y": 0.10268438299602956, "z": null, "yaw": 0.004919113042411986, "pitch": null, "roll": null}, "v": 2.093570171948545, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "acceleration": 0.010798544087064488, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019413540299883777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.2490702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25559829165294345, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0514419178423036, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0934011520216527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.2490702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 35.50691745660158, "y": 0.10268438299602956, "z": null, "yaw": 0.004919113042411986, "pitch": null, "roll": null}, "v": 2.093570171948545, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "acceleration": 0.010798544087064488, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019413540299883777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.2690701} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25559829165294345, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0514419178423036, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093381080873302, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.2690701} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 35.50691745660158, "y": 0.10268438299602956, "z": null, "yaw": 0.004919113042411986, "pitch": null, "roll": null}, "v": 2.093570171948545, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "acceleration": 0.010798544087064488, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019413540299883777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.2890701} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25559829165294345, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0514419178423036, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093361046585826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.2890701} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.2990701, "x": 39.7371920268243, "y": 5.103710372099999, "z": null, "yaw": 0.0038990901830875868, "pitch": null, "roll": null}, "v": 2.0933510432437057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484887380646804, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019411508333628594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.30907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25763639943208905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0981992716966804, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093341049091368, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.30907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 35.7371920268243, "y": 0.10371037209999923, "z": null, "yaw": 0.0038990901830875868, "pitch": null, "roll": null}, "v": 2.0933510432437057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484887380646804, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019411508333628594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.32907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2569984837737823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0981992716966804, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0935757347716715, "gear": 1, "accelerator_pedal_position": 0.25763639943208905, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.32907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 35.7371920268243, "y": 0.10371037209999923, "z": null, "yaw": 0.0038990901830875868, "pitch": null, "roll": null}, "v": 2.0933510432437057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484887380646804, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019411508333628594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.34907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2569984837737823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0981992716966804, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0937302866093956, "gear": 1, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.34907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 35.7371920268243, "y": 0.10371037209999923, "z": null, "yaw": 0.0038990901830875868, "pitch": null, "roll": null}, "v": 2.0933510432437057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484887380646804, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019411508333628594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.36907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2569984837737823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0981992716966804, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0938845545921803, "gear": 1, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.36907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 35.7371920268243, "y": 0.10371037209999923, "z": null, "yaw": 0.0038990901830875868, "pitch": null, "roll": null}, "v": 2.0933510432437057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484887380646804, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019411508333628594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.38907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2569984837737823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0981992716966804, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.094038539231848, "gear": 1, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.38907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.40907, "x": 39.967499829500596, "y": 5.104501576393245, "z": null, "yaw": 0.002879067323763187, "pitch": null, "roll": null}, "v": 2.094192241039333, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "acceleration": 0.007674500109879301, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019419308706180895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.40907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2587357923225668, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1492267783056795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.094192241039333, "gear": 1, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.40907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 35.967499829500596, "y": 0.10450157639324509, "z": null, "yaw": 0.002879067323763187, "pitch": null, "roll": null}, "v": 2.094192241039333, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "acceleration": 0.007674500109879301, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019419308706180895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.42907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581967473182252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1492267783056795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0945627243213183, "gear": 1, "accelerator_pedal_position": 0.2587357923225668, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.42907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 35.967499829500596, "y": 0.10450157639324509, "z": null, "yaw": 0.002879067323763187, "pitch": null, "roll": null}, "v": 2.094192241039333, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "acceleration": 0.007674500109879301, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019419308706180895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.44907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581967473182252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1492267783056795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0948651773804294, "gear": 1, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.44907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 35.967499829500596, "y": 0.10450157639324509, "z": null, "yaw": 0.002879067323763187, "pitch": null, "roll": null}, "v": 2.094192241039333, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "acceleration": 0.007674500109879301, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019419308706180895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.46907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581967473182252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1492267783056795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0951670748116977, "gear": 1, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.46907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 35.967499829500596, "y": 0.10450157639324509, "z": null, "yaw": 0.002879067323763187, "pitch": null, "roll": null}, "v": 2.094192241039333, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "acceleration": 0.007674500109879301, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019419308706180895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.48907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581967473182252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1492267783056795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095468417599411, "gear": 1, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.48907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 35.967499829500596, "y": 0.10450157639324509, "z": null, "yaw": 0.002879067323763187, "pitch": null, "roll": null}, "v": 2.094192241039333, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "acceleration": 0.007674500109879301, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019419308706180895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.50907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581967473182252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1492267783056795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0957692067262492, "gear": 1, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.50907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.51907, "x": 40.197949840600515, "y": 5.105058195337708, "z": null, "yaw": 0.0018590444644387876, "pitch": null, "roll": null}, "v": 2.095919393973489, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "acceleration": 0.01500491997989084, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01943532448322079, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.52907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258267178989954, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1320154207909272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096069443173288, "gear": 1, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.52907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 36.197949840600515, "y": 0.10505819533770833, "z": null, "yaw": 0.0018590444644387876, "pitch": null, "roll": null}, "v": 2.095919393973489, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "acceleration": 0.01500491997989084, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01943532448322079, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.54907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582531054474492, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1320154207909272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09637792783247, "gear": 1, "accelerator_pedal_position": 0.258267178989954, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.54907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 36.197949840600515, "y": 0.10505819533770833, "z": null, "yaw": 0.0018590444644387876, "pitch": null, "roll": null}, "v": 2.095919393973489, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "acceleration": 0.01500491997989084, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01943532448322079, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.5690699} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582531054474492, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1320154207909272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0966840872128287, "gear": 1, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.5690699} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 36.197949840600515, "y": 0.10505819533770833, "z": null, "yaw": 0.0018590444644387876, "pitch": null, "roll": null}, "v": 2.095919393973489, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "acceleration": 0.01500491997989084, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01943532448322079, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.5890698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582531054474492, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1320154207909272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0969896839341353, "gear": 1, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.5890698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 36.197949840600515, "y": 0.10505819533770833, "z": null, "yaw": 0.0018590444644387876, "pitch": null, "roll": null}, "v": 2.095919393973489, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "acceleration": 0.01500491997989084, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01943532448322079, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.6090698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582531054474492, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1320154207909272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0972947189931053, "gear": 1, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.6090698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.6290698, "x": 40.42858476959887, "y": 5.105380007397418, "z": null, "yaw": 0.000839021605114388, "pitch": null, "roll": null}, "v": 2.0975991933848275, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "acceleration": 0.015202725616429436, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019450901154117562, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.6290698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25980498037485256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1881428000686045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0975991933848275, "gear": 1, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.6290698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 36.42858476959887, "y": 0.10538000739741804, "z": null, "yaw": 0.000839021605114388, "pitch": null, "roll": null}, "v": 2.0975991933848275, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "acceleration": 0.015202725616429436, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019450901154117562, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.6490698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259327740780692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1881428000686045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098097003278566, "gear": 1, "accelerator_pedal_position": 0.25980498037485256, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.6490698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 36.42858476959887, "y": 0.10538000739741804, "z": null, "yaw": 0.000839021605114388, "pitch": null, "roll": null}, "v": 2.0975991933848275, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "acceleration": 0.015202725616429436, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019450901154117562, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.6690698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259327740780692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1881428000686045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098534270508848, "gear": 1, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.6690698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 36.42858476959887, "y": 0.10538000739741804, "z": null, "yaw": 0.000839021605114388, "pitch": null, "roll": null}, "v": 2.0975991933848275, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "acceleration": 0.015202725616429436, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019450901154117562, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.6890697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259327740780692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1881428000686045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0989707338127714, "gear": 1, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.6890697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 36.42858476959887, "y": 0.10538000739741804, "z": null, "yaw": 0.000839021605114388, "pitch": null, "roll": null}, "v": 2.0975991933848275, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "acceleration": 0.015202725616429436, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019450901154117562, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.7090697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259327740780692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1881428000686045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099406394592209, "gear": 1, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.7090697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 36.42858476959887, "y": 0.10538000739741804, "z": null, "yaw": 0.000839021605114388, "pitch": null, "roll": null}, "v": 2.0975991933848275, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "acceleration": 0.015202725616429436, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019450901154117562, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.7290697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259327740780692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1881428000686045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0998412542468756, "gear": 1, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.7290697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.7390697, "x": 40.65944652333276, "y": 5.105466644449983, "z": null, "yaw": -0.0001810012542100112, "pitch": null, "roll": null}, "v": 2.1000583840892415, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "acceleration": 0.021693008509027556, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019473705069880658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.7490697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.256281952380739, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.030632267996983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1002753141743318, "gear": 1, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.7490697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 36.65944652333276, "y": 0.105466644449983, "z": null, "yaw": 6.283004305925377, "pitch": null, "roll": null}, "v": 2.1000583840892415, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "acceleration": 0.021693008509027556, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019473705069880658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.7690697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572450712842027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.030632267996983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1003280273679334, "gear": 1, "accelerator_pedal_position": 0.256281952380739, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.7690697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 36.65944652333276, "y": 0.105466644449983, "z": null, "yaw": 6.283004305925377, "pitch": null, "roll": null}, "v": 2.1000583840892415, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "acceleration": 0.021693008509027556, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019473705069880658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.7890697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572450712842027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.030632267996983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1005009780862105, "gear": 1, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.7890697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 36.65944652333276, "y": 0.105466644449983, "z": null, "yaw": 6.283004305925377, "pitch": null, "roll": null}, "v": 2.1000583840892415, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "acceleration": 0.021693008509027556, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019473705069880658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.8090696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572450712842027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.030632267996983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100673610689915, "gear": 1, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.8090696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 36.65944652333276, "y": 0.105466644449983, "z": null, "yaw": 6.283004305925377, "pitch": null, "roll": null}, "v": 2.1000583840892415, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "acceleration": 0.021693008509027556, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019473705069880658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.8290696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572450712842027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.030632267996983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1008459257522523, "gear": 1, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.8290696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.8490696, "x": 40.89050324110286, "y": 5.105317685933983, "z": null, "yaw": -0.0012010241135344106, "pitch": null, "roll": null}, "v": 2.101017923845437, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "acceleration": 0.00858803617079712, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019482602819751112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.8490696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590889937953027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.076632691018016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101017923845437, "gear": 1, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.8490696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 36.89050324110286, "y": 0.10531768593398283, "z": null, "yaw": 6.281984283066052, "pitch": null, "roll": null}, "v": 2.101017923845437, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "acceleration": 0.00858803617079712, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019482602819751112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.8690696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25851718203493357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.076632691018016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101419989802272, "gear": 1, "accelerator_pedal_position": 0.2590889937953027, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.8690696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 36.89050324110286, "y": 0.10531768593398283, "z": null, "yaw": 6.281984283066052, "pitch": null, "roll": null}, "v": 2.101017923845437, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "acceleration": 0.00858803617079712, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019482602819751112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.8890696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25851718203493357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.076632691018016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1017498725066384, "gear": 1, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.8890696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 36.89050324110286, "y": 0.10531768593398283, "z": null, "yaw": 6.281984283066052, "pitch": null, "roll": null}, "v": 2.101017923845437, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "acceleration": 0.00858803617079712, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019482602819751112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.9090695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25851718203493357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.076632691018016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.10207914828623, "gear": 1, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.9090695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 36.89050324110286, "y": 0.10531768593398283, "z": null, "yaw": 6.281984283066052, "pitch": null, "roll": null}, "v": 2.101017923845437, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "acceleration": 0.00858803617079712, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019482602819751112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.9290695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25851718203493357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.076632691018016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1024078182143304, "gear": 1, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.9290695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 36.89050324110286, "y": 0.10531768593398283, "z": null, "yaw": 6.281984283066052, "pitch": null, "roll": null}, "v": 2.101017923845437, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "acceleration": 0.00858803617079712, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019482602819751112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.9490695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25851718203493357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.076632691018016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102735883362487, "gear": 1, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.9490695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.9590695, "x": 41.1217123584171, "y": 5.104932781238462, "z": null, "yaw": -0.00222104697285881, "pitch": null, "roll": null}, "v": 2.102899689478471, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "acceleration": 0.01636553220432463, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019500052310310982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.9690695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600863594262879, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.127136101784425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1030633448005145, "gear": 1, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.9690695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 37.1217123584171, "y": 0.10493278123846217, "z": null, "yaw": 6.280964260206727, "pitch": null, "roll": null}, "v": 2.102899689478471, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "acceleration": 0.01636553220432463, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019500052310310982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.9890695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259604650983584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.127136101784425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1040781069343812, "gear": 1, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.9890695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 37.1217123584171, "y": 0.10493278123846217, "z": null, "yaw": 6.280964260206727, "pitch": null, "roll": null}, "v": 2.102899689478471, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "acceleration": 0.01636553220432463, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019500052310310982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.0090694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259604650983584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.127136101784425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1045389689768412, "gear": 1, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.0090694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 37.1217123584171, "y": 0.10493278123846217, "z": null, "yaw": 6.280964260206727, "pitch": null, "roll": null}, "v": 2.102899689478471, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "acceleration": 0.01636553220432463, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019500052310310982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.0390694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259604650983584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.127136101784425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104998982608481, "gear": 1, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.0390694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 37.1217123584171, "y": 0.10493278123846217, "z": null, "yaw": 6.280964260206727, "pitch": null, "roll": null}, "v": 2.102899689478471, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "acceleration": 0.01636553220432463, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019500052310310982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.0590694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259604650983584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.127136101784425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1052286717319726, "gear": 1, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.0590694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.0690694, "x": 41.35315795462964, "y": 5.1043113950152454, "z": null, "yaw": -0.0032410698321832096, "pitch": null, "roll": null}, "v": 2.1054581493065525, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "acceleration": 0.02292662099725845, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019523776742213766, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.0790694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25821412877294153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0357190537000218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1056874155165253, "gear": 1, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.0790694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 37.35315795462964, "y": 0.10431139501524544, "z": null, "yaw": 6.279944237347403, "pitch": null, "roll": null}, "v": 2.1054581493065525, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "acceleration": 0.02292662099725845, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019523776742213766, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.0990694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25866044686320283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0357190537000218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105971579359943, "gear": 1, "accelerator_pedal_position": 0.25821412877294153, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.0990694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 37.35315795462964, "y": 0.10431139501524544, "z": null, "yaw": 6.279944237347403, "pitch": null, "roll": null}, "v": 2.1054581493065525, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "acceleration": 0.02292662099725845, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019523776742213766, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.1190693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25866044686320283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0357190537000218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1063109839761456, "gear": 1, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.1190693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 37.35315795462964, "y": 0.10431139501524544, "z": null, "yaw": 6.279944237347403, "pitch": null, "roll": null}, "v": 2.1054581493065525, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "acceleration": 0.02292662099725845, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019523776742213766, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.1390693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25866044686320283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0357190537000218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1068189192552054, "gear": 1, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.1390693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 37.35315795462964, "y": 0.10431139501524544, "z": null, "yaw": 6.279944237347403, "pitch": null, "roll": null}, "v": 2.1054581493065525, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "acceleration": 0.02292662099725845, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019523776742213766, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.1590693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25866044686320283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0357190537000218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1069879191286747, "gear": 1, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.1590693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.1790693, "x": 41.58485128328884, "y": 5.103453015946671, "z": null, "yaw": -0.004261092691507609, "pitch": null, "roll": null}, "v": 2.1073254518737237, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "acceleration": 0.016853314700183475, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01954109211770276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.1790693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2603370462194979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0817389352310713, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107598772480494, "gear": 1, "accelerator_pedal_position": 0.2603370462194979, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.1790693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 37.58485128328884, "y": 0.10345301594667067, "z": null, "yaw": 6.278924214488079, "pitch": null, "roll": null}, "v": 2.1073254518737237, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "acceleration": 0.016853314700183475, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01954109211770276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.1990693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25982171011000965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0817389352310713, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107871841224396, "gear": 1, "accelerator_pedal_position": 0.2603370462194979, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.1990693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 37.58485128328884, "y": 0.10345301594667067, "z": null, "yaw": 6.278924214488079, "pitch": null, "roll": null}, "v": 2.1073254518737237, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "acceleration": 0.016853314700183475, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01954109211770276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.2190692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25982171011000965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0817389352310713, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108352836662618, "gear": 1, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.2190692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 37.58485128328884, "y": 0.10345301594667067, "z": null, "yaw": 6.278924214488079, "pitch": null, "roll": null}, "v": 2.1073254518737237, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "acceleration": 0.016853314700183475, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01954109211770276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.2390692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25982171011000965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0817389352310713, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108832945893882, "gear": 1, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.2390692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 37.58485128328884, "y": 0.10345301594667067, "z": null, "yaw": 6.278924214488079, "pitch": null, "roll": null}, "v": 2.1073254518737237, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "acceleration": 0.016853314700183475, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01954109211770276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.2590692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25982171011000965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0817389352310713, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.109312170458815, "gear": 1, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.2590692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 37.58485128328884, "y": 0.10345301594667067, "z": null, "yaw": 6.278924214488079, "pitch": null, "roll": null}, "v": 2.1073254518737237, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "acceleration": 0.016853314700183475, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01954109211770276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.2790692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25982171011000965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0817389352310713, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1100293519212348, "gear": 1, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.2790692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.2890692, "x": 41.8167928253646, "y": 5.102357119534158, "z": null, "yaw": -0.005281115550832009, "pitch": null, "roll": null}, "v": 2.1100293519212348, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "acceleration": 0.023861981931807053, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019566165207319033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.2990692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2610293098962597, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0878575618767448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110267971740553, "gear": 1, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.2990692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 37.8167928253646, "y": 0.10235711953415816, "z": null, "yaw": 6.277904191628754, "pitch": null, "roll": null}, "v": 2.1100293519212348, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "acceleration": 0.023861981931807053, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019566165207319033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.3190691} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26066439612684644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0878575618767448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110895431904103, "gear": 1, "accelerator_pedal_position": 0.2610293098962597, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.3190691} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 37.8167928253646, "y": 0.10235711953415816, "z": null, "yaw": 6.277904191628754, "pitch": null, "roll": null}, "v": 2.1100293519212348, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "acceleration": 0.023861981931807053, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019566165207319033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.3390691} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26066439612684644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0878575618767448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111766095728694, "gear": 1, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.3390691} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 37.8167928253646, "y": 0.10235711953415816, "z": null, "yaw": 6.277904191628754, "pitch": null, "roll": null}, "v": 2.1100293519212348, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "acceleration": 0.023861981931807053, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019566165207319033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.359069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26066439612684644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0878575618767448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1120557818344508, "gear": 1, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.359069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 37.8167928253646, "y": 0.10235711953415816, "z": null, "yaw": 6.277904191628754, "pitch": null, "roll": null}, "v": 2.1100293519212348, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "acceleration": 0.023861981931807053, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019566165207319033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.379069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26066439612684644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0878575618767448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112634352671753, "gear": 1, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.379069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.399069, "x": 42.04905059597657, "y": 5.10102280937973, "z": null, "yaw": -0.006301138410156408, "pitch": null, "roll": null}, "v": 2.113211856540623, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "acceleration": 0.02883523945952038, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019595676366061594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.399069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25990769189633145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9508221857616033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.113211856540623, "gear": 1, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.399069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.04905059597657, "y": 0.10102280937972985, "z": null, "yaw": 6.2768841687694295, "pitch": null, "roll": null}, "v": 2.113211856540623, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "acceleration": 0.02883523945952038, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019595676366061594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.419069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601588386369078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9508221857616033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.113693750884513, "gear": 1, "accelerator_pedal_position": 0.25990769189633145, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.419069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.04905059597657, "y": 0.10102280937972985, "z": null, "yaw": 6.2768841687694295, "pitch": null, "roll": null}, "v": 2.113211856540623, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "acceleration": 0.02883523945952038, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019595676366061594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.439069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601588386369078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9508221857616033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1142061351946175, "gear": 1, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.439069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.04905059597657, "y": 0.10102280937972985, "z": null, "yaw": 6.2768841687694295, "pitch": null, "roll": null}, "v": 2.113211856540623, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "acceleration": 0.02883523945952038, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019595676366061594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.459069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601588386369078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9508221857616033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1147175742685977, "gear": 1, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.459069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.04905059597657, "y": 0.10102280937972985, "z": null, "yaw": 6.2768841687694295, "pitch": null, "roll": null}, "v": 2.113211856540623, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "acceleration": 0.02883523945952038, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019595676366061594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.479069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601588386369078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9508221857616033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1152280697456263, "gear": 1, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.479069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.04905059597657, "y": 0.10102280937972985, "z": null, "yaw": 6.2768841687694295, "pitch": null, "roll": null}, "v": 2.113211856540623, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "acceleration": 0.02883523945952038, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019595676366061594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.499069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601588386369078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9508221857616033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11573762326243, "gear": 1, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.499069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.509069, "x": 42.28163642249572, "y": 5.099449366349305, "z": null, "yaw": -0.007321161269480808, "pitch": null, "roll": null}, "v": 2.1159920472965568, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "acceleration": 0.025418915673623144, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019621456894464637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.519069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616858524066491, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9897298709441593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.116246236453293, "gear": 1, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.519069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 38.28163642249572, "y": 0.09944936634930457, "z": null, "yaw": 6.275864145910106, "pitch": null, "roll": null}, "v": 2.1159920472965568, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "acceleration": 0.025418915673623144, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019621456894464637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.539069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612214897728341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9897298709441593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1169446995521226, "gear": 1, "accelerator_pedal_position": 0.2616858524066491, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.539069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 38.28163642249572, "y": 0.09944936634930457, "z": null, "yaw": 6.275864145910106, "pitch": null, "roll": null}, "v": 2.1159920472965568, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "acceleration": 0.025418915673623144, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019621456894464637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.559069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612214897728341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9897298709441593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1175838548609773, "gear": 1, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.559069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 38.28163642249572, "y": 0.09944936634930457, "z": null, "yaw": 6.275864145910106, "pitch": null, "roll": null}, "v": 2.1159920472965568, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "acceleration": 0.025418915673623144, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019621456894464637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.579069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612214897728341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9897298709441593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118221830214496, "gear": 1, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.579069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 38.28163642249572, "y": 0.09944936634930457, "z": null, "yaw": 6.275864145910106, "pitch": null, "roll": null}, "v": 2.1159920472965568, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "acceleration": 0.025418915673623144, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019621456894464637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.5990689} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612214897728341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9897298709441593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118858627628284, "gear": 1, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.5990689} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.6190689, "x": 42.51456262701955, "y": 5.097636011105622, "z": null, "yaw": -0.008341184128805202, "pitch": null, "roll": null}, "v": 2.1194942491151263, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "acceleration": 0.03173703990413579, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019653932584581982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.6190689} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625723775210014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.031818180720427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1194942491151263, "gear": 1, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.6190689} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 38.51456262701955, "y": 0.09763601110562181, "z": null, "yaw": 6.274844123050781, "pitch": null, "roll": null}, "v": 2.1194942491151263, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "acceleration": 0.03173703990413579, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019653932584581982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.6390688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26216639710196893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.031818180720427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1202974796422116, "gear": 1, "accelerator_pedal_position": 0.2625723775210014, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.6390688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 38.51456262701955, "y": 0.09763601110562181, "z": null, "yaw": 6.274844123050781, "pitch": null, "roll": null}, "v": 2.1194942491151263, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "acceleration": 0.03173703990413579, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019653932584581982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.6590688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26216639710196893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.031818180720427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121048502350531, "gear": 1, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.6590688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 38.51456262701955, "y": 0.09763601110562181, "z": null, "yaw": 6.274844123050781, "pitch": null, "roll": null}, "v": 2.1194942491151263, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "acceleration": 0.03173703990413579, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019653932584581982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.6790688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26216639710196893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.031818180720427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1217981375517794, "gear": 1, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.6790688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 38.51456262701955, "y": 0.09763601110562181, "z": null, "yaw": 6.274844123050781, "pitch": null, "roll": null}, "v": 2.1194942491151263, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "acceleration": 0.03173703990413579, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019653932584581982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.6990688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26216639710196893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.031818180720427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.122546387584685, "gear": 1, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.6990688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 38.51456262701955, "y": 0.09763601110562181, "z": null, "yaw": 6.274844123050781, "pitch": null, "roll": null}, "v": 2.1194942491151263, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "acceleration": 0.03173703990413579, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019653932584581982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.7190688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26216639710196893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.031818180720427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1232932547849, "gear": 1, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.7190688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.7290688, "x": 42.74790920273608, "y": 5.095581342310276, "z": null, "yaw": -0.009361206988129592, "pitch": null, "roll": null}, "v": 2.1236661705517994, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "acceleration": 0.03725709332025434, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019692618541243004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.7390687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2630547698281597, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9935924419571067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124038741485002, "gear": 1, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.7390687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 38.74790920273608, "y": 0.09558134231027626, "z": null, "yaw": 6.273824100191456, "pitch": null, "roll": null}, "v": 2.1236661705517994, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "acceleration": 0.03725709332025434, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019692618541243004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.7590687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26279643405139563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9935924419571067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.12489384525245, "gear": 1, "accelerator_pedal_position": 0.2630547698281597, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.7590687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 38.74790920273608, "y": 0.09558134231027626, "z": null, "yaw": 6.273824100191456, "pitch": null, "roll": null}, "v": 2.1236661705517994, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "acceleration": 0.03725709332025434, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019692618541243004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.7790687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26279643405139563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9935924419571067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1261251440009, "gear": 1, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.7790687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 38.74790920273608, "y": 0.09558134231027626, "z": null, "yaw": 6.273824100191456, "pitch": null, "roll": null}, "v": 2.1236661705517994, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "acceleration": 0.03725709332025434, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019692618541243004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.7990687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26279643405139563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9935924419571067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1265348177443166, "gear": 1, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.7990687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 38.74790920273608, "y": 0.09558134231027626, "z": null, "yaw": 6.273824100191456, "pitch": null, "roll": null}, "v": 2.1236661705517994, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "acceleration": 0.03725709332025434, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019692618541243004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.8190687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26279643405139563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9935924419571067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1273530283768056, "gear": 1, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.8190687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.8390687, "x": 42.98172594357323, "y": 5.093284011131108, "z": null, "yaw": -0.010381229847453982, "pitch": null, "roll": null}, "v": 2.128169725317225, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "acceleration": 0.040778162757793446, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019734379712233487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.8390687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640113931423123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8783464097028003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128169725317225, "gear": 1, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.8390687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 38.98172594357323, "y": 0.09328401113110818, "z": null, "yaw": 6.2728040773321325, "pitch": null, "roll": null}, "v": 2.128169725317225, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "acceleration": 0.040778162757793446, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019734379712233487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.8590686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26365255126594467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8783464097028003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1291367106908696, "gear": 1, "accelerator_pedal_position": 0.2640113931423123, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.8590686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 38.98172594357323, "y": 0.09328401113110818, "z": null, "yaw": 6.2728040773321325, "pitch": null, "roll": null}, "v": 2.128169725317225, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "acceleration": 0.040778162757793446, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019734379712233487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.8790686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26365255126594467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8783464097028003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1300570719955085, "gear": 1, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.8790686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 38.98172594357323, "y": 0.09328401113110818, "z": null, "yaw": 6.2728040773321325, "pitch": null, "roll": null}, "v": 2.128169725317225, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "acceleration": 0.040778162757793446, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019734379712233487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.8990686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26365255126594467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8783464097028003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.130975729643875, "gear": 1, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.8990686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 38.98172594357323, "y": 0.09328401113110818, "z": null, "yaw": 6.2728040773321325, "pitch": null, "roll": null}, "v": 2.128169725317225, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "acceleration": 0.040778162757793446, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019734379712233487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.9190686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26365255126594467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8783464097028003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131892686452145, "gear": 1, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.9190686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 38.98172594357323, "y": 0.09328401113110818, "z": null, "yaw": 6.2728040773321325, "pitch": null, "roll": null}, "v": 2.128169725317225, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "acceleration": 0.040778162757793446, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019734379712233487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.9390686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26365255126594467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8783464097028003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.132807945233155, "gear": 1, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.9390686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.9490685, "x": 43.21606807144092, "y": 5.090742452887189, "z": null, "yaw": -0.011401252706778373, "pitch": null, "roll": null}, "v": 2.1332649387415348, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "acceleration": 0.04565700548643814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019781627295560145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.9590685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26488483961750997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9092609618337026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133721508796399, "gear": 1, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.9590685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 39.21606807144092, "y": 0.09074245288718874, "z": null, "yaw": 6.271784054472808, "pitch": null, "roll": null}, "v": 2.1332649387415348, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "acceleration": 0.04565700548643814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019781627295560145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.9790685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26452334376374503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9092609618337026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1347873446083434, "gear": 1, "accelerator_pedal_position": 0.26488483961750997, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.9790685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 39.21606807144092, "y": 0.09074245288718874, "z": null, "yaw": 6.271784054472808, "pitch": null, "roll": null}, "v": 2.1332649387415348, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "acceleration": 0.04565700548643814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019781627295560145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.9990685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26452334376374503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9092609618337026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.13580603944456, "gear": 1, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.9990685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 39.21606807144092, "y": 0.09074245288718874, "z": null, "yaw": 6.271784054472808, "pitch": null, "roll": null}, "v": 2.1332649387415348, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "acceleration": 0.04565700548643814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019781627295560145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.0190685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26452334376374503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9092609618337026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1368228462715315, "gear": 1, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.0190685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 39.21606807144092, "y": 0.09074245288718874, "z": null, "yaw": 6.271784054472808, "pitch": null, "roll": null}, "v": 2.1332649387415348, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "acceleration": 0.04565700548643814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019781627295560145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.0390685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26452334376374503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9092609618337026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1378377681750536, "gear": 1, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.0390685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.0590684, "x": 43.45098934205834, "y": 5.087954952728666, "z": null, "yaw": -0.012421275566102763, "pitch": null, "roll": null}, "v": 2.1388508082375, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "acceleration": 0.05058153031254925, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019833424700788214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.0590684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2656146183191462, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9376918904823034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1388508082375, "gear": 1, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.0590684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.45098934205834, "y": 0.0879549527286656, "z": null, "yaw": 6.270764031613483, "pitch": null, "roll": null}, "v": 2.1388508082375, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "acceleration": 0.05058153031254925, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019833424700788214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.0790684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529949122822694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9376918904823034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1399983155716327, "gear": 1, "accelerator_pedal_position": 0.2656146183191462, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.0790684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.45098934205834, "y": 0.0879549527286656, "z": null, "yaw": 6.270764031613483, "pitch": null, "roll": null}, "v": 2.1388508082375, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "acceleration": 0.05058153031254925, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019833424700788214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.0990684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529949122822694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9376918904823034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1411043216459746, "gear": 1, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.0990684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.45098934205834, "y": 0.0879549527286656, "z": null, "yaw": 6.270764031613483, "pitch": null, "roll": null}, "v": 2.1388508082375, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "acceleration": 0.05058153031254925, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019833424700788214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.1190684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529949122822694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9376918904823034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.142208275559684, "gear": 1, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.1190684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.45098934205834, "y": 0.0879549527286656, "z": null, "yaw": 6.270764031613483, "pitch": null, "roll": null}, "v": 2.1388508082375, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "acceleration": 0.05058153031254925, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019833424700788214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.1390684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529949122822694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9376918904823034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.143310180633223, "gear": 1, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.1390684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.45098934205834, "y": 0.0879549527286656, "z": null, "yaw": 6.270764031613483, "pitch": null, "roll": null}, "v": 2.1388508082375, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "acceleration": 0.05058153031254925, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019833424700788214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.1590683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529949122822694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9376918904823034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.144410040183604, "gear": 1, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.1590683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.1690683, "x": 43.68655112322249, "y": 5.084919532932893, "z": null, "yaw": -0.013441298425427153, "pitch": null, "roll": null}, "v": 2.1449592039232326, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "acceleration": 0.054865360115306794, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019890067457454086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.1790683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2736887809949696, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6877222486740463, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1455078575243856, "gear": 1, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.1790683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 39.68655112322249, "y": 0.08491953293289267, "z": null, "yaw": 6.269744008754159, "pitch": null, "roll": null}, "v": 2.1449592039232326, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "acceleration": 0.054865360115306794, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019890067457454086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.1990683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710954808350752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6877222486740463, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1476518099451414, "gear": 1, "accelerator_pedal_position": 0.2736887809949696, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.1990683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 39.68655112322249, "y": 0.08491953293289267, "z": null, "yaw": 6.269744008754159, "pitch": null, "roll": null}, "v": 2.1449592039232326, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "acceleration": 0.054865360115306794, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019890067457454086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.2190683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710954808350752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6877222486740463, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1494677671115685, "gear": 1, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.2190683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 39.68655112322249, "y": 0.08491953293289267, "z": null, "yaw": 6.269744008754159, "pitch": null, "roll": null}, "v": 2.1449592039232326, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "acceleration": 0.054865360115306794, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019890067457454086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.2390683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710954808350752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6877222486740463, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1530895602232953, "gear": 1, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.2390683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 39.68655112322249, "y": 0.08491953293289267, "z": null, "yaw": 6.269744008754159, "pitch": null, "roll": null}, "v": 2.1449592039232326, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "acceleration": 0.054865360115306794, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019890067457454086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.2590683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710954808350752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6877222486740463, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1530895602232953, "gear": 1, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.2590683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.2790682, "x": 43.92296475340714, "y": 5.081631908464363, "z": null, "yaw": -0.014461321284751543, "pitch": null, "roll": null}, "v": 2.154895406087523, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "acceleration": 0.09016624280307256, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019982205215112674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.2790682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28505772963983866, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.44841166640435354, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.154895406087523, "gear": 1, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.2790682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 39.92296475340714, "y": 0.08163190846436308, "z": null, "yaw": 6.268723985894835, "pitch": null, "roll": null}, "v": 2.154895406087523, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "acceleration": 0.09016624280307256, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019982205215112674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.2990682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28074072667565414, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.44841166640435354, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.158442359890408, "gear": 1, "accelerator_pedal_position": 0.28505772963983866, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.2990682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 39.92296475340714, "y": 0.08163190846436308, "z": null, "yaw": 6.268723985894835, "pitch": null, "roll": null}, "v": 2.154895406087523, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "acceleration": 0.09016624280307256, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019982205215112674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.3190682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28074072667565414, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.44841166640435354, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1614433348168998, "gear": 1, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.3190682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 39.92296475340714, "y": 0.08163190846436308, "z": null, "yaw": 6.268723985894835, "pitch": null, "roll": null}, "v": 2.154895406087523, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "acceleration": 0.09016624280307256, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019982205215112674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.3390682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28074072667565414, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.44841166640435354, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1644387177020623, "gear": 1, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.3390682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 39.92296475340714, "y": 0.08163190846436308, "z": null, "yaw": 6.268723985894835, "pitch": null, "roll": null}, "v": 2.154895406087523, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "acceleration": 0.09016624280307256, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019982205215112674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.3590682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28074072667565414, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.44841166640435354, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.167428515378896, "gear": 1, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.3590682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 39.92296475340714, "y": 0.08163190846436308, "z": null, "yaw": 6.268723985894835, "pitch": null, "roll": null}, "v": 2.154895406087523, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "acceleration": 0.09016624280307256, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019982205215112674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.3790681} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28074072667565414, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.44841166640435354, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.170412734687725, "gear": 1, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.3790681} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.3890681, "x": 44.160852959886405, "y": 5.0780810146413335, "z": null, "yaw": -0.015481344144075933, "pitch": null, "roll": null}, "v": 2.17190275459372, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "acceleration": 0.14886278823903443, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02013991325377465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.399068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28060817833430174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4397439462532978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1733913824761104, "gear": 1, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.399068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 40.160852959886405, "y": 0.07808101464133355, "z": null, "yaw": 6.26770396303551, "pitch": null, "roll": null}, "v": 2.17190275459372, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "acceleration": 0.14886278823903443, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02013991325377465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.419068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2807289118235162, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4397439462532978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.176347904801686, "gear": 1, "accelerator_pedal_position": 0.28060817833430174, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.419068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 40.160852959886405, "y": 0.07808101464133355, "z": null, "yaw": 6.26770396303551, "pitch": null, "roll": null}, "v": 2.17190275459372, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "acceleration": 0.14886278823903443, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02013991325377465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.439068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2807289118235162, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4397439462532978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.180794943974859, "gear": 1, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.439068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 40.160852959886405, "y": 0.07808101464133355, "z": null, "yaw": 6.26770396303551, "pitch": null, "roll": null}, "v": 2.17190275459372, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "acceleration": 0.14886278823903443, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02013991325377465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.459068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2807289118235162, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4397439462532978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1822745168330746, "gear": 1, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.459068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 40.160852959886405, "y": 0.07808101464133355, "z": null, "yaw": 6.26770396303551, "pitch": null, "roll": null}, "v": 2.17190275459372, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "acceleration": 0.14886278823903443, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02013991325377465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.479068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2807289118235162, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4397439462532978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1852295074063584, "gear": 1, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.479068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.499068, "x": 44.40054661975757, "y": 5.07425862647786, "z": null, "yaw": -0.01650136700340034, "pitch": null, "roll": null}, "v": 2.1881789635234625, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "acceleration": 0.14726547895673708, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020290841482606257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.499068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2806750837736217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4304856816785004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1881789635234625, "gear": 1, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.499068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.40054661975757, "y": 0.07425862647786019, "z": null, "yaw": 6.266683940176186, "pitch": null, "roll": null}, "v": 2.1881789635234625, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "acceleration": 0.14726547895673708, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020290841482606257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.519068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28076807842300755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4304856816785004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.191116166721082, "gear": 1, "accelerator_pedal_position": 0.2806750837736217, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.519068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.40054661975757, "y": 0.07425862647786019, "z": null, "yaw": 6.266683940176186, "pitch": null, "roll": null}, "v": 2.1881789635234625, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "acceleration": 0.14726547895673708, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020290841482606257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.539068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28076807842300755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4304856816785004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.194059480738318, "gear": 1, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.539068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.40054661975757, "y": 0.07425862647786019, "z": null, "yaw": 6.266683940176186, "pitch": null, "roll": null}, "v": 2.1881789635234625, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "acceleration": 0.14726547895673708, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020290841482606257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.559068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28076807842300755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4304856816785004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.196997271779171, "gear": 1, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.559068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.40054661975757, "y": 0.07425862647786019, "z": null, "yaw": 6.266683940176186, "pitch": null, "roll": null}, "v": 2.1881789635234625, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "acceleration": 0.14726547895673708, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020290841482606257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.579068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28076807842300755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4304856816785004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1999295467565942, "gear": 1, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.579068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.40054661975757, "y": 0.07425862647786019, "z": null, "yaw": 6.266683940176186, "pitch": null, "roll": null}, "v": 2.1881789635234625, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "acceleration": 0.14726547895673708, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020290841482606257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.599068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28076807842300755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4304856816785004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.202856312589995, "gear": 1, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.599068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.609068, "x": 44.6420194662428, "y": 5.070161493477429, "z": null, "yaw": -0.017521389862724748, "pitch": null, "roll": null}, "v": 2.204317631741746, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "acceleration": 0.1459944463406344, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020440494305349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.619068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2807036392139631, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4197839358357152, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2057775762051524, "gear": 1, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.619068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 40.6420194662428, "y": 0.07016149347742928, "z": null, "yaw": 6.265663917316862, "pitch": null, "roll": null}, "v": 2.204317631741746, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "acceleration": 0.1459944463406344, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020440494305349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.639068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28079956772283127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4197839358357152, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.210143094688064, "gear": 1, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.639068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 40.6420194662428, "y": 0.07016149347742928, "z": null, "yaw": 6.265663917316862, "pitch": null, "roll": null}, "v": 2.204317631741746, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "acceleration": 0.1459944463406344, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020440494305349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.6690679} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28079956772283127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4197839358357152, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2130545788497797, "gear": 1, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.6690679} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 40.6420194662428, "y": 0.07016149347742928, "z": null, "yaw": 6.265663917316862, "pitch": null, "roll": null}, "v": 2.204317631741746, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "acceleration": 0.1459944463406344, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020440494305349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.6890678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28079956772283127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4197839358357152, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2174115222178443, "gear": 1, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.6890678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 40.6420194662428, "y": 0.07016149347742928, "z": null, "yaw": 6.265663917316862, "pitch": null, "roll": null}, "v": 2.204317631741746, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "acceleration": 0.1459944463406344, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020440494305349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.7090678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28079956772283127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4197839358357152, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2188610980535257, "gear": 1, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.7090678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.7190678, "x": 44.88525562182719, "y": 5.065786262191647, "z": null, "yaw": -0.018541412722049157, "pitch": null, "roll": null}, "v": 2.2203093060299306, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "acceleration": 0.1446840988217677, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020588784062920074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.7290678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29564437078188066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.178971657072768, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2217561470181484, "gear": 1, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.7290678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 40.88525562182719, "y": 0.06578626219164718, "z": null, "yaw": 6.264643894457537, "pitch": null, "roll": null}, "v": 2.2203093060299306, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "acceleration": 0.1446840988217677, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020588784062920074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.7490678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29108072461590634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.178971657072768, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.226500455375036, "gear": 1, "accelerator_pedal_position": 0.29564437078188066, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.7490678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 40.88525562182719, "y": 0.06578626219164718, "z": null, "yaw": 6.264643894457537, "pitch": null, "roll": null}, "v": 2.2203093060299306, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "acceleration": 0.1446840988217677, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020588784062920074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.7690678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29108072461590634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.178971657072768, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2306656146131307, "gear": 1, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.7690678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 40.88525562182719, "y": 0.06578626219164718, "z": null, "yaw": 6.264643894457537, "pitch": null, "roll": null}, "v": 2.2203093060299306, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "acceleration": 0.1446840988217677, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020588784062920074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.7890677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29108072461590634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.178971657072768, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2348228977235403, "gear": 1, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.7890677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 40.88525562182719, "y": 0.06578626219164718, "z": null, "yaw": 6.264643894457537, "pitch": null, "roll": null}, "v": 2.2203093060299306, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "acceleration": 0.1446840988217677, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020588784062920074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.8090677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29108072461590634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.178971657072768, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2389723126897354, "gear": 1, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.8090677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.8290677, "x": 45.130575577449626, "y": 5.061123165583551, "z": null, "yaw": -0.019561435581373566, "pitch": null, "roll": null}, "v": 2.243113867519301, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "acceleration": 0.20678323724687553, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02080024928124759, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.8290677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29085092957988234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1357944972936403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.243113867519301, "gear": 1, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.8290677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.130575577449626, "y": 0.06112316558355069, "z": null, "yaw": 6.263623871598213, "pitch": null, "roll": null}, "v": 2.243113867519301, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "acceleration": 0.20678323724687553, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02080024928124759, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.8490677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29103064525430117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1357944972936403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2472188594944815, "gear": 1, "accelerator_pedal_position": 0.29085092957988234, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.8490677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.130575577449626, "y": 0.06112316558355069, "z": null, "yaw": 6.263623871598213, "pitch": null, "roll": null}, "v": 2.243113867519301, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "acceleration": 0.20678323724687553, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02080024928124759, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.8690677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29103064525430117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1357944972936403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2513385157265606, "gear": 1, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.8690677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.130575577449626, "y": 0.06112316558355069, "z": null, "yaw": 6.263623871598213, "pitch": null, "roll": null}, "v": 2.243113867519301, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "acceleration": 0.20678323724687553, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02080024928124759, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.8890676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29103064525430117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1357944972936403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2554503478225434, "gear": 1, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.8890676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.130575577449626, "y": 0.06112316558355069, "z": null, "yaw": 6.263623871598213, "pitch": null, "roll": null}, "v": 2.243113867519301, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "acceleration": 0.20678323724687553, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02080024928124759, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.9090676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29103064525430117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1357944972936403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2595543638825384, "gear": 1, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.9090676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.130575577449626, "y": 0.06112316558355069, "z": null, "yaw": 6.263623871598213, "pitch": null, "roll": null}, "v": 2.243113867519301, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "acceleration": 0.20678323724687553, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02080024928124759, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.9290676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29103064525430117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1357944972936403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2636505720297957, "gear": 1, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.9290676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.9390676, "x": 45.37839862243923, "y": 5.056159615641147, "z": null, "yaw": -0.020581458440697975, "pitch": null, "roll": null}, "v": 2.2656957506809494, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "acceleration": 0.2043229729587976, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021009649617897353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.9490676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29096469401081576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07718871766117479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2677389804105372, "gear": 1, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.9490676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 41.37839862243923, "y": 0.05615961564114702, "z": null, "yaw": 6.262603848738888, "pitch": null, "roll": null}, "v": 2.2656957506809494, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "acceleration": 0.2043229729587976, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021009649617897353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.9690676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29109266727221306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07718871766117479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.271811357220511, "gear": 1, "accelerator_pedal_position": 0.29096469401081576, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.9690676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 41.37839862243923, "y": 0.05615961564114702, "z": null, "yaw": 6.262603848738888, "pitch": null, "roll": null}, "v": 2.2656957506809494, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "acceleration": 0.2043229729587976, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021009649617897353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.9890676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29109266727221306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07718871766117479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275891955372815, "gear": 1, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.9890676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 41.37839862243923, "y": 0.05615961564114702, "z": null, "yaw": 6.262603848738888, "pitch": null, "roll": null}, "v": 2.2656957506809494, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "acceleration": 0.2043229729587976, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021009649617897353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.0090675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29109266727221306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07718871766117479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2799647635140934, "gear": 1, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.0090675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 41.37839862243923, "y": 0.05615961564114702, "z": null, "yaw": 6.262603848738888, "pitch": null, "roll": null}, "v": 2.2656957506809494, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "acceleration": 0.2043229729587976, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021009649617897353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.0290675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29109266727221306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07718871766117479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2840297898838235, "gear": 1, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.0290675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.0490675, "x": 45.62869065371662, "y": 5.050891207946068, "z": null, "yaw": -0.021601481300022384, "pitch": null, "roll": null}, "v": 2.2880870427437467, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "acceleration": 0.20257139516242595, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021217282615659736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.0490675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24423739596169775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5022090373020178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2880870427437467, "gear": 1, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.0490675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 41.62869065371662, "y": 0.050891207946068384, "z": null, "yaw": 6.261583825879564, "pitch": null, "roll": null}, "v": 2.2880870427437467, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "acceleration": 0.20257139516242595, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021217282615659736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.0690675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25898663868700694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5022090373020178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2862824261317103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4332093910525168, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.0690675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 41.62869065371662, "y": 0.050891207946068384, "z": null, "yaw": 6.261583825879564, "pitch": null, "roll": null}, "v": 2.2880870427437467, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "acceleration": 0.20257139516242595, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021217282615659736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.0890675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25898663868700694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5022090373020178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2863240361497366, "gear": 1, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3529316420907091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.0890675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 41.62869065371662, "y": 0.050891207946068384, "z": null, "yaw": 6.261583825879564, "pitch": null, "roll": null}, "v": 2.2880870427437467, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "acceleration": 0.20257139516242595, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021217282615659736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.1090674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25898663868700694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5022090373020178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.286365566542454, "gear": 1, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3529316420907091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.1090674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 41.62869065371662, "y": 0.050891207946068384, "z": null, "yaw": 6.261583825879564, "pitch": null, "roll": null}, "v": 2.2880870427437467, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "acceleration": 0.20257139516242595, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021217282615659736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.1290674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25898663868700694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5022090373020178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2864070174615443, "gear": 1, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3529316420907091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.1290674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 41.62869065371662, "y": 0.050891207946068384, "z": null, "yaw": 6.261583825879564, "pitch": null, "roll": null}, "v": 2.2880870427437467, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "acceleration": 0.20257139516242595, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021217282615659736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.1490674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25898663868700694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5022090373020178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2864483890584033, "gear": 1, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3529316420907091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.1490674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.1590674, "x": 45.880155505141815, "y": 5.045363353823047, "z": null, "yaw": -0.02237402093052993, "pitch": null, "roll": null}, "v": 2.2864690451582295, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "acceleration": 0.0020636325912139486, "steering_wheel_angle": -0.3529316420907091, "front_wheel_angle": -0.016283743572151333, "heading_rate": -0.014545143283832792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.1690674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25684202343715656, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5741949583017796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2864896814841416, "gear": 1, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3529316420907091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.1690674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 41.880155505141815, "y": 0.04536335382304735, "z": null, "yaw": 6.260811286249056, "pitch": null, "roll": null}, "v": 2.2864690451582295, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "acceleration": 0.0020636325912139486, "steering_wheel_angle": -0.3529316420907091, "front_wheel_angle": -0.016283743572151333, "heading_rate": -0.014545143283832792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.1890674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25750447033275253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5741949583017796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.286262946296843, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27232490002694176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.1890674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 41.880155505141815, "y": 0.04536335382304735, "z": null, "yaw": 6.260811286249056, "pitch": null, "roll": null}, "v": 2.2864690451582295, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "acceleration": 0.0020636325912139486, "steering_wheel_angle": -0.3529316420907091, "front_wheel_angle": -0.016283743572151333, "heading_rate": -0.014545143283832792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.2090673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25750447033275253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5741949583017796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2861194112222605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27232490002694176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.2090673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 41.880155505141815, "y": 0.04536335382304735, "z": null, "yaw": 6.260811286249056, "pitch": null, "roll": null}, "v": 2.2864690451582295, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "acceleration": 0.0020636325912139486, "steering_wheel_angle": -0.3529316420907091, "front_wheel_angle": -0.016283743572151333, "heading_rate": -0.014545143283832792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.2290673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25750447033275253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5741949583017796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.285976150808622, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27232490002694176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.2290673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 41.880155505141815, "y": 0.04536335382304735, "z": null, "yaw": 6.260811286249056, "pitch": null, "roll": null}, "v": 2.2864690451582295, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "acceleration": 0.0020636325912139486, "steering_wheel_angle": -0.3529316420907091, "front_wheel_angle": -0.016283743572151333, "heading_rate": -0.014545143283832792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.2490673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25750447033275253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5741949583017796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2858331645221455, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27232490002694176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.2490673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.2690673, "x": 46.13156532001124, "y": 5.039668035544989, "z": null, "yaw": -0.022949818105578744, "pitch": null, "roll": null}, "v": 2.285690451830118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665283310073796, "steering_wheel_angle": -0.27232490002694176, "front_wheel_angle": -0.012551243178401608, "heading_rate": -0.011206938766482615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.2690673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23508526738213165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8390876015885809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.285690451830118, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27232490002694176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.2690673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.13156532001124, "y": 0.03966803554498899, "z": null, "yaw": 6.260235489074008, "pitch": null, "roll": null}, "v": 2.285690451830118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665283310073796, "steering_wheel_angle": -0.27232490002694176, "front_wheel_angle": -0.012551243178401608, "heading_rate": -0.011206938766482615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.2890673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24208754648549263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8390876015885809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2827469527578286, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1909595867181437, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.2890673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.13156532001124, "y": 0.03966803554498899, "z": null, "yaw": 6.260235489074008, "pitch": null, "roll": null}, "v": 2.285690451830118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665283310073796, "steering_wheel_angle": -0.27232490002694176, "front_wheel_angle": -0.012551243178401608, "heading_rate": -0.011206938766482615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.3090672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24208754648549263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8390876015885809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2806839494335573, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.109418704344607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.3090672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.13156532001124, "y": 0.03966803554498899, "z": null, "yaw": 6.260235489074008, "pitch": null, "roll": null}, "v": 2.285690451830118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665283310073796, "steering_wheel_angle": -0.27232490002694176, "front_wheel_angle": -0.012551243178401608, "heading_rate": -0.011206938766482615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.3290672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24208754648549263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8390876015885809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2786248896754397, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02770225290633157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.3290672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.13156532001124, "y": 0.03966803554498899, "z": null, "yaw": 6.260235489074008, "pitch": null, "roll": null}, "v": 2.285690451830118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665283310073796, "steering_wheel_angle": -0.27232490002694176, "front_wheel_angle": -0.012551243178401608, "heading_rate": -0.011206938766482615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.3490672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24208754648549263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8390876015885809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2765697642500093, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013217232987496627, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.3490672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.13156532001124, "y": 0.03966803554498899, "z": null, "yaw": 6.260235489074008, "pitch": null, "roll": null}, "v": 2.285690451830118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665283310073796, "steering_wheel_angle": -0.27232490002694176, "front_wheel_angle": -0.012551243178401608, "heading_rate": -0.011206938766482615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.3690672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24208754648549263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8390876015885809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2745185639511605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013217232987496627, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.3690672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.3790672, "x": 46.38227410688138, "y": 5.0338787909292195, "z": null, "yaw": -0.023129336670811965, "pitch": null, "roll": null}, "v": 2.2734944328547524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36536249100495316, "steering_wheel_angle": 0.013217232987496627, "front_wheel_angle": 0.0006070963076827579, "heading_rate": 0.0005391524395672043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.3890672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3146090898023577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.272471279600046, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013217232987496627, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.3890672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 42.38227410688138, "y": 0.03387879092921953, "z": null, "yaw": 6.260055970508774, "pitch": null, "roll": null}, "v": 2.2734944328547524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36536249100495316, "steering_wheel_angle": 0.013217232987496627, "front_wheel_angle": 0.0006070963076827579, "heading_rate": 0.0005391524395672043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.4090672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3146090898023577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2651694682746775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.09605129563692612, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.4090672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 42.38227410688138, "y": 0.03387879092921953, "z": null, "yaw": 6.260055970508774, "pitch": null, "roll": null}, "v": 2.2734944328547524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36536249100495316, "steering_wheel_angle": 0.013217232987496627, "front_wheel_angle": 0.0006070963076827579, "heading_rate": 0.0005391524395672043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.4290671} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3146090898023577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2578815733937243, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.17870508597973944, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.4290671} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 42.38227410688138, "y": 0.03387879092921953, "z": null, "yaw": 6.260055970508774, "pitch": null, "roll": null}, "v": 2.2734944328547524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36536249100495316, "steering_wheel_angle": 0.013217232987496627, "front_wheel_angle": 0.0006070963076827579, "heading_rate": 0.0005391524395672043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.449067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3146090898023577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2506075471987175, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26117860401593657, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.449067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 42.38227410688138, "y": 0.03387879092921953, "z": null, "yaw": 6.260055970508774, "pitch": null, "roll": null}, "v": 2.2734944328547524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36536249100495316, "steering_wheel_angle": 0.013217232987496627, "front_wheel_angle": 0.0006070963076827579, "heading_rate": 0.0005391524395672043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.469067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3146090898023577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.243347342143348, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3434718497455176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.469067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.489067, "x": 46.63055076206798, "y": 5.028158289059372, "z": null, "yaw": -0.022768406064869757, "pitch": null, "roll": null}, "v": 2.2361009108922802, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36180651838154687, "steering_wheel_angle": 0.42558482316848234, "front_wheel_angle": 0.01965484081046068, "heading_rate": 0.017170260868413976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.489067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22656280754309205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3625886585178872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2361009108922802, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.42558482316848234, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.489067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 42.63055076206798, "y": 0.028158289059372343, "z": null, "yaw": 6.260416901114716, "pitch": null, "roll": null}, "v": 2.2361009108922802, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36180651838154687, "steering_wheel_angle": 0.42558482316848234, "front_wheel_angle": 0.01965484081046068, "heading_rate": 0.017170260868413976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.509067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22152120117517687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3625886585178872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2321869856368526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5076283563940936, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.509067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 42.63055076206798, "y": 0.028158289059372343, "z": null, "yaw": 6.260416901114716, "pitch": null, "roll": null}, "v": 2.2361009108922802, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36180651838154687, "steering_wheel_angle": 0.42558482316848234, "front_wheel_angle": 0.01965484081046068, "heading_rate": 0.017170260868413976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.529067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22152120117517687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3625886585178872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2276505642708986, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5485823376726022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.529067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 42.63055076206798, "y": 0.028158289059372343, "z": null, "yaw": 6.260416901114716, "pitch": null, "roll": null}, "v": 2.2361009108922802, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36180651838154687, "steering_wheel_angle": 0.42558482316848234, "front_wheel_angle": 0.01965484081046068, "heading_rate": 0.017170260868413976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.549067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22152120117517687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3625886585178872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2231227195522103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5485823376726022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.549067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 42.63055076206798, "y": 0.028158289059372343, "z": null, "yaw": 6.260416901114716, "pitch": null, "roll": null}, "v": 2.2361009108922802, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36180651838154687, "steering_wheel_angle": 0.42558482316848234, "front_wheel_angle": 0.01965484081046068, "heading_rate": 0.017170260868413976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.569067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22152120117517687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3625886585178872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.218603427068929, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5485823376726022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.569067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 42.63055076206798, "y": 0.028158289059372343, "z": null, "yaw": 6.260416901114716, "pitch": null, "roll": null}, "v": 2.2361009108922802, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36180651838154687, "steering_wheel_angle": 0.42558482316848234, "front_wheel_angle": 0.01965484081046068, "heading_rate": 0.017170260868413976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.589067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22152120117517687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3625886585178872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2140926625017614, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5485823376726022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.589067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.599067, "x": 46.87527395127038, "y": 5.022697224619581, "z": null, "yaw": -0.021722485832598615, "pitch": null, "roll": null}, "v": 2.211840470612145, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3595144062049848, "steering_wheel_angle": 0.5485823376726022, "front_wheel_angle": 0.025376902572899887, "heading_rate": 0.02193035631302009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.609067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2331604672567738, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4154510994080107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2095904016235437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5485823376726022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.609067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 42.87527395127038, "y": 0.02269722461958068, "z": null, "yaw": 6.261462821346988, "pitch": null, "roll": null}, "v": 2.211840470612145, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3595144062049848, "steering_wheel_angle": 0.5485823376726022, "front_wheel_angle": 0.025376902572899887, "heading_rate": 0.02193035631302009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.629067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22940858853752327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4154510994080107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2065508436309416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5895523105158035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.629067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 42.87527395127038, "y": 0.02269722461958068, "z": null, "yaw": 6.261462821346988, "pitch": null, "roll": null}, "v": 2.211840470612145, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3595144062049848, "steering_wheel_angle": 0.5485823376726022, "front_wheel_angle": 0.025376902572899887, "heading_rate": 0.02193035631302009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.649067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22940858853752327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4154510994080107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2030482420157638, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5895523105158035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.649067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 42.87527395127038, "y": 0.02269722461958068, "z": null, "yaw": 6.261462821346988, "pitch": null, "roll": null}, "v": 2.211840470612145, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3595144062049848, "steering_wheel_angle": 0.5485823376726022, "front_wheel_angle": 0.025376902572899887, "heading_rate": 0.02193035631302009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.669067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22940858853752327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4154510994080107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.199552227689663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5895523105158035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.669067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 42.87527395127038, "y": 0.02269722461958068, "z": null, "yaw": 6.261462821346988, "pitch": null, "roll": null}, "v": 2.211840470612145, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3595144062049848, "steering_wheel_angle": 0.5485823376726022, "front_wheel_angle": 0.025376902572899887, "heading_rate": 0.02193035631302009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.689067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22940858853752327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4154510994080107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1960627833774744, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5895523105158035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.689067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.7090669, "x": 47.117548869564786, "y": 5.017559468562168, "z": null, "yaw": -0.020564635560362778, "pitch": null, "roll": null}, "v": 2.192579891864054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35770306041526856, "steering_wheel_angle": 0.5895523105158035, "front_wheel_angle": 0.027287110645736048, "heading_rate": 0.023376571821027346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.7090669} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9350945517560276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.192579891864054, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5895523105158035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.7090669} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.117548869564786, "y": 0.017559468562168057, "z": null, "yaw": 6.262620671619223, "pitch": null, "roll": null}, "v": 2.192579891864054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35770306041526856, "steering_wheel_angle": 0.5895523105158035, "front_wheel_angle": 0.027287110645736048, "heading_rate": 0.023376571821027346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.7290668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9350945517560276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.185429186476611, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.6725863671022435, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.7290668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.117548869564786, "y": 0.017559468562168057, "z": null, "yaw": 6.262620671619223, "pitch": null, "roll": null}, "v": 2.192579891864054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35770306041526856, "steering_wheel_angle": 0.5895523105158035, "front_wheel_angle": 0.027287110645736048, "heading_rate": 0.023376571821027346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.7490668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9350945517560276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.178291881570271, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.7554336216961034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.7490668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.117548869564786, "y": 0.017559468562168057, "z": null, "yaw": 6.262620671619223, "pitch": null, "roll": null}, "v": 2.192579891864054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35770306041526856, "steering_wheel_angle": 0.5895523105158035, "front_wheel_angle": 0.027287110645736048, "heading_rate": 0.023376571821027346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.7690668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9350945517560276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.171167931665497, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.8380940742973836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.7690668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.117548869564786, "y": 0.017559468562168057, "z": null, "yaw": 6.262620671619223, "pitch": null, "roll": null}, "v": 2.192579891864054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35770306041526856, "steering_wheel_angle": 0.5895523105158035, "front_wheel_angle": 0.027287110645736048, "heading_rate": 0.023376571821027346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.7890668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9350945517560276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.164057291482223, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.9205677249060837, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.7890668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.117548869564786, "y": 0.017559468562168057, "z": null, "yaw": 6.262620671619223, "pitch": null, "roll": null}, "v": 2.192579891864054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35770306041526856, "steering_wheel_angle": 0.5895523105158035, "front_wheel_angle": 0.027287110645736048, "heading_rate": 0.023376571821027346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.8090668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9350945517560276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1569599159387542, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.002854573522204, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.8090668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.8190668, "x": 47.35672332394124, "y": 5.012794452863626, "z": null, "yaw": -0.018974783487599227, "pitch": null, "roll": null}, "v": 2.1534161883728884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35404282222210864, "steering_wheel_angle": 1.043927947083047, "front_wheel_angle": 0.04861571737874103, "heading_rate": 0.040926729927091184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.8290668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03270414014979029, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.560128081155279, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1498757601506675, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.0849546201457445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.8290668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 43.35672332394124, "y": 0.012794452863626127, "z": null, "yaw": 6.264210523691987, "pitch": null, "roll": null}, "v": 2.1534161883728884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35404282222210864, "steering_wheel_angle": 1.043927947083047, "front_wheel_angle": 0.04861571737874103, "heading_rate": 0.040926729927091184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.8490667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022094389204309388, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.560128081155279, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1375745475933923, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03270414014979029, "steering_wheel_angle": 1.1684026313132372, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.8490667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 43.35672332394124, "y": 0.012794452863626127, "z": null, "yaw": 6.264210523691987, "pitch": null, "roll": null}, "v": 2.1534161883728884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35404282222210864, "steering_wheel_angle": 1.043927947083047, "front_wheel_angle": 0.04861571737874103, "heading_rate": 0.040926729927091184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.8690667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022094389204309388, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.560128081155279, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.126992932560354, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "steering_wheel_angle": 1.2516567665900236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.8690667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 43.35672332394124, "y": 0.012794452863626127, "z": null, "yaw": 6.264210523691987, "pitch": null, "roll": null}, "v": 2.1534161883728884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35404282222210864, "steering_wheel_angle": 1.043927947083047, "front_wheel_angle": 0.04861571737874103, "heading_rate": 0.040926729927091184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.8890667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022094389204309388, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.560128081155279, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.116430904080678, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "steering_wheel_angle": 1.334717025976103, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.8890667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 43.35672332394124, "y": 0.012794452863626127, "z": null, "yaw": 6.264210523691987, "pitch": null, "roll": null}, "v": 2.1534161883728884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35404282222210864, "steering_wheel_angle": 1.043927947083047, "front_wheel_angle": 0.04861571737874103, "heading_rate": 0.040926729927091184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.9090667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022094389204309388, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.560128081155279, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105888381297687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "steering_wheel_angle": 1.4175834094714752, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.9090667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.9290667, "x": 47.59068245067479, "y": 5.008602700397869, "z": null, "yaw": -0.016459895357891233, "pitch": null, "roll": null}, "v": 2.095365283751279, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "acceleration": -0.5254289345455398, "steering_wheel_angle": 1.5002559170761414, "front_wheel_angle": 0.07030804042266567, "heading_rate": 0.057642287026921965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.9290667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.568668417459568, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095365283751279, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "steering_wheel_angle": 1.5002559170761414, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.9290667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 43.59068245067479, "y": 0.008602700397869256, "z": null, "yaw": 6.266725411821695, "pitch": null, "roll": null}, "v": 2.095365283751279, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "acceleration": -0.5254289345455398, "steering_wheel_angle": 1.5002559170761414, "front_wheel_angle": 0.07030804042266567, "heading_rate": 0.057642287026921965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.9490666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.568668417459568, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0883950106844673, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.5827558703083306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.9490666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 43.59068245067479, "y": 0.008602700397869256, "z": null, "yaw": 6.266725411821695, "pitch": null, "roll": null}, "v": 2.095365283751279, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "acceleration": -0.5254289345455398, "steering_wheel_angle": 1.5002559170761414, "front_wheel_angle": 0.07030804042266567, "heading_rate": 0.057642287026921965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.9690666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.568668417459568, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.081437529550451, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.665061847281289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.9690666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 43.59068245067479, "y": 0.008602700397869256, "z": null, "yaw": 6.266725411821695, "pitch": null, "roll": null}, "v": 2.095365283751279, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "acceleration": -0.5254289345455398, "steering_wheel_angle": 1.5002559170761414, "front_wheel_angle": 0.07030804042266567, "heading_rate": 0.057642287026921965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.9890666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.568668417459568, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0744927975195586, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.747173847995016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.9890666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 43.59068245067479, "y": 0.008602700397869256, "z": null, "yaw": 6.266725411821695, "pitch": null, "roll": null}, "v": 2.095365283751279, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "acceleration": -0.5254289345455398, "steering_wheel_angle": 1.5002559170761414, "front_wheel_angle": 0.07030804042266567, "heading_rate": 0.057642287026921965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.0090666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.568668417459568, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0675607719470364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.0090666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 43.59068245067479, "y": 0.008602700397869256, "z": null, "yaw": 6.266725411821695, "pitch": null, "roll": null}, "v": 2.095365283751279, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "acceleration": -0.5254289345455398, "steering_wheel_angle": 1.5002559170761414, "front_wheel_angle": 0.07030804042266567, "heading_rate": 0.057642287026921965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.0290666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.568668417459568, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.060641410372039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.0290666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.0390666, "x": 47.81923445255131, "y": 5.005179654825905, "z": null, "yaw": -0.013053465477430425, "pitch": null, "roll": null}, "v": 2.057186465364639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34517948480102656, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.06777311157539678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.0490665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5946751992376633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.053734670516629, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.0490665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 43.81923445255131, "y": 0.005179654825904656, "z": null, "yaw": 6.270131841702156, "pitch": null, "roll": null}, "v": 2.057186465364639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34517948480102656, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.06777311157539678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.0690665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5946751992376633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0468405102847815, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.0690665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 43.81923445255131, "y": 0.005179654825904656, "z": null, "yaw": 6.270131841702156, "pitch": null, "roll": null}, "v": 2.057186465364639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34517948480102656, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.06777311157539678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.0890665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5946751992376633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0399588877613977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.0890665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 43.81923445255131, "y": 0.005179654825904656, "z": null, "yaw": 6.270131841702156, "pitch": null, "roll": null}, "v": 2.057186465364639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34517948480102656, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.06777311157539678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.1090665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5946751992376633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0330897612113223, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.1090665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 43.81923445255131, "y": 0.005179654825904656, "z": null, "yaw": 6.270131841702156, "pitch": null, "roll": null}, "v": 2.057186465364639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34517948480102656, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.06777311157539678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.1290665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5946751992376633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.026233089078368, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.1290665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.1490664, "x": 48.043616915300525, "y": 5.002618938349344, "z": null, "yaw": -0.00942956341565392, "pitch": null, "roll": null}, "v": 2.019388829984348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.341748753965873, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.0665278849500794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.1490664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.97231792864781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.019388829984348, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.1490664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.043616915300525, "y": 0.0026189383493440133, "z": null, "yaw": 6.273755743763933, "pitch": null, "roll": null}, "v": 2.019388829984348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.341748753965873, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.0665278849500794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.1690664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.97231792864781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.012556942728111, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.8709966816536787, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.1690664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.043616915300525, "y": 0.0026189383493440133, "z": null, "yaw": 6.273755743763933, "pitch": null, "roll": null}, "v": 2.019388829984348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.341748753965873, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.0665278849500794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.1890664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.97231792864781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0057373862845873, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.9536374144850583, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.1890664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.043616915300525, "y": 0.0026189383493440133, "z": null, "yaw": 6.273755743763933, "pitch": null, "roll": null}, "v": 2.019388829984348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.341748753965873, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.0665278849500794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.2090664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.97231792864781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9989301198038356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.036079305748806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.2090664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.043616915300525, "y": 0.0026189383493440133, "z": null, "yaw": 6.273755743763933, "pitch": null, "roll": null}, "v": 2.019388829984348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.341748753965873, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.0665278849500794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.2290664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.97231792864781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9921351026101022, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.118322355444921, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.2290664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.043616915300525, "y": 0.0026189383493440133, "z": null, "yaw": 6.273755743763933, "pitch": null, "roll": null}, "v": 2.019388829984348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.341748753965873, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.0665278849500794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.2490664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.97231792864781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9853522942008803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.2003665635734055, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.2490664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.2590663, "x": 48.26386852039332, "y": 5.0009294907662944, "z": null, "yaw": -0.005372271510060315, "pitch": null, "roll": null}, "v": 1.981965455680571, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33838014345913947, "steering_wheel_angle": 2.2003665635734055, "front_wheel_angle": 0.1041436977205166, "heading_rate": 0.08092136519675153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.2690663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.054013307997451715, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9620177541994455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9785816542459795, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.2003665635734055, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.2690663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 44.26386852039332, "y": 0.0009294907662944496, "z": null, "yaw": 6.277813035669526, "pitch": null, "roll": null}, "v": 1.981965455680571, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33838014345913947, "steering_wheel_angle": 2.2003665635734055, "front_wheel_angle": 0.1041436977205166, "heading_rate": 0.08092136519675153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.2890663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03706519720565103, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9620177541994455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9631848789663071, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.054013307997451715, "steering_wheel_angle": 2.28484764841897, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.2890663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 44.26386852039332, "y": 0.0009294907662944496, "z": null, "yaw": 6.277813035669526, "pitch": null, "roll": null}, "v": 1.981965455680571, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33838014345913947, "steering_wheel_angle": 2.2003665635734055, "front_wheel_angle": 0.1041436977205166, "heading_rate": 0.08092136519675153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.3090663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03706519720565103, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9620177541994455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9505260919225984, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "steering_wheel_angle": 2.3691168620441854, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.3090663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 44.26386852039332, "y": 0.0009294907662944496, "z": null, "yaw": 6.277813035669526, "pitch": null, "roll": null}, "v": 1.981965455680571, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33838014345913947, "steering_wheel_angle": 2.2003665635734055, "front_wheel_angle": 0.1041436977205166, "heading_rate": 0.08092136519675153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.3290663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03706519720565103, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9620177541994455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9378898461716583, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "steering_wheel_angle": 2.45317420444905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.3290663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 44.26386852039332, "y": 0.0009294907662944496, "z": null, "yaw": 6.277813035669526, "pitch": null, "roll": null}, "v": 1.981965455680571, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33838014345913947, "steering_wheel_angle": 2.2003665635734055, "front_wheel_angle": 0.1041436977205166, "heading_rate": 0.08092136519675153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.3490663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03706519720565103, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9620177541994455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.925276037733016, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "steering_wheel_angle": 2.5370196756335655, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.3490663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.3690662, "x": 48.478466370170636, "y": 5.000230708206152, "z": null, "yaw": -0.0005136227506359298, "pitch": null, "roll": null}, "v": 1.9126845631511535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "acceleration": -0.6287394281839331, "steering_wheel_angle": 2.6206532755977308, "front_wheel_angle": 0.1247934588979218, "heading_rate": 0.09372553318049479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.3690662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9551958124865076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9126845631511535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "steering_wheel_angle": 2.6206532755977308, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.3690662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.478466370170636, "y": 0.0002307082061516752, "z": null, "yaw": 6.2826716844289505, "pitch": null, "roll": null}, "v": 1.9126845631511535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "acceleration": -0.6287394281839331, "steering_wheel_angle": 2.6206532755977308, "front_wheel_angle": 0.1247934588979218, "heading_rate": 0.09372553318049479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.3890662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01626682828020963, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9551958124865076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9060431369818533, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.7040561946984236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.3890662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.478466370170636, "y": 0.0002307082061516752, "z": null, "yaw": 6.2826716844289505, "pitch": null, "roll": null}, "v": 1.9126845631511535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "acceleration": -0.6287394281839331, "steering_wheel_angle": 2.6206532755977308, "front_wheel_angle": 0.1247934588979218, "heading_rate": 0.09372553318049479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.4090662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01626682828020963, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9551958124865076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.896811868228515, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "steering_wheel_angle": 2.787247338233407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.4090662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.478466370170636, "y": 0.0002307082061516752, "z": null, "yaw": 6.2826716844289505, "pitch": null, "roll": null}, "v": 1.9126845631511535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "acceleration": -0.6287394281839331, "steering_wheel_angle": 2.6206532755977308, "front_wheel_angle": 0.1247934588979218, "heading_rate": 0.09372553318049479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.4290662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01626682828020963, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9551958124865076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.887596836115526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "steering_wheel_angle": 2.8702267062026774, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.4290662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.478466370170636, "y": 0.0002307082061516752, "z": null, "yaw": 6.2826716844289505, "pitch": null, "roll": null}, "v": 1.9126845631511535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "acceleration": -0.6287394281839331, "steering_wheel_angle": 2.6206532755977308, "front_wheel_angle": 0.1247934588979218, "heading_rate": 0.09372553318049479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.4490662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01626682828020963, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9551958124865076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8783979781328415, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "steering_wheel_angle": 2.952994298606237, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.4490662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.478466370170636, "y": 0.0002307082061516752, "z": null, "yaw": 6.2826716844289505, "pitch": null, "roll": null}, "v": 1.9126845631511535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "acceleration": -0.6287394281839331, "steering_wheel_angle": 2.6206532755977308, "front_wheel_angle": 0.1247934588979218, "heading_rate": 0.09372553318049479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.4690661} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01626682828020963, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9551958124865076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.869215232059005, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "steering_wheel_angle": 3.035550115444086, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.4690661} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.4790661, "x": 48.6865710430066, "y": 5.000656727512066, "z": null, "yaw": 0.005327987419951665, "pitch": null, "roll": null}, "v": 1.8646298816221825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "acceleration": -0.45813456627716975, "steering_wheel_angle": 3.0767486080258686, "front_wheel_angle": 0.1475030680419279, "heading_rate": 0.10822297970491074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.4890661} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.958883919613041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8600485359594108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "steering_wheel_angle": 3.1178941567162233, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.4890661} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 44.6865710430066, "y": 0.0006567275120659133, "z": null, "yaw": 0.005327987419951665, "pitch": null, "roll": null}, "v": 1.8646298816221825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "acceleration": -0.45813456627716975, "steering_wheel_angle": 3.0767486080258686, "front_wheel_angle": 0.1475030680419279, "heading_rate": 0.10822297970491074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.509066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.958883919613041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8534993869448342, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.509066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 44.6865710430066, "y": 0.0006567275120659133, "z": null, "yaw": 0.005327987419951665, "pitch": null, "roll": null}, "v": 1.8646298816221825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "acceleration": -0.45813456627716975, "steering_wheel_angle": 3.0767486080258686, "front_wheel_angle": 0.1475030680419279, "heading_rate": 0.10822297970491074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.529066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.958883919613041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8469616419389823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.529066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 44.6865710430066, "y": 0.0006567275120659133, "z": null, "yaw": 0.005327987419951665, "pitch": null, "roll": null}, "v": 1.8646298816221825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "acceleration": -0.45813456627716975, "steering_wheel_angle": 3.0767486080258686, "front_wheel_angle": 0.1475030680419279, "heading_rate": 0.10822297970491074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.549066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.958883919613041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8404352639946788, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.549066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 44.6865710430066, "y": 0.0006567275120659133, "z": null, "yaw": 0.005327987419951665, "pitch": null, "roll": null}, "v": 1.8646298816221825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "acceleration": -0.45813456627716975, "steering_wheel_angle": 3.0767486080258686, "front_wheel_angle": 0.1475030680419279, "heading_rate": 0.10822297970491074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.569066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.958883919613041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8339202163181598, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.569066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.589066, "x": 48.88974404350032, "y": 5.002343285409414, "z": null, "yaw": 0.011935142161647386, "pitch": null, "roll": null}, "v": 1.8274164622682683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32476533237910415, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.11058646408835184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.589066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22739380475318652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.955562264630508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8274164622682683, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.589066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 44.88974404350032, "y": 0.0023432854094140865, "z": null, "yaw": 0.011935142161647386, "pitch": null, "roll": null}, "v": 1.8274164622682683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32476533237910415, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.11058646408835184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.609066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21874975272958788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.955562264630508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.824346709963717, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.609066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 44.88974404350032, "y": 0.0023432854094140865, "z": null, "yaw": 0.011935142161647386, "pitch": null, "roll": null}, "v": 1.8274164622682683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32476533237910415, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.11058646408835184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.629066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21874975272958788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.955562264630508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.820202226724943, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.629066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 44.88974404350032, "y": 0.0023432854094140865, "z": null, "yaw": 0.011935142161647386, "pitch": null, "roll": null}, "v": 1.8274164622682683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32476533237910415, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.11058646408835184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.649066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21874975272958788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.955562264630508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8160649041112573, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.649066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 44.88974404350032, "y": 0.0023432854094140865, "z": null, "yaw": 0.011935142161647386, "pitch": null, "roll": null}, "v": 1.8274164622682683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32476533237910415, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.11058646408835184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.669066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21874975272958788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.955562264630508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8119347229068772, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.669066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 44.88974404350032, "y": 0.0023432854094140865, "z": null, "yaw": 0.011935142161647386, "pitch": null, "roll": null}, "v": 1.8274164622682683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32476533237910415, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.11058646408835184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.689066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21874975272958788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.955562264630508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.807811663964637, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.689066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.699066, "x": 49.089700668006536, "y": 5.005333708707709, "z": null, "yaw": 0.018591813643428594, "pitch": null, "roll": null}, "v": 1.8057527993770173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32289507169343024, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.10927548329781446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.709066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04876090534354788, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.516549204557914, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8036957082056821, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.709066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 45.089700668006536, "y": 0.005333708707708773, "z": null, "yaw": 0.018591813643428594, "pitch": null, "roll": null}, "v": 1.8057527993770173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32289507169343024, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.10927548329781446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.729066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04876090534354788, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.516549204557914, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7894457343134844, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "steering_wheel_angle": 3.286542123980042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.729066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 45.089700668006536, "y": 0.005333708707708773, "z": null, "yaw": 0.018591813643428594, "pitch": null, "roll": null}, "v": 1.8057527993770173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32289507169343024, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.10927548329781446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.7490659} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04876090534354788, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.516549204557914, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7752202200270313, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "steering_wheel_angle": 3.3728116331624345, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.7490659} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 45.089700668006536, "y": 0.005333708707708773, "z": null, "yaw": 0.018591813643428594, "pitch": null, "roll": null}, "v": 1.8057527993770173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32289507169343024, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.10927548329781446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.7690659} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04876090534354788, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.516549204557914, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7610190424506973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "steering_wheel_angle": 3.4588449622402435, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.7690659} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 45.089700668006536, "y": 0.005333708707708773, "z": null, "yaw": 0.018591813643428594, "pitch": null, "roll": null}, "v": 1.8057527993770173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32289507169343024, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.10927548329781446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.7890658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04876090534354788, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.516549204557914, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7468420793147177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "steering_wheel_angle": 3.544642111213466, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.7890658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.8090658, "x": 49.284881159392306, "y": 5.009567485870006, "z": null, "yaw": 0.025641794650124266, "pitch": null, "roll": null}, "v": 1.7326892089706283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "acceleration": -0.706743822145747, "steering_wheel_angle": 3.630203080082104, "front_wheel_angle": 0.1754993211415088, "heading_rate": 0.12001823298099505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.8090658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01928453816409896, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.553670605946441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7326892089706283, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "steering_wheel_angle": 3.630203080082104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.8090658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.284881159392306, "y": 0.00956748587000611, "z": null, "yaw": 0.025641794650124266, "pitch": null, "roll": null}, "v": 1.7326892089706283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "acceleration": -0.706743822145747, "steering_wheel_angle": 3.630203080082104, "front_wheel_angle": 0.1754993211415088, "heading_rate": 0.12001823298099505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.8290658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.028739600212213598, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.553670605946441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7232745356837258, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01928453816409896, "steering_wheel_angle": 3.7156448334301535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.8290658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.284881159392306, "y": 0.00956748587000611, "z": null, "yaw": 0.025641794650124266, "pitch": null, "roll": null}, "v": 1.7326892089706283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "acceleration": -0.706743822145747, "steering_wheel_angle": 3.630203080082104, "front_wheel_angle": 0.1754993211415088, "heading_rate": 0.12001823298099505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.8490658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.028739600212213598, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.553670605946441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7123635970448676, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "steering_wheel_angle": 3.8008497578110014, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.8490658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.284881159392306, "y": 0.00956748587000611, "z": null, "yaw": 0.025641794650124266, "pitch": null, "roll": null}, "v": 1.7326892089706283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "acceleration": -0.706743822145747, "steering_wheel_angle": 3.630203080082104, "front_wheel_angle": 0.1754993211415088, "heading_rate": 0.12001823298099505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.8690658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.028739600212213598, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.553670605946441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7014710468979917, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "steering_wheel_angle": 3.885817853224647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.8690658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.284881159392306, "y": 0.00956748587000611, "z": null, "yaw": 0.025641794650124266, "pitch": null, "roll": null}, "v": 1.7326892089706283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "acceleration": -0.706743822145747, "steering_wheel_angle": 3.630203080082104, "front_wheel_angle": 0.1754993211415088, "heading_rate": 0.12001823298099505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.8890657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.028739600212213598, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.553670605946441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6905968068133521, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "steering_wheel_angle": 3.970549119671091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.8890657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.284881159392306, "y": 0.00956748587000611, "z": null, "yaw": 0.025641794650124266, "pitch": null, "roll": null}, "v": 1.7326892089706283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "acceleration": -0.706743822145747, "steering_wheel_angle": 3.630203080082104, "front_wheel_angle": 0.1754993211415088, "heading_rate": 0.12001823298099505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.9090657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.028739600212213598, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.553670605946441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6797407987324284, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "steering_wheel_angle": 4.0550435571503325, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.9090657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.9190657, "x": 49.47254100391904, "y": 5.0150514142279246, "z": null, "yaw": 0.033746324119567524, "pitch": null, "roll": null}, "v": 1.6743196074009925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "acceleration": -0.5416662435450326, "steering_wheel_angle": 4.097201965027253, "front_wheel_angle": 0.19951468355290852, "heading_rate": 0.1322482443640357, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.9290657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02490302895387092, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.892460241357465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6689029449655421, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "steering_wheel_angle": 4.139301165662373, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.9290657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 45.47254100391904, "y": 0.015051414227924553, "z": null, "yaw": 0.033746324119567524, "pitch": null, "roll": null}, "v": 1.6743196074009925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "acceleration": -0.5416662435450326, "steering_wheel_angle": 4.097201965027253, "front_wheel_angle": 0.19951468355290852, "heading_rate": 0.1322482443640357, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.9490657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.026293643444409362, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.892460241357465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6586967640049377, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02490302895387092, "steering_wheel_angle": 4.2243939924510965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.9490657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 45.47254100391904, "y": 0.015051414227924553, "z": null, "yaw": 0.033746324119567524, "pitch": null, "roll": null}, "v": 1.6743196074009925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "acceleration": -0.5416662435450326, "steering_wheel_angle": 4.097201965027253, "front_wheel_angle": 0.19951468355290852, "heading_rate": 0.1322482443640357, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.9690657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.026293643444409362, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.892460241357465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6482851582579465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "steering_wheel_angle": 4.309243899419114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.9690657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 45.47254100391904, "y": 0.015051414227924553, "z": null, "yaw": 0.033746324119567524, "pitch": null, "roll": null}, "v": 1.6743196074009925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "acceleration": -0.5416662435450326, "steering_wheel_angle": 4.097201965027253, "front_wheel_angle": 0.19951468355290852, "heading_rate": 0.1322482443640357, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.9890656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.026293643444409362, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.892460241357465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6378908323038177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "steering_wheel_angle": 4.3938508865664225, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.9890656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 45.47254100391904, "y": 0.015051414227924553, "z": null, "yaw": 0.033746324119567524, "pitch": null, "roll": null}, "v": 1.6743196074009925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "acceleration": -0.5416662435450326, "steering_wheel_angle": 4.097201965027253, "front_wheel_angle": 0.19951468355290852, "heading_rate": 0.1322482443640357, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.0090656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.026293643444409362, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.892460241357465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6275137142649216, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "steering_wheel_angle": 4.478214953893027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.0090656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.0290656, "x": 49.65372096552338, "y": 5.021904041544273, "z": null, "yaw": 0.04292973668914304, "pitch": null, "roll": null}, "v": 1.6171537325973075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "acceleration": -0.5173586961336742, "steering_wheel_angle": 4.562336101398923, "front_wheel_angle": 0.22380900729963252, "heading_rate": 0.1437891796593677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.0290656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01560539321511805, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.123547496212532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6171537325973075, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "steering_wheel_angle": 4.562336101398923, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.0290656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.65372096552338, "y": 0.021904041544273056, "z": null, "yaw": 0.04292973668914304, "pitch": null, "roll": null}, "v": 1.6171537325973075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "acceleration": -0.5173586961336742, "steering_wheel_angle": 4.562336101398923, "front_wheel_angle": 0.22380900729963252, "heading_rate": 0.1437891796593677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.0490656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01913062580391154, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.123547496212532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6085202328542176, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01560539321511805, "steering_wheel_angle": 4.646958776329224, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.0490656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.65372096552338, "y": 0.021904041544273056, "z": null, "yaw": 0.04292973668914304, "pitch": null, "roll": null}, "v": 1.6171537325973075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "acceleration": -0.5173586961336742, "steering_wheel_angle": 4.562336101398923, "front_wheel_angle": 0.22380900729963252, "heading_rate": 0.1437891796593677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.0690656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01913062580391154, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.123547496212532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.599337117366317, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "steering_wheel_angle": 4.7313341939500715, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.0690656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.65372096552338, "y": 0.021904041544273056, "z": null, "yaw": 0.04292973668914304, "pitch": null, "roll": null}, "v": 1.6171537325973075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "acceleration": -0.5173586961336742, "steering_wheel_angle": 4.562336101398923, "front_wheel_angle": 0.22380900729963252, "heading_rate": 0.1437891796593677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.0890656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01913062580391154, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.123547496212532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5901690620096567, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "steering_wheel_angle": 4.8154623542614665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.0890656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.65372096552338, "y": 0.021904041544273056, "z": null, "yaw": 0.04292973668914304, "pitch": null, "roll": null}, "v": 1.6171537325973075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "acceleration": -0.5173586961336742, "steering_wheel_angle": 4.562336101398923, "front_wheel_angle": 0.22380900729963252, "heading_rate": 0.1437891796593677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.1090655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01913062580391154, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.123547496212532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5810160084783584, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "steering_wheel_angle": 4.899343257263408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.1090655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.65372096552338, "y": 0.021904041544273056, "z": null, "yaw": 0.04292973668914304, "pitch": null, "roll": null}, "v": 1.6171537325973075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "acceleration": -0.5173586961336742, "steering_wheel_angle": 4.562336101398923, "front_wheel_angle": 0.22380900729963252, "heading_rate": 0.1437891796593677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.1290655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01913062580391154, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.123547496212532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5718778987270217, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "steering_wheel_angle": 4.9829769029558975, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.1290655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.1390655, "x": 49.82893869301794, "y": 5.030230827506924, "z": null, "yaw": 0.05321632636998234, "pitch": null, "roll": null}, "v": 1.5673144297004946, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "acceleration": -0.45597547313179093, "steering_wheel_angle": 5.024701004311098, "front_wheel_angle": 0.24834741082035416, "heading_rate": 0.15525126446535648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.1490655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.085755733928949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5627546749691767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "steering_wheel_angle": 5.066363291338933, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.1490655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 45.82893869301794, "y": 0.030230827506923852, "z": null, "yaw": 0.05321632636998234, "pitch": null, "roll": null}, "v": 1.5673144297004946, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "acceleration": -0.45597547313179093, "steering_wheel_angle": 5.024701004311098, "front_wheel_angle": 0.24834741082035416, "heading_rate": 0.15525126446535648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.1690655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.085755733928949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.556705937396078, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.149381480496018, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.1690655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 45.82893869301794, "y": 0.030230827506923852, "z": null, "yaw": 0.05321632636998234, "pitch": null, "roll": null}, "v": 1.5673144297004946, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "acceleration": -0.45597547313179093, "steering_wheel_angle": 5.024701004311098, "front_wheel_angle": 0.24834741082035416, "heading_rate": 0.15525126446535648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.1890655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.085755733928949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5506670146783372, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.232153132255578, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.1890655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 45.82893869301794, "y": 0.030230827506923852, "z": null, "yaw": 0.05321632636998234, "pitch": null, "roll": null}, "v": 1.5673144297004946, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "acceleration": -0.45597547313179093, "steering_wheel_angle": 5.024701004311098, "front_wheel_angle": 0.24834741082035416, "heading_rate": 0.15525126446535648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.2090654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.085755733928949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.544637876308557, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.314678246617617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.2090654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 45.82893869301794, "y": 0.030230827506923852, "z": null, "yaw": 0.05321632636998234, "pitch": null, "roll": null}, "v": 1.5673144297004946, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "acceleration": -0.45597547313179093, "steering_wheel_angle": 5.024701004311098, "front_wheel_angle": 0.24834741082035416, "heading_rate": 0.15525126446535648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.2290654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.085755733928949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5386184918996713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.2290654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.2490654, "x": 49.99923811296317, "y": 5.040168485396333, "z": null, "yaw": 0.06461462367847921, "pitch": null, "roll": null}, "v": 1.5326088311843409, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3001193398534594, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16465637000952535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.2490654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22814554525844294, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.045121920026441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5326088311843409, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.2490654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 45.99923811296317, "y": 0.04016848539633333, "z": null, "yaw": 0.06461462367847921, "pitch": null, "roll": null}, "v": 1.5326088311843409, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3001193398534594, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16465637000952535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.2690654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21893032557707792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.045121920026441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5301256391684177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.2690654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 45.99923811296317, "y": 0.04016848539633333, "z": null, "yaw": 0.06461462367847921, "pitch": null, "roll": null}, "v": 1.5326088311843409, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3001193398534594, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16465637000952535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.2890654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21893032557707792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.045121920026441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.526495010780897, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.2890654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 45.99923811296317, "y": 0.04016848539633333, "z": null, "yaw": 0.06461462367847921, "pitch": null, "roll": null}, "v": 1.5326088311843409, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3001193398534594, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16465637000952535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.3090653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21893032557707792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.045121920026441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5228702288393405, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.3090653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 45.99923811296317, "y": 0.04016848539633333, "z": null, "yaw": 0.06461462367847921, "pitch": null, "roll": null}, "v": 1.5326088311843409, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3001193398534594, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16465637000952535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.3290653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21893032557707792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.045121920026441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5192512786756387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.3290653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 45.99923811296317, "y": 0.04016848539633333, "z": null, "yaw": 0.06461462367847921, "pitch": null, "roll": null}, "v": 1.5326088311843409, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3001193398534594, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16465637000952535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.3490653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21893032557707792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.045121920026441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5156381456706434, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.3490653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.3590653, "x": 50.16652527096918, "y": 5.051893402585271, "z": null, "yaw": 0.07643251245251903, "pitch": null, "roll": null}, "v": 1.5138337560475141, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29860861421186496, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16263926319415026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.3690653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24086274095880852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.032649595710259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5120308152539628, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.3690653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 46.16652527096918, "y": 0.05189340258527064, "z": null, "yaw": 0.07643251245251903, "pitch": null, "roll": null}, "v": 1.5138337560475141, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29860861421186496, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16263926319415026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.3890653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23393332032665579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.032649595710259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5111697252133829, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.3890653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 46.16652527096918, "y": 0.05189340258527064, "z": null, "yaw": 0.07643251245251903, "pitch": null, "roll": null}, "v": 1.5138337560475141, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29860861421186496, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16263926319415026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.4090652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23393332032665579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.032649595710259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5094441860875663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.4090652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 46.16652527096918, "y": 0.05189340258527064, "z": null, "yaw": 0.07643251245251903, "pitch": null, "roll": null}, "v": 1.5138337560475141, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29860861421186496, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16263926319415026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.4290652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23393332032665579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.032649595710259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5077214135309391, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.4290652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 46.16652527096918, "y": 0.05189340258527064, "z": null, "yaw": 0.07643251245251903, "pitch": null, "roll": null}, "v": 1.5138337560475141, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29860861421186496, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16263926319415026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.4490652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23393332032665579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.032649595710259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5060014019211385, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.4490652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.4690652, "x": 50.33199612346015, "y": 5.065458927522394, "z": null, "yaw": 0.08825040122655885, "pitch": null, "roll": null}, "v": 1.504284145650518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.297842915191081, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16161329743499467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.4690652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25133081164422855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.049107507884381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.504284145650518, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.4690652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.33199612346015, "y": 0.06545892752239357, "z": null, "yaw": 0.08825040122655885, "pitch": null, "roll": null}, "v": 1.504284145650518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.297842915191081, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16161329743499467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.4890652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458558070667551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.049107507884381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5047434548028322, "gear": 1, "accelerator_pedal_position": 0.25133081164422855, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.4890652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.33199612346015, "y": 0.06545892752239357, "z": null, "yaw": 0.08825040122655885, "pitch": null, "roll": null}, "v": 1.504284145650518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.297842915191081, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16161329743499467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.5090652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458558070667551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.049107507884381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5045179270114255, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.5090652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.33199612346015, "y": 0.06545892752239357, "z": null, "yaw": 0.08825040122655885, "pitch": null, "roll": null}, "v": 1.504284145650518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.297842915191081, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16161329743499467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.5290651} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458558070667551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.049107507884381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5042927603324725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.5290651} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.33199612346015, "y": 0.06545892752239357, "z": null, "yaw": 0.08825040122655885, "pitch": null, "roll": null}, "v": 1.504284145650518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.297842915191081, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16161329743499467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.549065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458558070667551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.049107507884381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5040679541674924, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.549065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.33199612346015, "y": 0.06545892752239357, "z": null, "yaw": 0.08825040122655885, "pitch": null, "roll": null}, "v": 1.504284145650518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.297842915191081, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16161329743499467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.569065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458558070667551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.049107507884381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5038435079190597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.569065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.579065, "x": 50.49674486524493, "y": 5.080928203469078, "z": null, "yaw": 0.10006829000059866, "pitch": null, "roll": null}, "v": 1.5037314195771414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2977986528010919, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16155391511447034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.589065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2199474519699499, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.624804258878803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5036194209908027, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.589065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 46.49674486524493, "y": 0.08092820346907814, "z": null, "yaw": 0.10006829000059866, "pitch": null, "roll": null}, "v": 1.5037314195771414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2977986528010919, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16155391511447034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.609065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22804160512514243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.624804258878803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5001584446917744, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.480744517515055, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.609065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 46.49674486524493, "y": 0.08092820346907814, "z": null, "yaw": 0.10006829000059866, "pitch": null, "roll": null}, "v": 1.5037314195771414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2977986528010919, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16155391511447034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.629065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22804160512514243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.624804258878803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4977143697263233, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.564274991739866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.629065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 46.49674486524493, "y": 0.08092820346907814, "z": null, "yaw": 0.10006829000059866, "pitch": null, "roll": null}, "v": 1.5037314195771414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2977986528010919, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16155391511447034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.649065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22804160512514243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.624804258878803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4952742020810066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.64754824625657, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.649065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 46.49674486524493, "y": 0.08092820346907814, "z": null, "yaw": 0.10006829000059866, "pitch": null, "roll": null}, "v": 1.5037314195771414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2977986528010919, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16155391511447034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.669065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22804160512514243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.624804258878803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.492837933128411, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.730564281065164, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.669065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.689065, "x": 50.66059047426573, "y": 5.09828417760623, "z": null, "yaw": 0.11231812695984851, "pitch": null, "roll": null}, "v": 1.490405554266321, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2967333648751951, "steering_wheel_angle": 5.813323096165648, "front_wheel_angle": 0.291150894434217, "heading_rate": 0.17446279858586525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.689065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21875470816287204, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.038505213274327, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.490405554266321, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.813323096165648, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.689065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.66059047426573, "y": 0.09828417760622976, "z": null, "yaw": 0.11231812695984851, "pitch": null, "roll": null}, "v": 1.490405554266321, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2967333648751951, "steering_wheel_angle": 5.813323096165648, "front_wheel_angle": 0.291150894434217, "heading_rate": 0.17446279858586525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.709065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22160360093516634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.038505213274327, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4868166578537039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.8972293943338165, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.709065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.66059047426573, "y": 0.09828417760622976, "z": null, "yaw": 0.11231812695984851, "pitch": null, "roll": null}, "v": 1.490405554266321, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2967333648751951, "steering_wheel_angle": 5.813323096165648, "front_wheel_angle": 0.291150894434217, "heading_rate": 0.17446279858586525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.729065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22160360093516634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.038505213274327, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4835894534376406, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.980869625044013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.729065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.66059047426573, "y": 0.09828417760622976, "z": null, "yaw": 0.11231812695984851, "pitch": null, "roll": null}, "v": 1.490405554266321, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2967333648751951, "steering_wheel_angle": 5.813323096165648, "front_wheel_angle": 0.291150894434217, "heading_rate": 0.17446279858586525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.749065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22160360093516634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.038505213274327, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4803673903571388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.064243788296234, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.749065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.66059047426573, "y": 0.09828417760622976, "z": null, "yaw": 0.11231812695984851, "pitch": null, "roll": null}, "v": 1.490405554266321, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2967333648751951, "steering_wheel_angle": 5.813323096165648, "front_wheel_angle": 0.291150894434217, "heading_rate": 0.17446279858586525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.769065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22160360093516634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.038505213274327, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.477150456270391, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.147351884090481, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.769065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.66059047426573, "y": 0.09828417760622976, "z": null, "yaw": 0.11231812695984851, "pitch": null, "roll": null}, "v": 1.490405554266321, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2967333648751951, "steering_wheel_angle": 5.813323096165648, "front_wheel_angle": 0.291150894434217, "heading_rate": 0.17446279858586525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.789065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22160360093516634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.038505213274327, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4739386388750628, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.230193912426757, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.789065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.7990649, "x": 50.82247335614242, "y": 5.11752572921933, "z": null, "yaw": 0.1257389312373576, "pitch": null, "roll": null}, "v": 1.4723346451029562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2952944253268523, "steering_wheel_angle": 6.2715151512981535, "front_wheel_angle": 0.31660557284006163, "heading_rate": 0.18842802143751153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.8090649} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.06301149252982435, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.628730411005295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4707319259081355, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.312769873305057, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.8090649} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 46.82247335614242, "y": 0.11752572921932991, "z": null, "yaw": 0.1257389312373576, "pitch": null, "roll": null}, "v": 1.4723346451029562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2952944253268523, "steering_wheel_angle": 6.2715151512981535, "front_wheel_angle": 0.31660557284006163, "heading_rate": 0.18842802143751153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.8290648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038102276724044724, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.628730411005295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4547530855966653, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.06301149252982435, "steering_wheel_angle": 6.40111770847626, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.8290648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 46.82247335614242, "y": 0.11752572921932991, "z": null, "yaw": 0.1257389312373576, "pitch": null, "roll": null}, "v": 1.4723346451029562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2952944253268523, "steering_wheel_angle": 6.2715151512981535, "front_wheel_angle": 0.31660557284006163, "heading_rate": 0.18842802143751153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.8490648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038102276724044724, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.628730411005295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4427834389136664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "steering_wheel_angle": 6.489158936218649, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.8490648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 46.82247335614242, "y": 0.11752572921932991, "z": null, "yaw": 0.1257389312373576, "pitch": null, "roll": null}, "v": 1.4723346451029562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2952944253268523, "steering_wheel_angle": 6.2715151512981535, "front_wheel_angle": 0.31660557284006163, "heading_rate": 0.18842802143751153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.8690648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038102276724044724, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.628730411005295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4308326765991595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "steering_wheel_angle": 6.576893556532226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.8690648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 46.82247335614242, "y": 0.11752572921932991, "z": null, "yaw": 0.1257389312373576, "pitch": null, "roll": null}, "v": 1.4723346451029562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2952944253268523, "steering_wheel_angle": 6.2715151512981535, "front_wheel_angle": 0.31660557284006163, "heading_rate": 0.18842802143751153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.8890648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038102276724044724, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.628730411005295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4189007117536525, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "steering_wheel_angle": 6.664321569416991, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.8890648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.9090648, "x": 50.979850334782334, "y": 5.138459434422154, "z": null, "yaw": 0.14040364357366894, "pitch": null, "roll": null}, "v": 1.4069874578840114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "acceleration": -0.5949637237529875, "steering_wheel_angle": 6.751442974872943, "front_wheel_angle": 0.34376070949892945, "heading_rate": 0.19674401403768907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.9090648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01494396540518829, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.68495930535984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4069874578840114, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "steering_wheel_angle": 6.751442974872943, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.9090648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 46.979850334782334, "y": 0.13845943442215436, "z": null, "yaw": 0.14040364357366894, "pitch": null, "roll": null}, "v": 1.4069874578840114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "acceleration": -0.5949637237529875, "steering_wheel_angle": 6.751442974872943, "front_wheel_angle": 0.34376070949892945, "heading_rate": 0.19674401403768907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.9290648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022382072075626758, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.68495930535984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3987967129053536, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01494396540518829, "steering_wheel_angle": 6.838492166597783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.9290648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 46.979850334782334, "y": 0.13845943442215436, "z": null, "yaw": 0.14040364357366894, "pitch": null, "roll": null}, "v": 1.4069874578840114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "acceleration": -0.5949637237529875, "steering_wheel_angle": 6.751442974872943, "front_wheel_angle": 0.34376070949892945, "heading_rate": 0.19674401403768907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.9490647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022382072075626758, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.68495930535984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3894291096777303, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "steering_wheel_angle": 6.925233090078158, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.9490647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 46.979850334782334, "y": 0.13845943442215436, "z": null, "yaw": 0.14040364357366894, "pitch": null, "roll": null}, "v": 1.4069874578840114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "acceleration": -0.5949637237529875, "steering_wheel_angle": 6.751442974872943, "front_wheel_angle": 0.34376070949892945, "heading_rate": 0.19674401403768907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.9690647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022382072075626758, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.68495930535984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3800760834049672, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "steering_wheel_angle": 7.011665745314071, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.9690647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 46.979850334782334, "y": 0.13845943442215436, "z": null, "yaw": 0.14040364357366894, "pitch": null, "roll": null}, "v": 1.4069874578840114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "acceleration": -0.5949637237529875, "steering_wheel_angle": 6.751442974872943, "front_wheel_angle": 0.34376070949892945, "heading_rate": 0.19674401403768907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.9890647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022382072075626758, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.68495930535984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3707375764257486, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "steering_wheel_angle": 7.09779013230552, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.9890647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 46.979850334782334, "y": 0.13845943442215436, "z": null, "yaw": 0.14040364357366894, "pitch": null, "roll": null}, "v": 1.4069874578840114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "acceleration": -0.5949637237529875, "steering_wheel_angle": 6.751442974872943, "front_wheel_angle": 0.34376070949892945, "heading_rate": 0.19674401403768907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.0090647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022382072075626758, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.68495930535984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3614135313312645, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "steering_wheel_angle": 7.183606251052504, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.0090647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.0190647, "x": 51.1305013800405, "y": 5.1608449667153655, "z": null, "yaw": 0.1563929095303462, "pitch": null, "roll": null}, "v": 1.3567569141192195, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "acceleration": -0.46530231555107815, "steering_wheel_angle": 7.226398709834323, "front_wheel_angle": 0.3711597988694116, "heading_rate": 0.20626841042836974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.0290647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.575886189797833, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3521038909637086, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "steering_wheel_angle": 7.269114101555026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.0290647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 47.1305013800405, "y": 0.16084496671536552, "z": null, "yaw": 0.1563929095303462, "pitch": null, "roll": null}, "v": 1.3567569141192195, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "acceleration": -0.46530231555107815, "steering_wheel_angle": 7.226398709834323, "front_wheel_angle": 0.3711597988694116, "heading_rate": 0.20626841042836974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.0490646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.575886189797833, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.346388351802227, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.353870365175435, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.0490646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 47.1305013800405, "y": 0.16084496671536552, "z": null, "yaw": 0.1563929095303462, "pitch": null, "roll": null}, "v": 1.3567569141192195, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "acceleration": -0.46530231555107815, "steering_wheel_angle": 7.226398709834323, "front_wheel_angle": 0.3711597988694116, "heading_rate": 0.20626841042836974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.0690646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.575886189797833, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3406816061971407, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.4383215659806785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.0690646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 47.1305013800405, "y": 0.16084496671536552, "z": null, "yaw": 0.1563929095303462, "pitch": null, "roll": null}, "v": 1.3567569141192195, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "acceleration": -0.46530231555107815, "steering_wheel_angle": 7.226398709834323, "front_wheel_angle": 0.3711597988694116, "heading_rate": 0.20626841042836974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.0890646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.575886189797833, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3349836275974774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.5224677039707535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.0890646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 47.1305013800405, "y": 0.16084496671536552, "z": null, "yaw": 0.1563929095303462, "pitch": null, "roll": null}, "v": 1.3567569141192195, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "acceleration": -0.46530231555107815, "steering_wheel_angle": 7.226398709834323, "front_wheel_angle": 0.3711597988694116, "heading_rate": 0.20626841042836974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.1090646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.575886189797833, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3292943895530904, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.606308779145661, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.1090646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.1290646, "x": 51.27601153586769, "y": 5.1849440898256045, "z": null, "yaw": 0.17373407954622683, "pitch": null, "roll": null}, "v": 1.323613865714171, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2837002299408167, "steering_wheel_angle": 7.689844791505401, "front_wheel_angle": 0.3984290495104766, "heading_rate": 0.2176428009916121, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.1290646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22704866439674892, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.456038917783701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.323613865714171, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.689844791505401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.1290646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.27601153586769, "y": 0.1849440898256045, "z": null, "yaw": 0.17373407954622683, "pitch": null, "roll": null}, "v": 1.323613865714171, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2837002299408167, "steering_wheel_angle": 7.689844791505401, "front_wheel_angle": 0.3984290495104766, "heading_rate": 0.2176428009916121, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.1490645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21732499096955613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.456038917783701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3213218207581738, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.772605166468362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.1490645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.27601153586769, "y": 0.1849440898256045, "z": null, "yaw": 0.17373407954622683, "pitch": null, "roll": null}, "v": 1.323613865714171, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2837002299408167, "steering_wheel_angle": 7.689844791505401, "front_wheel_angle": 0.3984290495104766, "heading_rate": 0.2176428009916121, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.1690645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21732499096955613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.456038917783701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3178182835567018, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.81387224766803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.1690645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.27601153586769, "y": 0.1849440898256045, "z": null, "yaw": 0.17373407954622683, "pitch": null, "roll": null}, "v": 1.323613865714171, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2837002299408167, "steering_wheel_angle": 7.689844791505401, "front_wheel_angle": 0.3984290495104766, "heading_rate": 0.2176428009916121, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.1890645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21732499096955613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.456038917783701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3143200958869268, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.81387224766803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.1890645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.27601153586769, "y": 0.1849440898256045, "z": null, "yaw": 0.17373407954622683, "pitch": null, "roll": null}, "v": 1.323613865714171, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2837002299408167, "steering_wheel_angle": 7.689844791505401, "front_wheel_angle": 0.3984290495104766, "heading_rate": 0.2176428009916121, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.2090645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21732499096955613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.456038917783701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3108272446876168, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.81387224766803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.2090645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.27601153586769, "y": 0.1849440898256045, "z": null, "yaw": 0.17373407954622683, "pitch": null, "roll": null}, "v": 1.323613865714171, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2837002299408167, "steering_wheel_angle": 7.689844791505401, "front_wheel_angle": 0.3984290495104766, "heading_rate": 0.2176428009916121, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.2290645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21732499096955613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.456038917783701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3073397169398633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.81387224766803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.2290645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.2390645, "x": 51.41836759433695, "y": 5.211149709389604, "z": null, "yaw": 0.19212827218315282, "pitch": null, "roll": null}, "v": 1.3055979453034419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2823257572129778, "steering_wheel_angle": 7.81387224766803, "front_wheel_angle": 0.4058204721018434, "heading_rate": 0.21913193008224344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.2490644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.102309843733334, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3038574996669094, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.81387224766803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.2490644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 47.41836759433695, "y": 0.21114970938960376, "z": null, "yaw": 0.19212827218315282, "pitch": null, "roll": null}, "v": 1.3055979453034419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2823257572129778, "steering_wheel_angle": 7.81387224766803, "front_wheel_angle": 0.4058204721018434, "heading_rate": 0.21913193008224344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.2690644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.102309843733334, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2982157793413682, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.898802772515228, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.2690644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 47.41836759433695, "y": 0.21114970938960376, "z": null, "yaw": 0.19212827218315282, "pitch": null, "roll": null}, "v": 1.3055979453034419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2823257572129778, "steering_wheel_angle": 7.81387224766803, "front_wheel_angle": 0.4058204721018434, "heading_rate": 0.21913193008224344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.2890644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.102309843733334, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.292582630330385, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.983412116017765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.2890644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 47.41836759433695, "y": 0.21114970938960376, "z": null, "yaw": 0.19212827218315282, "pitch": null, "roll": null}, "v": 1.3055979453034419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2823257572129778, "steering_wheel_angle": 7.81387224766803, "front_wheel_angle": 0.4058204721018434, "heading_rate": 0.21913193008224344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.3090644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.102309843733334, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2869580269236542, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.067700278175643, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.3090644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 47.41836759433695, "y": 0.21114970938960376, "z": null, "yaw": 0.19212827218315282, "pitch": null, "roll": null}, "v": 1.3055979453034419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2823257572129778, "steering_wheel_angle": 7.81387224766803, "front_wheel_angle": 0.4058204721018434, "heading_rate": 0.21913193008224344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.3290644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.102309843733334, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2813419435076396, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.151667258988859, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.3290644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.3490644, "x": 51.55768861257462, "y": 5.2394803239679, "z": null, "yaw": 0.21112387268005653, "pitch": null, "roll": null}, "v": 1.275734354565109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.280061699162432, "steering_wheel_angle": 8.235313058457418, "front_wheel_angle": 0.4312450765634152, "heading_rate": 0.2292977235553572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.3490644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22450102191759114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.97704137683517, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.275734354565109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.235313058457418, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.3490644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.55768861257462, "y": 0.23948032396789998, "z": null, "yaw": 0.21112387268005653, "pitch": null, "roll": null}, "v": 1.275734354565109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.280061699162432, "steering_wheel_angle": 8.235313058457418, "front_wheel_angle": 0.4312450765634152, "heading_rate": 0.2292977235553572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.3690643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.97704137683517, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2731967066707268, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.318119734307803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.3690643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.55768861257462, "y": 0.23948032396789998, "z": null, "yaw": 0.21112387268005653, "pitch": null, "roll": null}, "v": 1.275734354565109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.280061699162432, "steering_wheel_angle": 8.235313058457418, "front_wheel_angle": 0.4312450765634152, "heading_rate": 0.2292977235553572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.3890643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.97704137683517, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2676014152201425, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.359404124767671, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.3890643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.55768861257462, "y": 0.23948032396789998, "z": null, "yaw": 0.21112387268005653, "pitch": null, "roll": null}, "v": 1.275734354565109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.280061699162432, "steering_wheel_angle": 8.235313058457418, "front_wheel_angle": 0.4312450765634152, "heading_rate": 0.2292977235553572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.4090643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.97704137683517, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2620145560533353, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.359404124767671, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.4090643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.55768861257462, "y": 0.23948032396789998, "z": null, "yaw": 0.21112387268005653, "pitch": null, "roll": null}, "v": 1.275734354565109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.280061699162432, "steering_wheel_angle": 8.235313058457418, "front_wheel_angle": 0.4312450765634152, "heading_rate": 0.2292977235553572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.4290643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.97704137683517, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2564361039820782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.359404124767671, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.4290643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.55768861257462, "y": 0.23948032396789998, "z": null, "yaw": 0.21112387268005653, "pitch": null, "roll": null}, "v": 1.275734354565109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.280061699162432, "steering_wheel_angle": 8.235313058457418, "front_wheel_angle": 0.4312450765634152, "heading_rate": 0.2292977235553572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.4490643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.97704137683517, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2508660339124102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.359404124767671, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.4490643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.4590642, "x": 51.6934121698956, "y": 5.269858118877879, "z": null, "yaw": 0.23121901277838186, "pitch": null, "roll": null}, "v": 1.2480841343119744, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2779813467788114, "steering_wheel_angle": 8.359404124767671, "front_wheel_angle": 0.4388249554438734, "heading_rate": 0.22882152472932987, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.4690642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.516628728760285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2453043208441863, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.359404124767671, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.4690642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 47.6934121698956, "y": 0.26985811887787925, "z": null, "yaw": 0.23121901277838186, "pitch": null, "roll": null}, "v": 1.2480841343119744, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2779813467788114, "steering_wheel_angle": 8.359404124767671, "front_wheel_angle": 0.4388249554438734, "heading_rate": 0.22882152472932987, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.4890642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.516628728760285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2397509398706288, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.444024674646164, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.4890642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 47.6934121698956, "y": 0.26985811887787925, "z": null, "yaw": 0.23121901277838186, "pitch": null, "roll": null}, "v": 1.2480841343119744, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2779813467788114, "steering_wheel_angle": 8.359404124767671, "front_wheel_angle": 0.4388249554438734, "heading_rate": 0.22882152472932987, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.5090642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.516628728760285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2342058661778823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.528310107371242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.5090642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 47.6934121698956, "y": 0.26985811887787925, "z": null, "yaw": 0.23121901277838186, "pitch": null, "roll": null}, "v": 1.2480841343119744, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2779813467788114, "steering_wheel_angle": 8.359404124767671, "front_wheel_angle": 0.4388249554438734, "heading_rate": 0.22882152472932987, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.5290642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.516628728760285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2286690750445703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.612260422942905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.5290642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 47.6934121698956, "y": 0.26985811887787925, "z": null, "yaw": 0.23121901277838186, "pitch": null, "roll": null}, "v": 1.2480841343119744, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2779813467788114, "steering_wheel_angle": 8.359404124767671, "front_wheel_angle": 0.4388249554438734, "heading_rate": 0.22882152472932987, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.5490642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.516628728760285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2231405418413552, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.69587562136115, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.5490642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.5690641, "x": 51.825266873290325, "y": 5.302192196517178, "z": null, "yaw": 0.2519476846163402, "pitch": null, "roll": null}, "v": 1.2176202420305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27570700263954917, "steering_wheel_angle": 8.77915570262598, "front_wheel_angle": 0.46479528007446297, "heading_rate": 0.23849918325728464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.5690641} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.67666518507491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2176202420305, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.77915570262598, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.5690641} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 47.825266873290325, "y": 0.3021921965171783, "z": null, "yaw": 0.2519476846163402, "pitch": null, "roll": null}, "v": 1.2176202420305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27570700263954917, "steering_wheel_angle": 8.77915570262598, "front_wheel_angle": 0.46479528007446297, "heading_rate": 0.23849918325728464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.5890641} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.67666518507491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2121081511654332, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.862803159432758, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.5890641} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 47.825266873290325, "y": 0.3021921965171783, "z": null, "yaw": 0.2519476846163402, "pitch": null, "roll": null}, "v": 1.2176202420305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27570700263954917, "steering_wheel_angle": 8.77915570262598, "front_wheel_angle": 0.46479528007446297, "heading_rate": 0.23849918325728464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.609064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.67666518507491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2066042448903158, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.94610978689045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.609064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 47.825266873290325, "y": 0.3021921965171783, "z": null, "yaw": 0.2519476846163402, "pitch": null, "roll": null}, "v": 1.2176202420305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27570700263954917, "steering_wheel_angle": 8.77915570262598, "front_wheel_angle": 0.46479528007446297, "heading_rate": 0.23849918325728464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.629064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.67666518507491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2011084989396101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.02907558499905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.629064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 47.825266873290325, "y": 0.3021921965171783, "z": null, "yaw": 0.2519476846163402, "pitch": null, "roll": null}, "v": 1.2176202420305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27570700263954917, "steering_wheel_angle": 8.77915570262598, "front_wheel_angle": 0.46479528007446297, "heading_rate": 0.23849918325728464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.649064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.67666518507491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1956208891376527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.649064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 47.825266873290325, "y": 0.3021921965171783, "z": null, "yaw": 0.2519476846163402, "pitch": null, "roll": null}, "v": 1.2176202420305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27570700263954917, "steering_wheel_angle": 8.77915570262598, "front_wheel_angle": 0.46479528007446297, "heading_rate": 0.23849918325728464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.669064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.67666518507491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1901413913982277, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.669064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.679064, "x": 51.95317430929381, "y": 5.336476482153712, "z": null, "yaw": 0.27412601182778307, "pitch": null, "roll": null}, "v": 1.1874046770493767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27346953252325623, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24332247810442317, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.689064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23399148530840708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.458152522260749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1846699817241442, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.689064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 47.95317430929381, "y": 0.33647648215371184, "z": null, "yaw": 0.27412601182778307, "pitch": null, "roll": null}, "v": 1.1874046770493767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27346953252325623, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24332247810442317, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.709064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22416994831726333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.458152522260749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1834540069875576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.709064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 47.95317430929381, "y": 0.33647648215371184, "z": null, "yaw": 0.27412601182778307, "pitch": null, "roll": null}, "v": 1.1874046770493767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27346953252325623, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24332247810442317, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.729064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22416994831726333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.458152522260749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1810125833122709, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.729064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 47.95317430929381, "y": 0.33647648215371184, "z": null, "yaw": 0.27412601182778307, "pitch": null, "roll": null}, "v": 1.1874046770493767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27346953252325623, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24332247810442317, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.749064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22416994831726333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.458152522260749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.17857475367409, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.749064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 47.95317430929381, "y": 0.33647648215371184, "z": null, "yaw": 0.27412601182778307, "pitch": null, "roll": null}, "v": 1.1874046770493767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27346953252325623, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24332247810442317, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.769064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22416994831726333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.458152522260749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1761405104058762, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.769064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.789064, "x": 52.07785180542216, "y": 5.3729161926955085, "z": null, "yaw": 0.29666716659062037, "pitch": null, "roll": null}, "v": 1.173709845862259, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27246144031585307, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.2405161389295164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.789064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2485686327656828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.249984898590888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.173709845862259, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.789064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.07785180542216, "y": 0.37291619269550846, "z": null, "yaw": 0.29666716659062037, "pitch": null, "roll": null}, "v": 1.173709845862259, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27246144031585307, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.2405161389295164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.809064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408936342330604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.249984898590888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1743314676922318, "gear": 1, "accelerator_pedal_position": 0.2485686327656828, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.809064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.07785180542216, "y": 0.37291619269550846, "z": null, "yaw": 0.29666716659062037, "pitch": null, "roll": null}, "v": 1.173709845862259, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27246144031585307, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.2405161389295164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.829064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408936342330604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.249984898590888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1739931539749704, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.829064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.07785180542216, "y": 0.37291619269550846, "z": null, "yaw": 0.29666716659062037, "pitch": null, "roll": null}, "v": 1.173709845862259, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27246144031585307, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.2405161389295164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.8490639} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408936342330604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.249984898590888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1736553372713974, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.8490639} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.07785180542216, "y": 0.37291619269550846, "z": null, "yaw": 0.29666716659062037, "pitch": null, "roll": null}, "v": 1.173709845862259, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27246144031585307, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.2405161389295164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.8690639} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408936342330604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.249984898590888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1733180168057231, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.8690639} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.07785180542216, "y": 0.37291619269550846, "z": null, "yaw": 0.29666716659062037, "pitch": null, "roll": null}, "v": 1.173709845862259, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27246144031585307, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.2405161389295164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.8890638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408936342330604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.249984898590888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1728129648595307, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.8890638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.8990638, "x": 52.20092257108941, "y": 5.411920418508863, "z": null, "yaw": 0.31920832135345767, "pitch": null, "roll": null}, "v": 1.1728129648595307, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27239555074840255, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24033235044327686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.9090638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2593866701297724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.073650420051983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.172644861491613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.9090638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 48.20092257108941, "y": 0.4119204185088634, "z": null, "yaw": 0.31920832135345767, "pitch": null, "roll": null}, "v": 1.1728129648595307, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27239555074840255, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24033235044327686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.9290638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536042981424589, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.073650420051983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1746198055112036, "gear": 1, "accelerator_pedal_position": 0.2593866701297724, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.9290638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 48.20092257108941, "y": 0.4119204185088634, "z": null, "yaw": 0.31920832135345767, "pitch": null, "roll": null}, "v": 1.1728129648595307, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27239555074840255, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24033235044327686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.9490638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536042981424589, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.073650420051983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.175869317280074, "gear": 1, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.9490638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 48.20092257108941, "y": 0.4119204185088634, "z": null, "yaw": 0.31920832135345767, "pitch": null, "roll": null}, "v": 1.1728129648595307, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27239555074840255, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24033235044327686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.9690638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536042981424589, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.073650420051983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.177116992663563, "gear": 1, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.9690638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 48.20092257108941, "y": 0.4119204185088634, "z": null, "yaw": 0.31920832135345767, "pitch": null, "roll": null}, "v": 1.1728129648595307, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27239555074840255, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24033235044327686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.9890637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536042981424589, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.073650420051983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1783628337381244, "gear": 1, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.9890637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.0090637, "x": 52.3232989772473, "y": 5.453764344822384, "z": null, "yaw": 0.34174947611629497, "pitch": null, "roll": null}, "v": 1.1796068425799053, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "acceleration": 0.06213179823075937, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24172454907177465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.0090637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2684590839995283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.919546332895194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1796068425799053, "gear": 1, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.0090637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.3232989772473, "y": 0.4537643448223836, "z": null, "yaw": 0.34174947611629497, "pitch": null, "roll": null}, "v": 1.1796068425799053, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "acceleration": 0.06213179823075937, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24172454907177465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.0290637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26384193611251633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.919546332895194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.182705186048158, "gear": 1, "accelerator_pedal_position": 0.2684590839995283, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.0290637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.3232989772473, "y": 0.4537643448223836, "z": null, "yaw": 0.34174947611629497, "pitch": null, "roll": null}, "v": 1.1796068425799053, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "acceleration": 0.06213179823075937, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24172454907177465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.0490637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26384193611251633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.919546332895194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1852220371826732, "gear": 1, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.0490637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.3232989772473, "y": 0.4537643448223836, "z": null, "yaw": 0.34174947611629497, "pitch": null, "roll": null}, "v": 1.1796068425799053, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "acceleration": 0.06213179823075937, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24172454907177465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.0690637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26384193611251633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.919546332895194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1877351802555427, "gear": 1, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.0690637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.3232989772473, "y": 0.4537643448223836, "z": null, "yaw": 0.34174947611629497, "pitch": null, "roll": null}, "v": 1.1796068425799053, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "acceleration": 0.06213179823075937, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24172454907177465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.0890636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26384193611251633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.919546332895194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1902446182044073, "gear": 1, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.0890636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.3232989772473, "y": 0.4537643448223836, "z": null, "yaw": 0.34174947611629497, "pitch": null, "roll": null}, "v": 1.1796068425799053, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "acceleration": 0.06213179823075937, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24172454907177465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.1090636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26384193611251633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.919546332895194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1927503539737443, "gear": 1, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.1090636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.1190636, "x": 52.44579730899187, "y": 5.498760045060176, "z": null, "yaw": 0.36429063087913227, "pitch": null, "roll": null}, "v": 1.1940018344630992, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "acceleration": 0.12505560517305958, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24467436488858244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.1290636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.021604878434488772, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.340128926147996, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1952523905148298, "gear": 1, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.1290636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 48.44579730899187, "y": 0.4987600450601759, "z": null, "yaw": 0.36429063087913227, "pitch": null, "roll": null}, "v": 1.1940018344630992, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "acceleration": 0.12505560517305958, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24467436488858244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.1490636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.340128926147996, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1863179326496838, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.021604878434488772, "steering_wheel_angle": 9.155956053125985, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.1490636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 48.44579730899187, "y": 0.4987600450601759, "z": null, "yaw": 0.36429063087913227, "pitch": null, "roll": null}, "v": 1.1940018344630992, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "acceleration": 0.12505560517305958, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24467436488858244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.1690636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.340128926147996, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1808521595226396, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.241114687767215, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.1690636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 48.44579730899187, "y": 0.4987600450601759, "z": null, "yaw": 0.36429063087913227, "pitch": null, "roll": null}, "v": 1.1940018344630992, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "acceleration": 0.12505560517305958, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24467436488858244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.1890635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.340128926147996, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.175394433900931, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.325906576971134, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.1890635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 48.44579730899187, "y": 0.4987600450601759, "z": null, "yaw": 0.36429063087913227, "pitch": null, "roll": null}, "v": 1.1940018344630992, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "acceleration": 0.12505560517305958, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24467436488858244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.2090635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.340128926147996, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1699447320255194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.410331720737743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.2090635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.2290635, "x": 52.566723563991665, "y": 5.546308734635975, "z": null, "yaw": 0.38744640035374084, "pitch": null, "roll": null}, "v": 1.1645030302248467, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27178582458527084, "steering_wheel_angle": 9.494390119067042, "front_wheel_angle": 0.5102970224571116, "heading_rate": 0.25462074186382233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.2290635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2176876251595622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.321859200160748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1645030302248467, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.494390119067042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.2290635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.566723563991665, "y": 0.546308734635975, "z": null, "yaw": 0.38744640035374084, "pitch": null, "roll": null}, "v": 1.1645030302248467, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27178582458527084, "steering_wheel_angle": 9.494390119067042, "front_wheel_angle": 0.5102970224571116, "heading_rate": 0.25462074186382233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.2490635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.321859200160748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1612794483336146, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.577994481550679, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.2490635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.566723563991665, "y": 0.546308734635975, "z": null, "yaw": 0.38744640035374084, "pitch": null, "roll": null}, "v": 1.1645030302248467, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27178582458527084, "steering_wheel_angle": 9.494390119067042, "front_wheel_angle": 0.5102970224571116, "heading_rate": 0.25462074186382233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.2690635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.321859200160748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1558504425949307, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.661232864905543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.2690635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.566723563991665, "y": 0.546308734635975, "z": null, "yaw": 0.38744640035374084, "pitch": null, "roll": null}, "v": 1.1645030302248467, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27178582458527084, "steering_wheel_angle": 9.494390119067042, "front_wheel_angle": 0.5102970224571116, "heading_rate": 0.25462074186382233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.2890635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.321859200160748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.150429375953393, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.2890635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.566723563991665, "y": 0.546308734635975, "z": null, "yaw": 0.38744640035374084, "pitch": null, "roll": null}, "v": 1.1645030302248467, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27178582458527084, "steering_wheel_angle": 9.494390119067042, "front_wheel_angle": 0.5102970224571116, "heading_rate": 0.25462074186382233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.3090634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.321859200160748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1450162250483786, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.3090634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.566723563991665, "y": 0.546308734635975, "z": null, "yaw": 0.38744640035374084, "pitch": null, "roll": null}, "v": 1.1645030302248467, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27178582458527084, "steering_wheel_angle": 9.494390119067042, "front_wheel_angle": 0.5102970224571116, "heading_rate": 0.25462074186382233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.3290634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.321859200160748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1396109666048708, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.3290634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.3390634, "x": 52.683595931475715, "y": 5.595518708180422, "z": null, "yaw": 0.41212970365060864, "pitch": null, "roll": null}, "v": 1.1369112898060478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26977123729918695, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2581736066880822, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.3490634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22939180587261251, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.257400234553558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.134213577433056, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.3490634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 48.683595931475715, "y": 0.5955187081804221, "z": null, "yaw": 0.41212970365060864, "pitch": null, "roll": null}, "v": 1.1369112898060478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26977123729918695, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2581736066880822, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.3690634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22396910814292678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.257400234553558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1324966756137111, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.3690634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 48.683595931475715, "y": 0.5955187081804221, "z": null, "yaw": 0.41212970365060864, "pitch": null, "roll": null}, "v": 1.1369112898060478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26977123729918695, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2581736066880822, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.3890634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22396910814292678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.257400234553558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1301046767772325, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.3890634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 48.683595931475715, "y": 0.5955187081804221, "z": null, "yaw": 0.41212970365060864, "pitch": null, "roll": null}, "v": 1.1369112898060478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26977123729918695, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2581736066880822, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.4090633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22396910814292678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.257400234553558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.127716150534339, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.4090633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 48.683595931475715, "y": 0.5955187081804221, "z": null, "yaw": 0.41212970365060864, "pitch": null, "roll": null}, "v": 1.1369112898060478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26977123729918695, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2581736066880822, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.4290633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22396910814292678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.257400234553558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1253310895624837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.4290633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.4490633, "x": 52.79692305836316, "y": 5.646598502087921, "z": null, "yaw": 0.43710887044253477, "pitch": null, "roll": null}, "v": 1.1229494865596739, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2687576298216301, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2550031138516528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.4490633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23121164714312586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.276025676227368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1229494865596739, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.4490633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 48.79692305836316, "y": 0.6465985020879206, "z": null, "yaw": 0.43710887044253477, "pitch": null, "roll": null}, "v": 1.1229494865596739, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2687576298216301, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2550031138516528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.4690633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22889767181452536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.276025676227368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.121476323714709, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.4690633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 48.79692305836316, "y": 0.6465985020879206, "z": null, "yaw": 0.43710887044253477, "pitch": null, "roll": null}, "v": 1.1229494865596739, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2687576298216301, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2550031138516528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.4890633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22889767181452536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.276025676227368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1197161521342422, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.4890633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 48.79692305836316, "y": 0.6465985020879206, "z": null, "yaw": 0.43710887044253477, "pitch": null, "roll": null}, "v": 1.1229494865596739, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2687576298216301, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2550031138516528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.5090632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22889767181452536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.276025676227368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1179585284695888, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.5090632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 48.79692305836316, "y": 0.6465985020879206, "z": null, "yaw": 0.43710887044253477, "pitch": null, "roll": null}, "v": 1.1229494865596739, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2687576298216301, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2550031138516528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.5290632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22889767181452536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.276025676227368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1162034477972933, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.5290632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 48.79692305836316, "y": 0.6465985020879206, "z": null, "yaw": 0.43710887044253477, "pitch": null, "roll": null}, "v": 1.1229494865596739, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2687576298216301, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2550031138516528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.5490632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22889767181452536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.276025676227368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1144509052063858, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.5490632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.5590632, "x": 52.907819569870256, "y": 5.699955178982982, "z": null, "yaw": 0.4620880372344609, "pitch": null, "roll": null}, "v": 1.1135755841601789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26807928502438577, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2528744568377599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.5690632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23031181781787274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.367050996379675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1127008957983429, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.5690632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 48.907819569870256, "y": 0.6999551789829823, "z": null, "yaw": 0.4620880372344609, "pitch": null, "roll": null}, "v": 1.1135755841601789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26807928502438577, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2528744568377599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.5890632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22983597963998065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.367050996379675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1111301190910536, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.785511252914395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.5890632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 48.907819569870256, "y": 0.6999551789829823, "z": null, "yaw": 0.4620880372344609, "pitch": null, "roll": null}, "v": 1.1135755841601789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26807928502438577, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2528744568377599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.6090631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22983597963998065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.367050996379675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1095021524246351, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.785511252914395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.6090631} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 48.907819569870256, "y": 0.6999551789829823, "z": null, "yaw": 0.4620880372344609, "pitch": null, "roll": null}, "v": 1.1135755841601789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26807928502438577, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2528744568377599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.6290631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22983597963998065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.367050996379675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.107876535634424, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.785511252914395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.6290631} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 48.907819569870256, "y": 0.6999551789829823, "z": null, "yaw": 0.4620880372344609, "pitch": null, "roll": null}, "v": 1.1135755841601789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26807928502438577, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2528744568377599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.649063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22983597963998065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.367050996379675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1062532642718386, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.785511252914395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.649063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.669063, "x": 53.01643531628282, "y": 5.755603553972554, "z": null, "yaw": 0.48719539662995837, "pitch": null, "roll": null}, "v": 1.1046323338992892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26743374262592234, "steering_wheel_angle": 9.785511252914395, "front_wheel_angle": 0.5293019481555268, "heading_rate": 0.2524169903571838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.669063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22583675821801802, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.54257964736771, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1046323338992892, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.785511252914395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.669063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.01643531628282, "y": 0.7556035539725539, "z": null, "yaw": 0.48719539662995837, "pitch": null, "roll": null}, "v": 1.1046323338992892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26743374262592234, "steering_wheel_angle": 9.785511252914395, "front_wheel_angle": 0.5293019481555268, "heading_rate": 0.2524169903571838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.689063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2270542385907005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.54257964736771, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1025140175622161, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.868890984052669, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.689063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.01643531628282, "y": 0.7556035539725539, "z": null, "yaw": 0.48719539662995837, "pitch": null, "roll": null}, "v": 1.1046323338992892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26743374262592234, "steering_wheel_angle": 9.785511252914395, "front_wheel_angle": 0.5293019481555268, "heading_rate": 0.2524169903571838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.709063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2270542385907005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.54257964736771, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1005508833169888, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.951895258215732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.709063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.01643531628282, "y": 0.7556035539725539, "z": null, "yaw": 0.48719539662995837, "pitch": null, "roll": null}, "v": 1.1046323338992892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26743374262592234, "steering_wheel_angle": 9.785511252914395, "front_wheel_angle": 0.5293019481555268, "heading_rate": 0.2524169903571838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.729063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2270542385907005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.54257964736771, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0985905757849084, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.951895258215732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.729063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.01643531628282, "y": 0.7556035539725539, "z": null, "yaw": 0.48719539662995837, "pitch": null, "roll": null}, "v": 1.1046323338992892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26743374262592234, "steering_wheel_angle": 9.785511252914395, "front_wheel_angle": 0.5293019481555268, "heading_rate": 0.2524169903571838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.749063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2270542385907005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.54257964736771, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0966330893592262, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.951895258215732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.749063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.01643531628282, "y": 0.7556035539725539, "z": null, "yaw": 0.48719539662995837, "pitch": null, "roll": null}, "v": 1.1046323338992892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26743374262592234, "steering_wheel_angle": 9.785511252914395, "front_wheel_angle": 0.5293019481555268, "heading_rate": 0.2524169903571838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.769063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2270542385907005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.54257964736771, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0946784184478981, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.951895258215732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.769063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.779063, "x": 53.12265197621588, "y": 5.813460601648707, "z": null, "yaw": 0.5128242215510951, "pitch": null, "roll": null}, "v": 1.0937021370666113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2666469504995713, "steering_wheel_angle": 9.951895258215732, "front_wheel_angle": 0.5402975531287564, "heading_rate": 0.25626558870097105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.789063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23422695792296108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.549657281949427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0927265574735343, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.951895258215732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.789063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 49.12265197621588, "y": 0.8134606016487069, "z": null, "yaw": 0.5128242215510951, "pitch": null, "roll": null}, "v": 1.0937021370666113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2666469504995713, "steering_wheel_angle": 9.951895258215732, "front_wheel_angle": 0.5402975531287564, "heading_rate": 0.25626558870097105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.809063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23194614202989267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.549657281949427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.091673768736955, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.993273763815132, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.809063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 49.12265197621588, "y": 0.8134606016487069, "z": null, "yaw": 0.5128242215510951, "pitch": null, "roll": null}, "v": 1.0937021370666113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2666469504995713, "steering_wheel_angle": 9.951895258215732, "front_wheel_angle": 0.5402975531287564, "heading_rate": 0.25626558870097105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.829063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23194614202989267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.549657281949427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0903374924730798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.993273763815132, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.829063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 49.12265197621588, "y": 0.8134606016487069, "z": null, "yaw": 0.5128242215510951, "pitch": null, "roll": null}, "v": 1.0937021370666113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2666469504995713, "steering_wheel_angle": 9.951895258215732, "front_wheel_angle": 0.5402975531287564, "heading_rate": 0.25626558870097105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.849063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23194614202989267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.549657281949427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0890031347717997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.993273763815132, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.849063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 49.12265197621588, "y": 0.8134606016487069, "z": null, "yaw": 0.5128242215510951, "pitch": null, "roll": null}, "v": 1.0937021370666113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2666469504995713, "steering_wheel_angle": 9.951895258215732, "front_wheel_angle": 0.5402975531287564, "heading_rate": 0.25626558870097105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.869063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23194614202989267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.549657281949427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0876706921665846, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.993273763815132, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.869063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.889063, "x": 53.22645589044781, "y": 5.8735267995967755, "z": null, "yaw": 0.5387300305509897, "pitch": null, "roll": null}, "v": 1.0863401611989445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2661183575182847, "steering_wheel_angle": 9.993273763815132, "front_wheel_angle": 0.5430475964576865, "heading_rate": 0.2561300963851827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.889063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22788726542757837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.692335255396786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0863401611989445, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.993273763815132, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.889063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.22645589044781, "y": 0.8735267995967755, "z": null, "yaw": 0.5387300305509897, "pitch": null, "roll": null}, "v": 1.0863401611989445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2661183575182847, "steering_wheel_angle": 9.993273763815132, "front_wheel_angle": 0.5430475964576865, "heading_rate": 0.2561300963851827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.9090629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2291292355310363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.692335255396786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0845043607593683, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.07644705614864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.9090629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.22645589044781, "y": 0.8735267995967755, "z": null, "yaw": 0.5387300305509897, "pitch": null, "roll": null}, "v": 1.0863401611989445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2661183575182847, "steering_wheel_angle": 9.993273763815132, "front_wheel_angle": 0.5430475964576865, "heading_rate": 0.2561300963851827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.9290628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2291292355310363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.692335255396786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0828263825155298, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.9290628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.22645589044781, "y": 0.8735267995967755, "z": null, "yaw": 0.5387300305509897, "pitch": null, "roll": null}, "v": 1.0863401611989445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2661183575182847, "steering_wheel_angle": 9.993273763815132, "front_wheel_angle": 0.5430475964576865, "heading_rate": 0.2561300963851827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.9490628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2291292355310363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.692335255396786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0811508084534553, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.9490628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.22645589044781, "y": 0.8735267995967755, "z": null, "yaw": 0.5387300305509897, "pitch": null, "roll": null}, "v": 1.0863401611989445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2661183575182847, "steering_wheel_angle": 9.993273763815132, "front_wheel_angle": 0.5430475964576865, "heading_rate": 0.2561300963851827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.9690628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2291292355310363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.692335255396786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0794776340058525, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.9690628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.22645589044781, "y": 0.8735267995967755, "z": null, "yaw": 0.5387300305509897, "pitch": null, "roll": null}, "v": 1.0863401611989445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2661183575182847, "steering_wheel_angle": 9.993273763815132, "front_wheel_angle": 0.5430475964576865, "heading_rate": 0.2561300963851827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.9890628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2291292355310363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.692335255396786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0778068546167932, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.9890628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.9990628, "x": 53.327881343302934, "y": 5.935801606005048, "z": null, "yaw": 0.5650660921102498, "pitch": null, "roll": null}, "v": 1.0769723616485887, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654473127599788, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25872100196405745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.0090628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23842402878288338, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.641835080473687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0761384657416786, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.0090628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 49.327881343302934, "y": 0.9358016060050476, "z": null, "yaw": 0.5650660921102498, "pitch": null, "roll": null}, "v": 1.0769723616485887, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654473127599788, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25872100196405745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.0290627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23548585172734687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.641835080473687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0756338965734082, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.0290627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 49.327881343302934, "y": 0.9358016060050476, "z": null, "yaw": 0.5650660921102498, "pitch": null, "roll": null}, "v": 1.0769723616485887, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654473127599788, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25872100196405745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.0490627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23548585172734687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.641835080473687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0747629080128949, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.0490627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 49.327881343302934, "y": 0.9358016060050476, "z": null, "yaw": 0.5650660921102498, "pitch": null, "roll": null}, "v": 1.0769723616485887, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654473127599788, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25872100196405745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.0690627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23548585172734687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.641835080473687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0738931645140442, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.0690627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 49.327881343302934, "y": 0.9358016060050476, "z": null, "yaw": 0.5650660921102498, "pitch": null, "roll": null}, "v": 1.0769723616485887, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654473127599788, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25872100196405745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.0890627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23548585172734687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.641835080473687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0730246639945906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.0890627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.1090627, "x": 53.426953670347736, "y": 6.000296330387909, "z": null, "yaw": 0.5914913851163595, "pitch": null, "roll": null}, "v": 1.0721574043765414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2651030852164215, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2575643050847325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.1090627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2428009709190308, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.601276199619413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0721574043765414, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.1090627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.426953670347736, "y": 1.0002963303879087, "z": null, "yaw": 0.5914913851163595, "pitch": null, "roll": null}, "v": 1.0721574043765414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2651030852164215, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2575643050847325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.1290627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049778328436422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.601276199619413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0722054468693667, "gear": 1, "accelerator_pedal_position": 0.2428009709190308, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.1290627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.426953670347736, "y": 1.0002963303879087, "z": null, "yaw": 0.5914913851163595, "pitch": null, "roll": null}, "v": 1.0721574043765414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2651030852164215, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2575643050847325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.1490626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049778328436422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.601276199619413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0719656251274112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.1490626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.426953670347736, "y": 1.0002963303879087, "z": null, "yaw": 0.5914913851163595, "pitch": null, "roll": null}, "v": 1.0721574043765414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2651030852164215, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2575643050847325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.1690626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049778328436422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.601276199619413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0717261459228178, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.1690626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.426953670347736, "y": 1.0002963303879087, "z": null, "yaw": 0.5914913851163595, "pitch": null, "roll": null}, "v": 1.0721574043765414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2651030852164215, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2575643050847325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.1890626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049778328436422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.601276199619413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.071487008743408, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.1890626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.426953670347736, "y": 1.0002963303879087, "z": null, "yaw": 0.5914913851163595, "pitch": null, "roll": null}, "v": 1.0721574043765414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2651030852164215, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2575643050847325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.2090626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049778328436422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.601276199619413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0712482130778342, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.2090626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.2190626, "x": 53.524023287387024, "y": 6.067205273138756, "z": null, "yaw": 0.6179166781224691, "pitch": null, "roll": null}, "v": 1.0711289431531659, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2650296192862625, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2573172379104314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.2290626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24234990116992877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.632576047846722, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.071009758415576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.2290626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 49.524023287387024, "y": 1.0672052731387556, "z": null, "yaw": 0.6179166781224691, "pitch": null, "roll": null}, "v": 1.0711289431531659, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2650296192862625, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2573172379104314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.2490625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24176744065229103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.632576047846722, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.071003076309915, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.2490625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 49.524023287387024, "y": 1.0672052731387556, "z": null, "yaw": 0.6179166781224691, "pitch": null, "roll": null}, "v": 1.0711289431531659, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2650296192862625, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2573172379104314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.2690625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24176744065229103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.632576047846722, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0709236221803202, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.2690625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 49.524023287387024, "y": 1.0672052731387556, "z": null, "yaw": 0.6179166781224691, "pitch": null, "roll": null}, "v": 1.0711289431531659, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2650296192862625, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2573172379104314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.2890625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24176744065229103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.632576047846722, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0708442815006813, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.2890625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 49.524023287387024, "y": 1.0672052731387556, "z": null, "yaw": 0.6179166781224691, "pitch": null, "roll": null}, "v": 1.0711289431531659, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2650296192862625, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2573172379104314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.3090625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24176744065229103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.632576047846722, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0707650541064901, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.3090625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.3290625, "x": 53.61921169543759, "y": 6.136597953711866, "z": null, "yaw": 0.6443419711285787, "pitch": null, "roll": null}, "v": 1.0706859398334834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2649979808092453, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25721081525111056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.3290625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23801695273214843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.750632574914366, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0706859398334834, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.3290625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.61921169543759, "y": 1.136597953711866, "z": null, "yaw": 0.6443419711285787, "pitch": null, "roll": null}, "v": 1.0706859398334834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2649979808092453, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25721081525111056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.3490624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23918739905074654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.750632574914366, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0701382949179596, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.200778807951238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.3490624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.61921169543759, "y": 1.136597953711866, "z": null, "yaw": 0.6443419711285787, "pitch": null, "roll": null}, "v": 1.0706859398334834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2649979808092453, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25721081525111056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.3690624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23918739905074654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.750632574914366, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0697376853805431, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.200778807951238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.3690624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.61921169543759, "y": 1.136597953711866, "z": null, "yaw": 0.6443419711285787, "pitch": null, "roll": null}, "v": 1.0706859398334834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2649979808092453, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25721081525111056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.3890624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23918739905074654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.750632574914366, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0693376476833556, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.200778807951238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.3890624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.61921169543759, "y": 1.136597953711866, "z": null, "yaw": 0.6443419711285787, "pitch": null, "roll": null}, "v": 1.0706859398334834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2649979808092453, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25721081525111056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.4090624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23918739905074654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.750632574914366, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0689381809461487, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.200778807951238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.4090624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.61921169543759, "y": 1.136597953711866, "z": null, "yaw": 0.6443419711285787, "pitch": null, "roll": null}, "v": 1.0706859398334834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2649979808092453, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25721081525111056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.4290624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23918739905074654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.750632574914366, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0685392842902042, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.200778807951238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.4290624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.4390624, "x": 53.71240745943211, "y": 6.208400368869333, "z": null, "yaw": 0.6710528977786145, "pitch": null, "roll": null}, "v": 1.0683400494685236, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26483050708641026, "steering_wheel_angle": 10.200778807951238, "front_wheel_angle": 0.5569338799933807, "heading_rate": 0.25985969925836855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.4490623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24019110178846273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.798874361321507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.068140956838331, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.200778807951238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.4490623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 49.71240745943211, "y": 1.2084003688693334, "z": null, "yaw": 0.6710528977786145, "pitch": null, "roll": null}, "v": 1.0683400494685236, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26483050708641026, "steering_wheel_angle": 10.200778807951238, "front_wheel_angle": 0.5569338799933807, "heading_rate": 0.25985969925836855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.4690623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986907078564468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.798874361321507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0678686157922692, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.242198890096242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.4690623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 49.71240745943211, "y": 1.2084003688693334, "z": null, "yaw": 0.6710528977786145, "pitch": null, "roll": null}, "v": 1.0683400494685236, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26483050708641026, "steering_wheel_angle": 10.200778807951238, "front_wheel_angle": 0.5569338799933807, "heading_rate": 0.25985969925836855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.4890623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986907078564468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.798874361321507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.067556423771891, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.242198890096242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.4890623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 49.71240745943211, "y": 1.2084003688693334, "z": null, "yaw": 0.6710528977786145, "pitch": null, "roll": null}, "v": 1.0683400494685236, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26483050708641026, "steering_wheel_angle": 10.200778807951238, "front_wheel_angle": 0.5569338799933807, "heading_rate": 0.25985969925836855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.5090623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986907078564468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.798874361321507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0672446771073785, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.242198890096242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.5090623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 49.71240745943211, "y": 1.2084003688693334, "z": null, "yaw": 0.6710528977786145, "pitch": null, "roll": null}, "v": 1.0683400494685236, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26483050708641026, "steering_wheel_angle": 10.200778807951238, "front_wheel_angle": 0.5569338799933807, "heading_rate": 0.25985969925836855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.5290623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986907078564468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.798874361321507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0669333751245507, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.242198890096242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.5290623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.5490623, "x": 53.803474371849575, "y": 6.2825351033675005, "z": null, "yaw": 0.6979453675196218, "pitch": null, "roll": null}, "v": 1.0666225171503554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26470796179843936, "steering_wheel_angle": 10.242198890096242, "front_wheel_angle": 0.5597250687411017, "heading_rate": 0.2610586125154011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.5490623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24156186014983982, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.831956439609591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0666225171503554, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.242198890096242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.5490623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 49.803474371849575, "y": 1.2825351033675005, "z": null, "yaw": 0.6979453675196218, "pitch": null, "roll": null}, "v": 1.0666225171503554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26470796179843936, "steering_wheel_angle": 10.242198890096242, "front_wheel_angle": 0.5597250687411017, "heading_rate": 0.2610586125154011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.5690622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102673585827547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.831956439609591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0665236257162976, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.283605034976686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.5690622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 49.803474371849575, "y": 1.2825351033675005, "z": null, "yaw": 0.6979453675196218, "pitch": null, "roll": null}, "v": 1.0666225171503554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26470796179843936, "steering_wheel_angle": 10.242198890096242, "front_wheel_angle": 0.5597250687411017, "heading_rate": 0.2610586125154011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.5890622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102673585827547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.831956439609591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0663580086321356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.283605034976686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.5890622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 49.803474371849575, "y": 1.2825351033675005, "z": null, "yaw": 0.6979453675196218, "pitch": null, "roll": null}, "v": 1.0666225171503554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26470796179843936, "steering_wheel_angle": 10.242198890096242, "front_wheel_angle": 0.5597250687411017, "heading_rate": 0.2610586125154011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.6090622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102673585827547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.831956439609591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0661926277263825, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.283605034976686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.6090622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 49.803474371849575, "y": 1.2825351033675005, "z": null, "yaw": 0.6979453675196218, "pitch": null, "roll": null}, "v": 1.0666225171503554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26470796179843936, "steering_wheel_angle": 10.242198890096242, "front_wheel_angle": 0.5597250687411017, "heading_rate": 0.2610586125154011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.6290622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102673585827547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.831956439609591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0660274826512997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.283605034976686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.6290622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 49.803474371849575, "y": 1.2825351033675005, "z": null, "yaw": 0.6979453675196218, "pitch": null, "roll": null}, "v": 1.0666225171503554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26470796179843936, "steering_wheel_angle": 10.242198890096242, "front_wheel_angle": 0.5597250687411017, "heading_rate": 0.2610586125154011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.6490622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102673585827547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.831956439609591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0658625730596905, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.283605034976686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.6490622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.6590621, "x": 53.89240079607856, "y": 6.359007578204368, "z": null, "yaw": 0.7250205582208973, "pitch": null, "roll": null}, "v": 1.0657802064618378, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26464788480795026, "steering_wheel_angle": 10.283605034976686, "front_wheel_angle": 0.5625218593050793, "heading_rate": 0.2624767778758382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.6690621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23335387233415397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0656978986049006, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.283605034976686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.6690621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 49.89240079607856, "y": 1.359007578204368, "z": null, "yaw": 0.7250205582208973, "pitch": null, "roll": null}, "v": 1.0657802064618378, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26464788480795026, "steering_wheel_angle": 10.283605034976686, "front_wheel_angle": 0.5625218593050793, "heading_rate": 0.2624767778758382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.689062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23574863990604947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0645746929583322, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.366891721050093, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.689062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 49.89240079607856, "y": 1.359007578204368, "z": null, "yaw": 0.7250205582208973, "pitch": null, "roll": null}, "v": 1.0657802064618378, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26464788480795026, "steering_wheel_angle": 10.283605034976686, "front_wheel_angle": 0.5625218593050793, "heading_rate": 0.2624767778758382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.709062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23574863990604947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0637523276241219, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.709062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 49.89240079607856, "y": 1.359007578204368, "z": null, "yaw": 0.7250205582208973, "pitch": null, "roll": null}, "v": 1.0657802064618378, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26464788480795026, "steering_wheel_angle": 10.283605034976686, "front_wheel_angle": 0.5625218593050793, "heading_rate": 0.2624767778758382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.729062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23574863990604947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.062931134222293, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.729062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 49.89240079607856, "y": 1.359007578204368, "z": null, "yaw": 0.7250205582208973, "pitch": null, "roll": null}, "v": 1.0657802064618378, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26464788480795026, "steering_wheel_angle": 10.283605034976686, "front_wheel_angle": 0.5625218593050793, "heading_rate": 0.2624767778758382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.749062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23574863990604947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0621111108131063, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.749062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.769062, "x": 53.97901293903882, "y": 6.437687220711942, "z": null, "yaw": 0.7524827019597181, "pitch": null, "roll": null}, "v": 1.0612922554607394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643280252880464, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26630417011238827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.769062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2327153876928454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0612922554607394, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.769062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 49.97901293903882, "y": 1.4376872207119424, "z": null, "yaw": 0.7524827019597181, "pitch": null, "roll": null}, "v": 1.0612922554607394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643280252880464, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26630417011238827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.789062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23364728664447704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.060095544716244, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.789062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 49.97901293903882, "y": 1.4376872207119424, "z": null, "yaw": 0.7524827019597181, "pitch": null, "roll": null}, "v": 1.0612922554607394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643280252880464, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26630417011238827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.809062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23364728664447704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0590169835750083, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.809062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 49.97901293903882, "y": 1.4376872207119424, "z": null, "yaw": 0.7524827019597181, "pitch": null, "roll": null}, "v": 1.0612922554607394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643280252880464, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26630417011238827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.829062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23364728664447704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0579399574505601, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.829062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 49.97901293903882, "y": 1.4376872207119424, "z": null, "yaw": 0.7524827019597181, "pitch": null, "roll": null}, "v": 1.0612922554607394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643280252880464, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26630417011238827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.849062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23364728664447704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0568644636944224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.849062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 49.97901293903882, "y": 1.4376872207119424, "z": null, "yaw": 0.7524827019597181, "pitch": null, "roll": null}, "v": 1.0612922554607394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643280252880464, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26630417011238827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.869062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23364728664447704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0557904996638658, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.869062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.879062, "x": 54.063002851029964, "y": 6.518321272529326, "z": null, "yaw": 0.7800843909022661, "pitch": null, "roll": null}, "v": 1.0552540904713956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26389831647813594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26478904691402777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.889062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24335506812075086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0547180627218942, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.889062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.063002851029964, "y": 1.5183212725293256, "z": null, "yaw": 0.7800843909022661, "pitch": null, "roll": null}, "v": 1.0552540904713956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26389831647813594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26478904691402777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.909062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402998989657948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0548601915946214, "gear": 1, "accelerator_pedal_position": 0.24335506812075086, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.909062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.063002851029964, "y": 1.5183212725293256, "z": null, "yaw": 0.7800843909022661, "pitch": null, "roll": null}, "v": 1.0552540904713956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26389831647813594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26478904691402777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.929062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402998989657948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0546203580553382, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.929062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.063002851029964, "y": 1.5183212725293256, "z": null, "yaw": 0.7800843909022661, "pitch": null, "roll": null}, "v": 1.0552540904713956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26389831647813594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26478904691402777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.9490619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402998989657948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0543808654074625, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.9490619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.063002851029964, "y": 1.5183212725293256, "z": null, "yaw": 0.7800843909022661, "pitch": null, "roll": null}, "v": 1.0552540904713956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26389831647813594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26478904691402777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.9690619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402998989657948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.054141713143528, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.9690619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.9890618, "x": 54.144431524686674, "y": 6.600936003455046, "z": null, "yaw": 0.8076860798448141, "pitch": null, "roll": null}, "v": 1.0539029007568874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2638022582800822, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2644500003849166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.9890618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26000665854078553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.765073905190201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0539029007568874, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.9890618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.144431524686674, "y": 1.600936003455046, "z": null, "yaw": 0.8076860798448141, "pitch": null, "roll": null}, "v": 1.0539029007568874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2638022582800822, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2644500003849166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.0090618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538434892228095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.765073905190201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0561268971173907, "gear": 1, "accelerator_pedal_position": 0.26000665854078553, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.0090618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.144431524686674, "y": 1.600936003455046, "z": null, "yaw": 0.8076860798448141, "pitch": null, "roll": null}, "v": 1.0539029007568874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2638022582800822, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2644500003849166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.0290618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538434892228095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.765073905190201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.057577609440657, "gear": 1, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.0290618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.144431524686674, "y": 1.600936003455046, "z": null, "yaw": 0.8076860798448141, "pitch": null, "roll": null}, "v": 1.0539029007568874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2638022582800822, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2644500003849166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.0490618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538434892228095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.765073905190201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.059026258300063, "gear": 1, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.0490618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.144431524686674, "y": 1.600936003455046, "z": null, "yaw": 0.8076860798448141, "pitch": null, "roll": null}, "v": 1.0539029007568874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2638022582800822, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2644500003849166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.0690618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538434892228095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.765073905190201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0604728457915027, "gear": 1, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.0690618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.144431524686674, "y": 1.600936003455046, "z": null, "yaw": 0.8076860798448141, "pitch": null, "roll": null}, "v": 1.0539029007568874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2638022582800822, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2644500003849166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.0890617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538434892228095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.765073905190201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.06191737401147, "gear": 1, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.0890617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.0990617, "x": 54.22381918923415, "y": 6.6860596163655, "z": null, "yaw": 0.8352877687873621, "pitch": null, "roll": null}, "v": 1.062638866549967, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "acceleration": 0.0720978507080351, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26664206775249233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.1090617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22020808490874705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0633598450570474, "gear": 1, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.1090617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.22381918923415, "y": 1.6860596163655002, "z": null, "yaw": 0.8352877687873621, "pitch": null, "roll": null}, "v": 1.062638866549967, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "acceleration": 0.0720978507080351, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26664206775249233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.1290617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23075024060158958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0605973335357355, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.1290617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.22381918923415, "y": 1.6860596163655002, "z": null, "yaw": 0.8352877687873621, "pitch": null, "roll": null}, "v": 1.062638866549967, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "acceleration": 0.0720978507080351, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26664206775249233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.1490617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23075024060158958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0591560562482252, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.1490617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.22381918923415, "y": 1.6860596163655002, "z": null, "yaw": 0.8352877687873621, "pitch": null, "roll": null}, "v": 1.062638866549967, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "acceleration": 0.0720978507080351, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26664206775249233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.1690617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23075024060158958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0577168303303828, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.1690617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.22381918923415, "y": 1.6860596163655002, "z": null, "yaw": 0.8352877687873621, "pitch": null, "roll": null}, "v": 1.062638866549967, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "acceleration": 0.0720978507080351, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26664206775249233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.1890616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23075024060158958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0562796520342408, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.1890616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.2090616, "x": 54.3009130074523, "y": 6.773432351662795, "z": null, "yaw": 0.8628894577299101, "pitch": null, "roll": null}, "v": 1.0548445176206989, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26386919544457943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2646862750738073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.2090616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24129565108748577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0548445176206989, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.2090616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.3009130074523, "y": 1.7734323516627946, "z": null, "yaw": 0.8628894577299101, "pitch": null, "roll": null}, "v": 1.0548445176206989, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26386919544457943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2646862750738073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.2290616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23797247005729869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0547291311300997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.2290616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.3009130074523, "y": 1.7734323516627946, "z": null, "yaw": 0.8628894577299101, "pitch": null, "roll": null}, "v": 1.0548445176206989, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26386919544457943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2646862750738073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.2490616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23797247005729869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0541986586767216, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.2490616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.3009130074523, "y": 1.7734323516627946, "z": null, "yaw": 0.8628894577299101, "pitch": null, "roll": null}, "v": 1.0548445176206989, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26386919544457943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2646862750738073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.2690616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23797247005729869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0536689401452226, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.2690616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.3009130074523, "y": 1.7734323516627946, "z": null, "yaw": 0.8628894577299101, "pitch": null, "roll": null}, "v": 1.0548445176206989, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26386919544457943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2646862750738073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.2890615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23797247005729869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0531399743519074, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.2890615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.3009130074523, "y": 1.7734323516627946, "z": null, "yaw": 0.8628894577299101, "pitch": null, "roll": null}, "v": 1.0548445176206989, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26386919544457943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2646862750738073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.3090615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23797247005729869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0526117601152414, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.3090615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.3190615, "x": 54.375180971341145, "y": 6.862440183237372, "z": null, "yaw": 0.8904911466724581, "pitch": null, "roll": null}, "v": 1.0523479344620117, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636917584747652, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26405982133048655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.3390615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23748836387798727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.051234013068664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.3390615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.375180971341145, "y": 1.8624401832373723, "z": null, "yaw": 0.8904911466724581, "pitch": null, "roll": null}, "v": 1.0523479344620117, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636917584747652, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26405982133048655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.3590615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23763077530390359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.051234013068664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.3590615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.375180971341145, "y": 1.8624401832373723, "z": null, "yaw": 0.8904911466724581, "pitch": null, "roll": null}, "v": 1.0523479344620117, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636917584747652, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26405982133048655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.3790615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23763077530390359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.050382009912236, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.3790615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.375180971341145, "y": 1.8624401832373723, "z": null, "yaw": 0.8904911466724581, "pitch": null, "roll": null}, "v": 1.0523479344620117, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636917584747652, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26405982133048655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.3990614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23763077530390359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.050098412127099, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.3990614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.375180971341145, "y": 1.8624401832373723, "z": null, "yaw": 0.8904911466724581, "pitch": null, "roll": null}, "v": 1.0523479344620117, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636917584747652, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26405982133048655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.4190614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23763077530390359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0495318205019324, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.4190614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.4290614, "x": 54.44676490348642, "y": 6.9532108640644354, "z": null, "yaw": 0.9180928356150061, "pitch": null, "roll": null}, "v": 1.0492488263439508, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26347167231303914, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2632821793461771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.4390614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23454894728524658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0489660330773143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.4390614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.44676490348642, "y": 1.9532108640644354, "z": null, "yaw": 0.9180928356150061, "pitch": null, "roll": null}, "v": 1.0492488263439508, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26347167231303914, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2632821793461771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.4590614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23550101485721472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0480159567831484, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.4590614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.44676490348642, "y": 1.9532108640644354, "z": null, "yaw": 0.9180928356150061, "pitch": null, "roll": null}, "v": 1.0492488263439508, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26347167231303914, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2632821793461771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.4790614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23550101485721472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.04718619468256, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.4790614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.44676490348642, "y": 1.9532108640644354, "z": null, "yaw": 0.9180928356150061, "pitch": null, "roll": null}, "v": 1.0492488263439508, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26347167231303914, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2632821793461771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.4990613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23550101485721472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0463576095614446, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.4990613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.44676490348642, "y": 1.9532108640644354, "z": null, "yaw": 0.9180928356150061, "pitch": null, "roll": null}, "v": 1.0492488263439508, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26347167231303914, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2632821793461771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.5190613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23550101485721472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0455301994757868, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.5190613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.5390613, "x": 54.515570507517864, "y": 7.045591690671431, "z": null, "yaw": 0.9456945245575541, "pitch": null, "roll": null}, "v": 1.0447039624854961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2631492618166038, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26214176190520166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.5390613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24243460152006116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0447039624854961, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.5390613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.515570507517864, "y": 2.045591690671431, "z": null, "yaw": 0.9456945245575541, "pitch": null, "roll": null}, "v": 1.0447039624854961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2631492618166038, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26214176190520166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.5590613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24025173373190023, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0447452877853391, "gear": 1, "accelerator_pedal_position": 0.24243460152006116, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.5590613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.515570507517864, "y": 2.045591690671431, "z": null, "yaw": 0.9456945245575541, "pitch": null, "roll": null}, "v": 1.0447039624854961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2631492618166038, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26214176190520166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.5790613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24025173373190023, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0445137927576194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.5790613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.515570507517864, "y": 2.045591690671431, "z": null, "yaw": 0.9456945245575541, "pitch": null, "roll": null}, "v": 1.0447039624854961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2631492618166038, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26214176190520166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.5990613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24025173373190023, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0441671652589128, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.5990613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.515570507517864, "y": 2.045591690671431, "z": null, "yaw": 0.9456945245575541, "pitch": null, "roll": null}, "v": 1.0447039624854961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2631492618166038, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26214176190520166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.6190612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24025173373190023, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0440517865276266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.6190612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.515570507517864, "y": 2.045591690671431, "z": null, "yaw": 0.9456945245575541, "pitch": null, "roll": null}, "v": 1.0447039624854961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2631492618166038, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26214176190520166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.6390612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24025173373190023, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.043706140789126, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.6390612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.6490612, "x": 54.58161993948238, "y": 7.139581040507427, "z": null, "yaw": 0.9732962135001021, "pitch": null, "roll": null}, "v": 1.043706140789126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26307853212266563, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26189138404989865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.6590612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23575379601873617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.043591088826143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.6590612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.58161993948238, "y": 2.1395810405074274, "z": null, "yaw": 0.9732962135001021, "pitch": null, "roll": null}, "v": 1.043706140789126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26307853212266563, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26189138404989865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.6790612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23715586598867175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0424912854858446, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.6790612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.58161993948238, "y": 2.1395810405074274, "z": null, "yaw": 0.9732962135001021, "pitch": null, "roll": null}, "v": 1.043706140789126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26307853212266563, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26189138404989865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.6990612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23715586598867175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0421836026593623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.6990612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.58161993948238, "y": 2.1395810405074274, "z": null, "yaw": 0.9732962135001021, "pitch": null, "roll": null}, "v": 1.043706140789126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26307853212266563, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26189138404989865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.7190611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23715586598867175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0415688907828882, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.7190611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.58161993948238, "y": 2.1395810405074274, "z": null, "yaw": 0.9732962135001021, "pitch": null, "roll": null}, "v": 1.043706140789126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26307853212266563, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26189138404989865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.739061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23715586598867175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.040648454811632, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.739061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.759061, "x": 54.64491993074157, "y": 7.235159529806492, "z": null, "yaw": 1.00089790244265, "pitch": null, "roll": null}, "v": 1.040342077287868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2628402202421498, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26104725828312864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.759061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23417659854198275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.040342077287868, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.759061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.64491993074157, "y": 2.2351595298064924, "z": null, "yaw": 1.00089790244265, "pitch": null, "roll": null}, "v": 1.040342077287868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2628402202421498, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26104725828312864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.779061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23509570462766016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0389234725534795, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.779061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.64491993074157, "y": 2.2351595298064924, "z": null, "yaw": 1.00089790244265, "pitch": null, "roll": null}, "v": 1.040342077287868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2628402202421498, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26104725828312864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.799061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23509570462766016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0384895561582492, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.799061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.64491993074157, "y": 2.2351595298064924, "z": null, "yaw": 1.00089790244265, "pitch": null, "roll": null}, "v": 1.040342077287868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2628402202421498, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26104725828312864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.819061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23509570462766016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0371896485562904, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.819061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.64491993074157, "y": 2.2351595298064924, "z": null, "yaw": 1.00089790244265, "pitch": null, "roll": null}, "v": 1.040342077287868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2628402202421498, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26104725828312864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.839061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23509570462766016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0363245755950345, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.839061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.64491993074157, "y": 2.2351595298064924, "z": null, "yaw": 1.00089790244265, "pitch": null, "roll": null}, "v": 1.040342077287868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2628402202421498, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26104725828312864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.859061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23509570462766016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0358924979838675, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.859061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.869061, "x": 54.70531779948901, "y": 7.332062505839323, "z": null, "yaw": 1.0284995913851993, "pitch": null, "roll": null}, "v": 1.0354607259473665, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624948254471628, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25982240790749395, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.879061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2453095760536653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0350292592321235, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.879061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.70531779948901, "y": 2.332062505839323, "z": null, "yaw": 1.0284995913851993, "pitch": null, "roll": null}, "v": 1.0354607259473665, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624948254471628, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25982240790749395, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.899061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24210046938923505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0354435233664412, "gear": 1, "accelerator_pedal_position": 0.2453095760536653, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.899061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.70531779948901, "y": 2.332062505839323, "z": null, "yaw": 1.0284995913851993, "pitch": null, "roll": null}, "v": 1.0354607259473665, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624948254471628, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25982240790749395, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.919061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24210046938923505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0354562053734713, "gear": 1, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.919061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.70531779948901, "y": 2.332062505839323, "z": null, "yaw": 1.0284995913851993, "pitch": null, "roll": null}, "v": 1.0354607259473665, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624948254471628, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25982240790749395, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.939061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24210046938923505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0354751947763265, "gear": 1, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.939061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.70531779948901, "y": 2.332062505839323, "z": null, "yaw": 1.0284995913851993, "pitch": null, "roll": null}, "v": 1.0354607259473665, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624948254471628, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25982240790749395, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.959061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24210046938923505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0354815156278658, "gear": 1, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.959061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.979061, "x": 54.76286888730258, "y": 7.430342805226212, "z": null, "yaw": 1.0561012803277485, "pitch": null, "roll": null}, "v": 1.0354941439257566, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "acceleration": 0.000630745265385757, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2598307932951723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.979061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23188947381791758, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.034862264155203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.979061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.76286888730258, "y": 2.4303428052262124, "z": null, "yaw": 1.0561012803277485, "pitch": null, "roll": null}, "v": 1.0354941439257566, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "acceleration": 0.000630745265385757, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2598307932951723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.9990609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2350805301746824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.034230831146168, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.9990609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.76286888730258, "y": 2.4303428052262124, "z": null, "yaw": 1.0561012803277485, "pitch": null, "roll": null}, "v": 1.0354941439257566, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "acceleration": 0.000630745265385757, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2598307932951723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.0190609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2350805301746824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0333680449221831, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.0190609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.76286888730258, "y": 2.4303428052262124, "z": null, "yaw": 1.0561012803277485, "pitch": null, "roll": null}, "v": 1.0354941439257566, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "acceleration": 0.000630745265385757, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2598307932951723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.0390608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2350805301746824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0320761506926337, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.0390608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.76286888730258, "y": 2.4303428052262124, "z": null, "yaw": 1.0561012803277485, "pitch": null, "roll": null}, "v": 1.0354941439257566, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "acceleration": 0.000630745265385757, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2598307932951723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.0590608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2350805301746824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.031646127635122, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.0590608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.76286888730258, "y": 2.4303428052262124, "z": null, "yaw": 1.0561012803277485, "pitch": null, "roll": null}, "v": 1.0354941439257566, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "acceleration": 0.000630745265385757, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2598307932951723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.0790608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2350805301746824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.030357879994875, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.0790608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.0890608, "x": 54.81755918070452, "y": 7.529940810389744, "z": null, "yaw": 1.0837029692702977, "pitch": null, "roll": null}, "v": 1.030357879994875, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2621342676084191, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2585419791192902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.0990608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2275224800548705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0299290704547084, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.0990608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.81755918070452, "y": 2.5299408103897436, "z": null, "yaw": 1.0837029692702977, "pitch": null, "roll": null}, "v": 1.030357879994875, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2621342676084191, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2585419791192902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.1190608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22986622621354574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0281279365438938, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.1190608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.81755918070452, "y": 2.5299408103897436, "z": null, "yaw": 1.0837029692702977, "pitch": null, "roll": null}, "v": 1.030357879994875, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2621342676084191, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2585419791192902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.1390607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22986622621354574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.026622208844013, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.1390607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.81755918070452, "y": 2.5299408103897436, "z": null, "yaw": 1.0837029692702977, "pitch": null, "roll": null}, "v": 1.030357879994875, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2621342676084191, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2585419791192902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.1590607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22986622621354574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0251186046747993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.1590607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.81755918070452, "y": 2.5299408103897436, "z": null, "yaw": 1.0837029692702977, "pitch": null, "roll": null}, "v": 1.030357879994875, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2621342676084191, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2585419791192902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.1790607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22986622621354574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0236171201374213, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.1790607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.1990607, "x": 54.86916246364028, "y": 7.630390385483864, "z": null, "yaw": 1.111304658212847, "pitch": null, "roll": null}, "v": 1.0221177513423683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615531345432102, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2564743294109896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.1990607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23206464454424763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0221177513423683, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.1990607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.86916246364028, "y": 2.6303903854838637, "z": null, "yaw": 1.111304658212847, "pitch": null, "roll": null}, "v": 1.0221177513423683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615531345432102, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2564743294109896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.2190607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134858169315548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0208951999308473, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.2190607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.86916246364028, "y": 2.6303903854838637, "z": null, "yaw": 1.111304658212847, "pitch": null, "roll": null}, "v": 1.0221177513423683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615531345432102, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2564743294109896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.2390606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134858169315548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.01893043207896, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.2390606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.86916246364028, "y": 2.6303903854838637, "z": null, "yaw": 1.111304658212847, "pitch": null, "roll": null}, "v": 1.0221177513423683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615531345432102, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2564743294109896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.2590606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134858169315548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0182764312962012, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.2590606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.86916246364028, "y": 2.6303903854838637, "z": null, "yaw": 1.111304658212847, "pitch": null, "roll": null}, "v": 1.0221177513423683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615531345432102, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2564743294109896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.2790606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134858169315548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.016317188714354, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.2790606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.86916246364028, "y": 2.6303903854838637, "z": null, "yaw": 1.111304658212847, "pitch": null, "roll": null}, "v": 1.0221177513423683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615531345432102, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2564743294109896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.2990606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134858169315548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0156650264130114, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.2990606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.3090606, "x": 54.91760553420527, "y": 7.731458116057944, "z": null, "yaw": 1.1389063471553962, "pitch": null, "roll": null}, "v": 1.0150133227110392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261053186588361, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2546916546001125, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.3190606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23971670960569363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0143620772009778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.3190606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 50.91760553420527, "y": 2.7314581160579436, "z": null, "yaw": 1.1389063471553962, "pitch": null, "roll": null}, "v": 1.0150133227110392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261053186588361, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2546916546001125, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.3390605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23707667050433848, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0138140049325688, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.3390605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 50.91760553420527, "y": 2.7314581160579436, "z": null, "yaw": 1.1389063471553962, "pitch": null, "roll": null}, "v": 1.0150133227110392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261053186588361, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2546916546001125, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.3590605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23707667050433848, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0135216079529639, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.3590605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 50.91760553420527, "y": 2.7314581160579436, "z": null, "yaw": 1.1389063471553962, "pitch": null, "roll": null}, "v": 1.0150133227110392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261053186588361, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2546916546001125, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.3790605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23707667050433848, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0129374302637897, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.3790605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 50.91760553420527, "y": 2.7314581160579436, "z": null, "yaw": 1.1389063471553962, "pitch": null, "roll": null}, "v": 1.0150133227110392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261053186588361, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2546916546001125, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.3990605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23707667050433848, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0123540731922307, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.3990605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.4190605, "x": 54.962996274365544, "y": 7.833278131538733, "z": null, "yaw": 1.1665080360979454, "pitch": null, "roll": null}, "v": 1.0117715354494585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608253931719305, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25387821093091195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.4190605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385714448099956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0117715354494585, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.4190605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.962996274365544, "y": 2.8332781315387328, "z": null, "yaw": 1.1665080360979454, "pitch": null, "roll": null}, "v": 1.0117715354494585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608253931719305, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25387821093091195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.4390604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380929378549226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0111494289808647, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.4390604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.962996274365544, "y": 2.8332781315387328, "z": null, "yaw": 1.1665080360979454, "pitch": null, "roll": null}, "v": 1.0117715354494585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608253931719305, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25387821093091195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.4590604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380929378549226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.010922420565534, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.4590604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.962996274365544, "y": 2.8332781315387328, "z": null, "yaw": 1.1665080360979454, "pitch": null, "roll": null}, "v": 1.0117715354494585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608253931719305, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25387821093091195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.4790604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380929378549226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0104688818334613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.4790604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.962996274365544, "y": 2.8332781315387328, "z": null, "yaw": 1.1665080360979454, "pitch": null, "roll": null}, "v": 1.0117715354494585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608253931719305, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25387821093091195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.4990604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380929378549226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.010015979751828, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.4990604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.962996274365544, "y": 2.8332781315387328, "z": null, "yaw": 1.1665080360979454, "pitch": null, "roll": null}, "v": 1.0117715354494585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608253931719305, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25387821093091195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.5190604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380929378549226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0093378182150528, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.5190604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.5290604, "x": 55.00544228915263, "y": 7.936028286973913, "z": null, "yaw": 1.1941097250404946, "pitch": null, "roll": null}, "v": 1.0093378182150528, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2606545192235439, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2532675317847466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.5390604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23636901304481056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0087787581939003, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.5390604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 51.00544228915263, "y": 2.9360282869739134, "z": null, "yaw": 1.1941097250404946, "pitch": null, "roll": null}, "v": 1.0093378182150528, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2606545192235439, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2532675317847466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.5590603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368991961981664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0084456686718057, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.5590603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 51.00544228915263, "y": 2.9360282869739134, "z": null, "yaw": 1.1941097250404946, "pitch": null, "roll": null}, "v": 1.0093378182150528, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2606545192235439, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2532675317847466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.5790603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368991961981664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0075471413929082, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.5790603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 51.00544228915263, "y": 2.9360282869739134, "z": null, "yaw": 1.1941097250404946, "pitch": null, "roll": null}, "v": 1.0093378182150528, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2606545192235439, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2532675317847466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.5990603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368991961981664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0069491733326208, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.5990603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 51.00544228915263, "y": 2.9360282869739134, "z": null, "yaw": 1.1941097250404946, "pitch": null, "roll": null}, "v": 1.0093378182150528, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2606545192235439, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2532675317847466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.6190603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368991961981664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0063520438313465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.6190603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.6390603, "x": 55.04492566356124, "y": 8.039619531841296, "z": null, "yaw": 1.2217114139830438, "pitch": null, "roll": null}, "v": 1.0060537931282039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2604241320030867, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2524434896126854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.6390603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24575896312316528, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0063094870033709, "gear": 1, "accelerator_pedal_position": 0.24575896312316528, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.6390603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.04492566356124, "y": 3.0396195318412964, "z": null, "yaw": 1.2217114139830438, "pitch": null, "roll": null}, "v": 1.0060537931282039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2604241320030867, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2524434896126854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.6590602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429787647752402, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0065650015767038, "gear": 1, "accelerator_pedal_position": 0.24575896312316528, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.6590602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.04492566356124, "y": 3.0396195318412964, "z": null, "yaw": 1.2217114139830438, "pitch": null, "roll": null}, "v": 1.0060537931282039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2604241320030867, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2524434896126854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.6790602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429787647752402, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.006809548951183, "gear": 1, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.6790602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.04492566356124, "y": 3.0396195318412964, "z": null, "yaw": 1.2217114139830438, "pitch": null, "roll": null}, "v": 1.0060537931282039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2604241320030867, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2524434896126854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.6990602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429787647752402, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.006890950428374, "gear": 1, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.6990602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.04492566356124, "y": 3.0396195318412964, "z": null, "yaw": 1.2217114139830438, "pitch": null, "roll": null}, "v": 1.0060537931282039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2604241320030867, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2524434896126854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.7190602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429787647752402, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0070535821438007, "gear": 1, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.7190602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.04492566356124, "y": 3.0396195318412964, "z": null, "yaw": 1.2217114139830438, "pitch": null, "roll": null}, "v": 1.0060537931282039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2604241320030867, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2524434896126854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.7390602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429787647752402, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0072971021999748, "gear": 1, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.7390602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.7490602, "x": 55.08149427490017, "y": 8.144147777037587, "z": null, "yaw": 1.249313102925593, "pitch": null, "roll": null}, "v": 1.0072971021999748, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "acceleration": 0.008105950214247704, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25275546625139883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.7590601} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26008852039255403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0073781617021174, "gear": 1, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.7590601} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 51.08149427490017, "y": 3.1441477770375865, "z": null, "yaw": 1.249313102925593, "pitch": null, "roll": null}, "v": 1.0072971021999748, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "acceleration": 0.008105950214247704, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25275546625139883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.7790601} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547460781407612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0104929252155748, "gear": 1, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.7790601} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 51.08149427490017, "y": 3.1441477770375865, "z": null, "yaw": 1.249313102925593, "pitch": null, "roll": null}, "v": 1.0072971021999748, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "acceleration": 0.008105950214247704, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25275546625139883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.79906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547460781407612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0113071990415734, "gear": 1, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.79906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 51.08149427490017, "y": 3.1441477770375865, "z": null, "yaw": 1.249313102925593, "pitch": null, "roll": null}, "v": 1.0072971021999748, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "acceleration": 0.008105950214247704, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25275546625139883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.81906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547460781407612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0129340316621696, "gear": 1, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.81906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 51.08149427490017, "y": 3.1441477770375865, "z": null, "yaw": 1.249313102925593, "pitch": null, "roll": null}, "v": 1.0072971021999748, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "acceleration": 0.008105950214247704, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25275546625139883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.83906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547460781407612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0153699970511274, "gear": 1, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.83906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.85906, "x": 55.11531129458047, "y": 8.250113147973728, "z": null, "yaw": 1.2769147918681423, "pitch": null, "roll": null}, "v": 1.0161808443133082, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "acceleration": 0.08102771108059903, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25498461431010827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.85906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22319619983940017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0161808443133082, "gear": 1, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.85906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.11531129458047, "y": 3.250113147973728, "z": null, "yaw": 1.2769147918681423, "pitch": null, "roll": null}, "v": 1.0161808443133082, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "acceleration": 0.08102771108059903, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25498461431010827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.87906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23308674067672713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0133166816348294, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.87906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.11531129458047, "y": 3.250113147973728, "z": null, "yaw": 1.2769147918681423, "pitch": null, "roll": null}, "v": 1.0161808443133082, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "acceleration": 0.08102771108059903, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25498461431010827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.89906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23308674067672713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0127752635165794, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.89906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.11531129458047, "y": 3.250113147973728, "z": null, "yaw": 1.2769147918681423, "pitch": null, "roll": null}, "v": 1.0161808443133082, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "acceleration": 0.08102771108059903, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25498461431010827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.91906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23308674067672713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.011693568170282, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.91906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.11531129458047, "y": 3.250113147973728, "z": null, "yaw": 1.2769147918681423, "pitch": null, "roll": null}, "v": 1.0161808443133082, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "acceleration": 0.08102771108059903, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25498461431010827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.93906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23308674067672713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0100738724940066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.93906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.11531129458047, "y": 3.250113147973728, "z": null, "yaw": 1.2769147918681423, "pitch": null, "roll": null}, "v": 1.0161808443133082, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "acceleration": 0.08102771108059903, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25498461431010827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.95906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23308674067672713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0095347319272656, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.95906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.96906, "x": 55.146231070215634, "y": 8.35709560614575, "z": null, "yaw": 1.3045164808106915, "pitch": null, "roll": null}, "v": 1.0089959698161006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26063052716185636, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2531817536649886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.97906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23435024279030625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.00799854854801, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.97906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 51.146231070215634, "y": 3.3570956061457498, "z": null, "yaw": 1.3045164808106915, "pitch": null, "roll": null}, "v": 1.0089959698161006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26063052716185636, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2531817536649886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.99906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2339301605975203, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0075398333407428, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.99906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 51.146231070215634, "y": 3.3570956061457498, "z": null, "yaw": 1.3045164808106915, "pitch": null, "roll": null}, "v": 1.0089959698161006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26063052716185636, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2531817536649886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.01906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2339301605975203, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0065708762402554, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.01906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 51.146231070215634, "y": 3.3570956061457498, "z": null, "yaw": 1.3045164808106915, "pitch": null, "roll": null}, "v": 1.0089959698161006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26063052716185636, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2531817536649886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.0390599} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2339301605975203, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0056032778437491, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.0390599} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 51.146231070215634, "y": 3.3570956061457498, "z": null, "yaw": 1.3045164808106915, "pitch": null, "roll": null}, "v": 1.0089959698161006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26063052716185636, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2531817536649886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.0590599} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2339301605975203, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0046370358716363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.0590599} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.0790598, "x": 55.174024943189856, "y": 8.464268986752623, "z": null, "yaw": 1.3321181697532407, "pitch": null, "roll": null}, "v": 1.0036721480490995, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26025718521014995, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25184587664318553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.0790598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23015163993145654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0031902112343432, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.0790598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23015163993145654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0031902112343432, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.0890598} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 51.174024943189856, "y": 3.4642689867526233, "z": null, "yaw": 1.3321181697532407, "pitch": null, "roll": null}, "v": 1.0036721480490995, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26025718521014995, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25184587664318553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.1190598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2313137613039623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0010384492777997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.1190598} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 51.174024943189856, "y": 3.4642689867526233, "z": null, "yaw": 1.3321181697532407, "pitch": null, "roll": null}, "v": 1.0036721480490995, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26025718521014995, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25184587664318553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.1390598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2313137613039623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9991089499293542, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.1390598} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 51.174024943189856, "y": 3.4642689867526233, "z": null, "yaw": 1.3321181697532407, "pitch": null, "roll": null}, "v": 1.0036721480490995, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26025718521014995, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25184587664318553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.1590598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2313137613039623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9984666836665043, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.1590598} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 51.174024943189856, "y": 3.4642689867526233, "z": null, "yaw": 1.3321181697532407, "pitch": null, "roll": null}, "v": 1.0036721480490995, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26025718521014995, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25184587664318553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.1790597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2313137613039623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9971834990359226, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.1790597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.1890597, "x": 55.19869989201104, "y": 8.571512058609247, "z": null, "yaw": 1.35971985869579, "pitch": null, "roll": null}, "v": 0.9965425798748273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25975810012877715, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25005689370644957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.1990597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404724030941957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9959021089550372, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.1990597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 51.19869989201104, "y": 3.5715120586092475, "z": null, "yaw": 1.35971985869579, "pitch": null, "roll": null}, "v": 0.9965425798748273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25975810012877715, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25005689370644957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.2190597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23758537138779365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9957669403004388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.2190597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 51.19869989201104, "y": 3.5715120586092475, "z": null, "yaw": 1.35971985869579, "pitch": null, "roll": null}, "v": 0.9965425798748273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25975810012877715, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25005689370644957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.2390597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23758537138779365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9952712077747223, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.2390597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 51.19869989201104, "y": 3.5715120586092475, "z": null, "yaw": 1.35971985869579, "pitch": null, "roll": null}, "v": 0.9965425798748273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25975810012877715, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25005689370644957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.2590597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23758537138779365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9947761681191689, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.2590597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 51.19869989201104, "y": 3.5715120586092475, "z": null, "yaw": 1.35971985869579, "pitch": null, "roll": null}, "v": 0.9965425798748273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25975810012877715, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25005689370644957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.2790596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23758537138779365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9942818202673837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.2790596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.2990596, "x": 55.22029140892946, "y": 8.678833013924367, "z": null, "yaw": 1.3873215476383391, "pitch": null, "roll": null}, "v": 0.9937881631548727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.259565557290011, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24936574321988286, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.2990596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2415142264615556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9937881631548727, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.2990596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.22029140892946, "y": 3.6788330139243666, "z": null, "yaw": 1.3873215476383391, "pitch": null, "roll": null}, "v": 0.9937881631548727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.259565557290011, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24936574321988286, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.3190596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402768312977672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9937861310269974, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.3190596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.22029140892946, "y": 3.6788330139243666, "z": null, "yaw": 1.3873215476383391, "pitch": null, "roll": null}, "v": 0.9937881631548727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.259565557290011, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24936574321988286, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.3390596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402768312977672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9935512386426892, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.3390596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.22029140892946, "y": 3.6788330139243666, "z": null, "yaw": 1.3873215476383391, "pitch": null, "roll": null}, "v": 0.9937881631548727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.259565557290011, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24936574321988286, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.3590596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402768312977672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9934730505730975, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.3590596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.22029140892946, "y": 3.6788330139243666, "z": null, "yaw": 1.3873215476383391, "pitch": null, "roll": null}, "v": 0.9937881631548727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.259565557290011, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24936574321988286, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.3790596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402768312977672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9932388139879507, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.3790596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.22029140892946, "y": 3.6788330139243666, "z": null, "yaw": 1.3873215476383391, "pitch": null, "roll": null}, "v": 0.9937881631548727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.259565557290011, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24936574321988286, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.3990595} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402768312977672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.993160844202906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.3990595} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.4090595, "x": 55.23888067802692, "y": 8.786525303471445, "z": null, "yaw": 1.4149232365808884, "pitch": null, "roll": null}, "v": 0.9930829288906692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595162834810742, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24918878270359035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.4190595} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2289438110400655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9930050680119689, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.4190595} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 51.23888067802692, "y": 3.7865253034714446, "z": null, "yaw": 1.4149232365808884, "pitch": null, "roll": null}, "v": 0.9930829288906692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595162834810742, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24918878270359035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.4390595} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23248291850057012, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9897430724529601, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.4390595} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 51.23888067802692, "y": 3.7865253034714446, "z": null, "yaw": 1.4149232365808884, "pitch": null, "roll": null}, "v": 0.9930829288906692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595162834810742, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24918878270359035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.4690595} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23248291850057012, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9891804241880724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.4690595} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 51.23888067802692, "y": 3.7865253034714446, "z": null, "yaw": 1.4149232365808884, "pitch": null, "roll": null}, "v": 0.9930829288906692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595162834810742, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24918878270359035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.4890594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23248291850057012, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9874948340521416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.4890594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 51.23888067802692, "y": 3.7865253034714446, "z": null, "yaw": 1.4149232365808884, "pitch": null, "roll": null}, "v": 0.9930829288906692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595162834810742, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24918878270359035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.5090594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23248291850057012, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9874948340521416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.5090594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.5190594, "x": 55.254442419460545, "y": 8.894344725268342, "z": null, "yaw": 1.4425249255234376, "pitch": null, "roll": null}, "v": 0.9869337544366732, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25908707007829834, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24764580451692983, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.5290594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348598701157142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9863730661421758, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.5290594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 51.254442419460545, "y": 3.8943447252683416, "z": null, "yaw": 1.4425249255234376, "pitch": null, "roll": null}, "v": 0.9869337544366732, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25908707007829834, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24764580451692983, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.5490594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23409561156475592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9855498775527615, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.5490594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 51.254442419460545, "y": 3.8943447252683416, "z": null, "yaw": 1.4425249255234376, "pitch": null, "roll": null}, "v": 0.9869337544366732, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25908707007829834, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24764580451692983, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.5690594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23409561156475592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.984632337312244, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.5690594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 51.254442419460545, "y": 3.8943447252683416, "z": null, "yaw": 1.4425249255234376, "pitch": null, "roll": null}, "v": 0.9869337544366732, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25908707007829834, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24764580451692983, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.5890594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23409561156475592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9832584235796266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.5890594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 51.254442419460545, "y": 3.8943447252683416, "z": null, "yaw": 1.4425249255234376, "pitch": null, "roll": null}, "v": 0.9869337544366732, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25908707007829834, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24764580451692983, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.6090593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23409561156475592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.98280109037788, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.6090593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.6290593, "x": 55.266949315596854, "y": 9.001925103129183, "z": null, "yaw": 1.4701266144659868, "pitch": null, "roll": null}, "v": 0.9818873794537647, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25873539723199407, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2463795456754235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.6290593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23797425332799466, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9818873794537647, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.6290593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.266949315596854, "y": 4.001925103129183, "z": null, "yaw": 1.4701266144659868, "pitch": null, "roll": null}, "v": 0.9818873794537647, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25873539723199407, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2463795456754235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.6490593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367445933284394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.981459602169657, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.6490593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.266949315596854, "y": 4.001925103129183, "z": null, "yaw": 1.4701266144659868, "pitch": null, "roll": null}, "v": 0.9818873794537647, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25873539723199407, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2463795456754235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.6690593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367445933284394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9808787664210055, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.6690593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.266949315596854, "y": 4.001925103129183, "z": null, "yaw": 1.4701266144659868, "pitch": null, "roll": null}, "v": 0.9818873794537647, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25873539723199407, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2463795456754235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.6890593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367445933284394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9802987391521008, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.6890593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.266949315596854, "y": 4.001925103129183, "z": null, "yaw": 1.4701266144659868, "pitch": null, "roll": null}, "v": 0.9818873794537647, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25873539723199407, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2463795456754235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.7090592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367445933284394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9797195191030738, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.7090592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.266949315596854, "y": 4.001925103129183, "z": null, "yaw": 1.4701266144659868, "pitch": null, "roll": null}, "v": 0.9818873794537647, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25873539723199407, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2463795456754235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.7290592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367445933284394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9791411050163705, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.7290592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.7390592, "x": 55.27644271424494, "y": 9.10936566186795, "z": null, "yaw": 1.497728303408536, "pitch": null, "roll": null}, "v": 0.9788521998165365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2585241262816836, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24561794490968233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.7490592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23377736813688182, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9785634956367472, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.7490592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 51.27644271424494, "y": 4.109365661867949, "z": null, "yaw": 1.497728303408536, "pitch": null, "roll": null}, "v": 0.9788521998165365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2585241262816836, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24561794490968233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.7690592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23469406306276008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9776159155691951, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.7690592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 51.27644271424494, "y": 4.109365661867949, "z": null, "yaw": 1.497728303408536, "pitch": null, "roll": null}, "v": 0.9788521998165365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2585241262816836, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24561794490968233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.7890592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23469406306276008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9767842002827372, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.7890592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 51.27644271424494, "y": 4.109365661867949, "z": null, "yaw": 1.497728303408536, "pitch": null, "roll": null}, "v": 0.9788521998165365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2585241262816836, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24561794490968233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.8090591} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23469406306276008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9759536413411051, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.8090591} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 51.27644271424494, "y": 4.109365661867949, "z": null, "yaw": 1.497728303408536, "pitch": null, "roll": null}, "v": 0.9788521998165365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2585241262816836, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24561794490968233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.8290591} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23469406306276008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9751242368607819, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.8290591} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.849059, "x": 55.2829426463818, "y": 9.216613497061765, "z": null, "yaw": 1.5253299923510852, "pitch": null, "roll": null}, "v": 0.9742959849620187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2582073259112321, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24447467922632035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.849059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24244693188837935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9742959849620187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.849059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.2829426463818, "y": 4.216613497061765, "z": null, "yaw": 1.5253299923510852, "pitch": null, "roll": null}, "v": 0.9742959849620187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2582073259112321, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24447467922632035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.869059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400083187629714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9744376556916279, "gear": 1, "accelerator_pedal_position": 0.24244693188837935, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.869059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.2829426463818, "y": 4.216613497061765, "z": null, "yaw": 1.5253299923510852, "pitch": null, "roll": null}, "v": 0.9742959849620187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2582073259112321, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24447467922632035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.889059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400083187629714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9742744088704787, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.889059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.2829426463818, "y": 4.216613497061765, "z": null, "yaw": 1.5253299923510852, "pitch": null, "roll": null}, "v": 0.9742959849620187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2582073259112321, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24447467922632035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.909059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400083187629714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9741113888388753, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.909059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.2829426463818, "y": 4.216613497061765, "z": null, "yaw": 1.5253299923510852, "pitch": null, "roll": null}, "v": 0.9742959849620187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2582073259112321, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24447467922632035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.929059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400083187629714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9739485952711253, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.929059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.2829426463818, "y": 4.216613497061765, "z": null, "yaw": 1.5253299923510852, "pitch": null, "roll": null}, "v": 0.9742959849620187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2582073259112321, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24447467922632035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.949059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400083187629714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9737048288279959, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.949059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.959059, "x": 55.28646967912529, "y": 9.32370873086624, "z": null, "yaw": 1.5529316812936345, "pitch": null, "roll": null}, "v": 0.9737048288279959, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581662523782294, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24432634370152237, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.969059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426800379490936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9736236862268993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.969059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 51.28646967912529, "y": 4.32370873086624, "z": null, "yaw": 1.5529316812936345, "pitch": null, "roll": null}, "v": 0.9737048288279959, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581662523782294, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24432634370152237, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.989059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418430714780223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9737954189928657, "gear": 1, "accelerator_pedal_position": 0.2426800379490936, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.989059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 51.28646967912529, "y": 4.32370873086624, "z": null, "yaw": 1.5529316812936345, "pitch": null, "roll": null}, "v": 0.9737048288279959, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581662523782294, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24432634370152237, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.009059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418430714780223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9738623287537442, "gear": 1, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.009059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 51.28646967912529, "y": 4.32370873086624, "z": null, "yaw": 1.5529316812936345, "pitch": null, "roll": null}, "v": 0.9737048288279959, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581662523782294, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24432634370152237, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.029059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418430714780223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9739958695786959, "gear": 1, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.029059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 51.28646967912529, "y": 4.32370873086624, "z": null, "yaw": 1.5529316812936345, "pitch": null, "roll": null}, "v": 0.9737048288279959, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581662523782294, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24432634370152237, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.049059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418430714780223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9739958695786959, "gear": 1, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.049059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.069059, "x": 55.28703928045949, "y": 9.430827216195938, "z": null, "yaw": 1.5805333702361837, "pitch": null, "roll": null}, "v": 0.9740625008972308, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "acceleration": 0.003328094136236137, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2444160923669629, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.069059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2332864199621576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9740625008972308, "gear": 1, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.069059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.28703928045949, "y": 4.430827216195938, "z": null, "yaw": 1.5805333702361837, "pitch": null, "roll": null}, "v": 0.9740625008972308, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "acceleration": 0.003328094136236137, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2444160923669629, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.0890589} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23596161782602043, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.972726216426594, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.0890589} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.28703928045949, "y": 4.430827216195938, "z": null, "yaw": 1.5805333702361837, "pitch": null, "roll": null}, "v": 0.9740625008972308, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "acceleration": 0.003328094136236137, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2444160923669629, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.1090589} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23596161782602043, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9723928348032945, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.1090589} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.28703928045949, "y": 4.430827216195938, "z": null, "yaw": 1.5805333702361837, "pitch": null, "roll": null}, "v": 0.9740625008972308, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "acceleration": 0.003328094136236137, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2444160923669629, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.1290588} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23596161782602043, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9713940784265634, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.1290588} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.28703928045949, "y": 4.430827216195938, "z": null, "yaw": 1.5805333702361837, "pitch": null, "roll": null}, "v": 0.9740625008972308, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "acceleration": 0.003328094136236137, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2444160923669629, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.1490588} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23596161782602043, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9710616218559163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.1490588} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.28703928045949, "y": 4.430827216195938, "z": null, "yaw": 1.5805333702361837, "pitch": null, "roll": null}, "v": 0.9740625008972308, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "acceleration": 0.003328094136236137, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2444160923669629, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.1690588} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23596161782602043, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9703974009518072, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.1690588} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.1790588, "x": 55.28465774264606, "y": 9.537729038449298, "z": null, "yaw": 1.608135059178733, "pitch": null, "roll": null}, "v": 0.9700656362538801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2579135551991005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24341318132486078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.1890588} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23895195609503514, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9689705625407291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.1890588} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 51.28465774264606, "y": 4.537729038449298, "z": null, "yaw": 1.608135059178733, "pitch": null, "roll": null}, "v": 0.9700656362538801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2579135551991005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24341318132486078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.2290587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380035973940605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9687674117014805, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.2290587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 51.28465774264606, "y": 4.537729038449298, "z": null, "yaw": 1.608135059178733, "pitch": null, "roll": null}, "v": 0.9700656362538801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2579135551991005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24341318132486078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.2490587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380035973940605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9685644018029611, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.2490587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 51.28465774264606, "y": 4.537729038449298, "z": null, "yaw": 1.608135059178733, "pitch": null, "roll": null}, "v": 0.9700656362538801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2579135551991005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24341318132486078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.2690587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380035973940605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9681588044040947, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.2690587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.2890587, "x": 55.279343743527996, "y": 9.644176671039832, "z": null, "yaw": 1.6357367481212821, "pitch": null, "roll": null}, "v": 0.9677537694970065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257753162058607, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24283307744213492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.2890587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233267629106883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9677537694970065, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.2890587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.279343743527996, "y": 4.644176671039832, "z": null, "yaw": 1.6357367481212821, "pitch": null, "roll": null}, "v": 0.9677537694970065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257753162058607, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24283307744213492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.3090587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23473960050470094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9667575054690347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.3090587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.279343743527996, "y": 4.644176671039832, "z": null, "yaw": 1.6357367481212821, "pitch": null, "roll": null}, "v": 0.9677537694970065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257753162058607, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24283307744213492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.3290586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23473960050470094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655415017087721, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.3290586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.279343743527996, "y": 4.644176671039832, "z": null, "yaw": 1.6357367481212821, "pitch": null, "roll": null}, "v": 0.9677537694970065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257753162058607, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24283307744213492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.3490586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23473960050470094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651367289503093, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.3490586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.279343743527996, "y": 4.644176671039832, "z": null, "yaw": 1.6357367481212821, "pitch": null, "roll": null}, "v": 0.9677537694970065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257753162058607, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24283307744213492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.3690586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23473960050470094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643280248111434, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.3690586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.279343743527996, "y": 4.644176671039832, "z": null, "yaw": 1.6357367481212821, "pitch": null, "roll": null}, "v": 0.9677537694970065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257753162058607, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24283307744213492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.3890586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23473960050470094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9635204409956917, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.3890586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.3990586, "x": 55.271123333442496, "y": 9.750067208471215, "z": null, "yaw": 1.6633384370638313, "pitch": null, "roll": null}, "v": 0.963117068642716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574317983112452, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24166961585395516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.4090586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24170295107522438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627139756911474, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.4090586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 51.271123333442496, "y": 4.750067208471215, "z": null, "yaw": 1.6633384370638313, "pitch": null, "roll": null}, "v": 0.963117068642716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574317983112452, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24166961585395516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.4290586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23951083439730403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627787445245929, "gear": 1, "accelerator_pedal_position": 0.24170295107522438, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.4290586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 51.271123333442496, "y": 4.750067208471215, "z": null, "yaw": 1.6633384370638313, "pitch": null, "roll": null}, "v": 0.963117068642716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574317983112452, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24166961585395516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.4490585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23951083439730403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9625695039769244, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.4490585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 51.271123333442496, "y": 4.750067208471215, "z": null, "yaw": 1.6633384370638313, "pitch": null, "roll": null}, "v": 0.963117068642716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574317983112452, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24166961585395516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.4690585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23951083439730403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623605531372617, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.4690585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 51.271123333442496, "y": 4.750067208471215, "z": null, "yaw": 1.6633384370638313, "pitch": null, "roll": null}, "v": 0.963117068642716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574317983112452, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24166961585395516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.4890585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23951083439730403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9621518915870257, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.4890585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.5090585, "x": 55.260017776037174, "y": 9.85535862922868, "z": null, "yaw": 1.6909401260063806, "pitch": null, "roll": null}, "v": 0.9619435189082899, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25735052928111113, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24137514353824388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.5090585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23409786908396085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619435189082899, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.5090585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.260017776037174, "y": 4.855358629228681, "z": null, "yaw": 1.6909401260063806, "pitch": null, "roll": null}, "v": 0.9619435189082899, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25735052928111113, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24137514353824388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.5290585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2357853583992781, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9610590482433748, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.5290585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.260017776037174, "y": 4.855358629228681, "z": null, "yaw": 1.6909401260063806, "pitch": null, "roll": null}, "v": 0.9619435189082899, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25735052928111113, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24137514353824388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.5490584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2357853583992781, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603866648813091, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.5490584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.260017776037174, "y": 4.855358629228681, "z": null, "yaw": 1.6909401260063806, "pitch": null, "roll": null}, "v": 0.9619435189082899, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25735052928111113, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24137514353824388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.5690584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2357853583992781, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9597152119249533, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.5690584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.260017776037174, "y": 4.855358629228681, "z": null, "yaw": 1.6909401260063806, "pitch": null, "roll": null}, "v": 0.9619435189082899, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25735052928111113, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24137514353824388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.5890584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2357853583992781, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.959044687906588, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.5890584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.260017776037174, "y": 4.855358629228681, "z": null, "yaw": 1.6909401260063806, "pitch": null, "roll": null}, "v": 0.9619435189082899, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25735052928111113, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24137514353824388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.6090584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2357853583992781, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9583750913612724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.6090584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.6190584, "x": 55.24604701077133, "y": 9.9600360007538, "z": null, "yaw": 1.7185418149489298, "pitch": null, "roll": null}, "v": 0.9580406404339725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25708045070893, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24039581592343776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.6290584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24002731161361224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9577064208268381, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.6290584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 51.24604701077133, "y": 4.960036000753799, "z": null, "yaw": 1.7185418149489298, "pitch": null, "roll": null}, "v": 0.9580406404339725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25708045070893, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24039581592343776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.6490583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23868819642753145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9575687356634941, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.6490583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 51.24604701077133, "y": 4.960036000753799, "z": null, "yaw": 1.7185418149489298, "pitch": null, "roll": null}, "v": 0.9580406404339725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25708045070893, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24039581592343776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.6690583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23868819642753145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.957263909334495, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.6690583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 51.24604701077133, "y": 4.960036000753799, "z": null, "yaw": 1.7185418149489298, "pitch": null, "roll": null}, "v": 0.9580406404339725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25708045070893, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24039581592343776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.6890583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23868819642753145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9569595044150714, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.6890583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 51.24604701077133, "y": 4.960036000753799, "z": null, "yaw": 1.7185418149489298, "pitch": null, "roll": null}, "v": 0.9580406404339725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25708045070893, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24039581592343776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.7090583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23868819642753145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95665552028559, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.7090583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.7290583, "x": 55.22924192706406, "y": 10.063979682483343, "z": null, "yaw": 1.746143503891479, "pitch": null, "roll": null}, "v": 0.956351956327428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25696368846008444, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23997208380133714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.7290583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25404462182484977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9571601083068803, "gear": 1, "accelerator_pedal_position": 0.25404462182484977, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.7290583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 51.22924192706406, "y": 5.0639796824833425, "z": null, "yaw": 1.746143503891479, "pitch": null, "roll": null}, "v": 0.956351956327428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25696368846008444, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23997208380133714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.7490582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24923989762552284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9579677015694865, "gear": 1, "accelerator_pedal_position": 0.25404462182484977, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.7490582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 51.22924192706406, "y": 5.0639796824833425, "z": null, "yaw": 1.746143503891479, "pitch": null, "roll": null}, "v": 0.956351956327428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25696368846008444, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23997208380133714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.7690582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24923989762552284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958980830164187, "gear": 1, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.7690582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 51.22924192706406, "y": 5.0639796824833425, "z": null, "yaw": 1.746143503891479, "pitch": null, "roll": null}, "v": 0.956351956327428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25696368846008444, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23997208380133714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.7890582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24923989762552284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599925575894048, "gear": 1, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.7890582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 51.22924192706406, "y": 5.0639796824833425, "z": null, "yaw": 1.746143503891479, "pitch": null, "roll": null}, "v": 0.956351956327428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25696368846008444, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23997208380133714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.8090582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24923989762552284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9610028853736796, "gear": 1, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.8090582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 51.22924192706406, "y": 5.0639796824833425, "z": null, "yaw": 1.746143503891479, "pitch": null, "roll": null}, "v": 0.956351956327428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25696368846008444, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23997208380133714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.8290582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24923989762552284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620118150451348, "gear": 1, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.8290582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.8390582, "x": 55.20952833422985, "y": 10.167653069880854, "z": null, "yaw": 1.7737451928340282, "pitch": null, "roll": null}, "v": 0.9625157560659787, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "acceleration": 0.05035920654946613, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2415187318294066, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.8490582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23280337845074242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9630193481314734, "gear": 1, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.8490582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 51.20952833422985, "y": 5.1676530698808545, "z": null, "yaw": 1.7737451928340282, "pitch": null, "roll": null}, "v": 0.9625157560659787, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "acceleration": 0.05035920654946613, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2415187318294066, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.8690581} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379611173320368, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619716327607892, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.8690581} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 51.20952833422985, "y": 5.1676530698808545, "z": null, "yaw": 1.7737451928340282, "pitch": null, "roll": null}, "v": 0.9625157560659787, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "acceleration": 0.05035920654946613, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2415187318294066, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.889058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379611173320368, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9615698620460976, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.889058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 51.20952833422985, "y": 5.1676530698808545, "z": null, "yaw": 1.7737451928340282, "pitch": null, "roll": null}, "v": 0.9625157560659787, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "acceleration": 0.05035920654946613, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2415187318294066, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.909058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379611173320368, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9611686474579333, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.909058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 51.20952833422985, "y": 5.1676530698808545, "z": null, "yaw": 1.7737451928340282, "pitch": null, "roll": null}, "v": 0.9625157560659787, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "acceleration": 0.05035920654946613, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2415187318294066, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.929058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379611173320368, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960767988162145, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.929058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.949058, "x": 55.18691021985771, "y": 10.270985132356767, "z": null, "yaw": 1.8013468817765774, "pitch": null, "roll": null}, "v": 0.9603678833260035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25724145887954086, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2409797780543432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.949058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24550161172161106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603678833260035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.949058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 51.18691021985771, "y": 5.270985132356767, "z": null, "yaw": 1.8013468817765774, "pitch": null, "roll": null}, "v": 0.9603678833260035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25724145887954086, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2409797780543432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.969058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313777093848876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9609105677524635, "gear": 1, "accelerator_pedal_position": 0.24550161172161106, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.969058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 51.18691021985771, "y": 5.270985132356767, "z": null, "yaw": 1.8013468817765774, "pitch": null, "roll": null}, "v": 0.9603678833260035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25724145887954086, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2409797780543432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.989058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313777093848876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9611571233664218, "gear": 1, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.989058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 51.18691021985771, "y": 5.270985132356767, "z": null, "yaw": 1.8013468817765774, "pitch": null, "roll": null}, "v": 0.9603678833260035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25724145887954086, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2409797780543432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.009058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313777093848876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614033377575146, "gear": 1, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.009058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 51.18691021985771, "y": 5.270985132356767, "z": null, "yaw": 1.8013468817765774, "pitch": null, "roll": null}, "v": 0.9603678833260035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25724145887954086, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2409797780543432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.029058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313777093848876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616492113737404, "gear": 1, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.029058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 51.18691021985771, "y": 5.270985132356767, "z": null, "yaw": 1.8013468817765774, "pitch": null, "roll": null}, "v": 0.9603678833260035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25724145887954086, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2409797780543432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.049058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313777093848876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618947446625778, "gear": 1, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.049058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.059058, "x": 55.16145889775232, "y": 10.373609210269073, "z": null, "yaw": 1.8289485707191266, "pitch": null, "roll": null}, "v": 0.9620173838239212, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "acceleration": 0.012255424706564433, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24139367805119868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.069058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2346232616272794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9621399380709869, "gear": 1, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.069058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 51.16145889775232, "y": 5.373609210269073, "z": null, "yaw": 1.8289485707191266, "pitch": null, "roll": null}, "v": 0.9620173838239212, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "acceleration": 0.012255424706564433, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24139367805119868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.089058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728975677429526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613208468465071, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.089058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 51.16145889775232, "y": 5.373609210269073, "z": null, "yaw": 1.8289485707191266, "pitch": null, "roll": null}, "v": 0.9620173838239212, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "acceleration": 0.012255424706564433, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24139367805119868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.109058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728975677429526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9608360858858702, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.109058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 51.16145889775232, "y": 5.373609210269073, "z": null, "yaw": 1.8289485707191266, "pitch": null, "roll": null}, "v": 0.9620173838239212, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "acceleration": 0.012255424706564433, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24139367805119868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.129058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728975677429526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960351995787768, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.129058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 51.16145889775232, "y": 5.373609210269073, "z": null, "yaw": 1.8289485707191266, "pitch": null, "roll": null}, "v": 0.9620173838239212, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "acceleration": 0.012255424706564433, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24139367805119868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.1490579} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728975677429526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598685755300862, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.1490579} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.1690578, "x": 55.13319668289231, "y": 10.475453926419348, "z": null, "yaw": 1.8565502596616759, "pitch": null, "roll": null}, "v": 0.9593858240925143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717350279932244, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2407333553862893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.1690578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23511485989956254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9593858240925143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.1690578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 51.13319668289231, "y": 5.475453926419348, "z": null, "yaw": 1.8565502596616759, "pitch": null, "roll": null}, "v": 0.9593858240925143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717350279932244, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2407333553862893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.1890578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578540856957908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958631972386389, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.1890578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 51.13319668289231, "y": 5.475453926419348, "z": null, "yaw": 1.8565502596616759, "pitch": null, "roll": null}, "v": 0.9593858240925143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717350279932244, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2407333553862893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.2090578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578540856957908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9579629528915805, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.2090578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 51.13319668289231, "y": 5.475453926419348, "z": null, "yaw": 1.8565502596616759, "pitch": null, "roll": null}, "v": 0.9593858240925143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717350279932244, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2407333553862893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.2290578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578540856957908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9572948584993742, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.2290578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 51.13319668289231, "y": 5.475453926419348, "z": null, "yaw": 1.8565502596616759, "pitch": null, "roll": null}, "v": 0.9593858240925143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717350279932244, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2407333553862893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.2490578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578540856957908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9566276877520842, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.2490578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 51.13319668289231, "y": 5.475453926419348, "z": null, "yaw": 1.8565502596616759, "pitch": null, "roll": null}, "v": 0.9593858240925143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717350279932244, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2407333553862893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.2690578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578540856957908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9559614391947798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.2690578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.2790577, "x": 55.10223940101324, "y": 10.576139476625483, "z": null, "yaw": 1.884151948604225, "pitch": null, "roll": null}, "v": 0.9556286602834584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569136943777245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2397905911429824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.2890577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24036893444791338, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9552961113752798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.2890577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 51.10223940101324, "y": 5.5761394766254835, "z": null, "yaw": 1.884151948604225, "pitch": null, "roll": null}, "v": 0.9556286602834584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569136943777245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2397905911429824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.3090577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23892359124221316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9552044456217816, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.3090577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 51.10223940101324, "y": 5.5761394766254835, "z": null, "yaw": 1.884151948604225, "pitch": null, "roll": null}, "v": 0.9556286602834584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569136943777245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2397905911429824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.3290577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23892359124221316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9549323010370149, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.3290577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 51.10223940101324, "y": 5.5761394766254835, "z": null, "yaw": 1.884151948604225, "pitch": null, "roll": null}, "v": 0.9556286602834584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569136943777245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2397905911429824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.3490577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23892359124221316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9546605324261596, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.3490577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 51.10223940101324, "y": 5.5761394766254835, "z": null, "yaw": 1.884151948604225, "pitch": null, "roll": null}, "v": 0.9556286602834584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569136943777245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2397905911429824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.3690577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23892359124221316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9543891392402662, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.3690577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.3890576, "x": 55.068610827096464, "y": 10.675647443335077, "z": null, "yaw": 1.9117536375467743, "pitch": null, "roll": null}, "v": 0.954118120931266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568093199334574, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2394115598944852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.3890576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517867781166175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.954118120931266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.3890576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 51.068610827096464, "y": 5.675647443335077, "z": null, "yaw": 1.9117536375467743, "pitch": null, "roll": null}, "v": 0.954118120931266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568093199334574, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2394115598944852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.4090576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321874325146248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9546290926958527, "gear": 1, "accelerator_pedal_position": 0.24517867781166175, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.4090576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 51.068610827096464, "y": 5.675647443335077, "z": null, "yaw": 1.9117536375467743, "pitch": null, "roll": null}, "v": 0.954118120931266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568093199334574, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2394115598944852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.4290576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321874325146248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9548944514636113, "gear": 1, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.4290576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 51.068610827096464, "y": 5.675647443335077, "z": null, "yaw": 1.9117536375467743, "pitch": null, "roll": null}, "v": 0.954118120931266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568093199334574, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2394115598944852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.4490576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321874325146248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9551594436504911, "gear": 1, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.4490576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 51.068610827096464, "y": 5.675647443335077, "z": null, "yaw": 1.9117536375467743, "pitch": null, "roll": null}, "v": 0.954118120931266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568093199334574, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2394115598944852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.4690576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321874325146248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9554240697348282, "gear": 1, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.4690576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 51.068610827096464, "y": 5.675647443335077, "z": null, "yaw": 1.9117536375467743, "pitch": null, "roll": null}, "v": 0.954118120931266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568093199334574, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2394115598944852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.4890575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321874325146248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.955688330194414, "gear": 1, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.4890575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.4990575, "x": 55.03224492590729, "y": 10.774197782836119, "z": null, "yaw": 1.9393553264893235, "pitch": null, "roll": null}, "v": 0.9558203234640862, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "acceleration": 0.01319020424096623, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983868412019538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.5090575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590354657561024, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9559522255064958, "gear": 1, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.5090575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 51.03224492590729, "y": 5.774197782836119, "z": null, "yaw": 1.9393553264893235, "pitch": null, "roll": null}, "v": 0.9558203234640862, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "acceleration": 0.01319020424096623, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983868412019538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.5290575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540986177939135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9581921630641083, "gear": 1, "accelerator_pedal_position": 0.2590354657561024, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.5290575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 51.03224492590729, "y": 5.774197782836119, "z": null, "yaw": 1.9393553264893235, "pitch": null, "roll": null}, "v": 0.9558203234640862, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "acceleration": 0.01319020424096623, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983868412019538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.5490575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540986177939135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598121112123408, "gear": 1, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.5490575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 51.03224492590729, "y": 5.774197782836119, "z": null, "yaw": 1.9393553264893235, "pitch": null, "roll": null}, "v": 0.9558203234640862, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "acceleration": 0.01319020424096623, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983868412019538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.5690575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540986177939135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614298185120671, "gear": 1, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.5690575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 51.03224492590729, "y": 5.774197782836119, "z": null, "yaw": 1.9393553264893235, "pitch": null, "roll": null}, "v": 0.9558203234640862, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "acceleration": 0.01319020424096623, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983868412019538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.5890574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540986177939135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9630452870165885, "gear": 1, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.5890574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.6090574, "x": 54.99297746932043, "y": 10.872189979938453, "z": null, "yaw": 1.9669570154318727, "pitch": null, "roll": null}, "v": 0.964658518780709, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "acceleration": 0.08057777469436206, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205640337422182, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.6090574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.231504574436293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964658518780709, "gear": 1, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.6090574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.99297746932043, "y": 5.872189979938453, "z": null, "yaw": 1.9669570154318727, "pitch": null, "roll": null}, "v": 0.964658518780709, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "acceleration": 0.08057777469436206, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205640337422182, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.6290574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385957999067653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963121734422241, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.6290574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.99297746932043, "y": 5.872189979938453, "z": null, "yaw": 1.9669570154318727, "pitch": null, "roll": null}, "v": 0.964658518780709, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "acceleration": 0.08057777469436206, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205640337422182, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.6490574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385957999067653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9629596507016711, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.6490574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.99297746932043, "y": 5.872189979938453, "z": null, "yaw": 1.9669570154318727, "pitch": null, "roll": null}, "v": 0.964658518780709, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "acceleration": 0.08057777469436206, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205640337422182, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.6690574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385957999067653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627976792416052, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.6690574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.99297746932043, "y": 5.872189979938453, "z": null, "yaw": 1.9669570154318727, "pitch": null, "roll": null}, "v": 0.964658518780709, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "acceleration": 0.08057777469436206, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205640337422182, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.6890574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385957999067653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9621509143473805, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.6890574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.99297746932043, "y": 5.872189979938453, "z": null, "yaw": 1.9669570154318727, "pitch": null, "roll": null}, "v": 0.964658518780709, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "acceleration": 0.08057777469436206, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205640337422182, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.7090573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385957999067653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618282033085036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.7090573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.7190573, "x": 54.95087677224477, "y": 10.969400482561571, "z": null, "yaw": 1.994558704374422, "pitch": null, "roll": null}, "v": 0.9619895029461817, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573537131850955, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24138668205742767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.7390573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2338595657836149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612099243607127, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.7390573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 50.95087677224477, "y": 5.969400482561571, "z": null, "yaw": 1.994558704374422, "pitch": null, "roll": null}, "v": 0.9619895029461817, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573537131850955, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24138668205742767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.7590573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23533039624482588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9607531498081393, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.7590573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 50.95087677224477, "y": 5.969400482561571, "z": null, "yaw": 1.994558704374422, "pitch": null, "roll": null}, "v": 0.9619895029461817, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573537131850955, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24138668205742767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.7790573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23533039624482588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9600243391633602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.7790573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 50.95087677224477, "y": 5.969400482561571, "z": null, "yaw": 1.994558704374422, "pitch": null, "roll": null}, "v": 0.9619895029461817, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573537131850955, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24138668205742767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.7990572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23533039624482588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9592965369037009, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.7990572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 50.95087677224477, "y": 5.969400482561571, "z": null, "yaw": 1.994558704374422, "pitch": null, "roll": null}, "v": 0.9619895029461817, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573537131850955, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24138668205742767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.8190572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23533039624482588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9585697414221509, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.8190572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23533039624482588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9571191643808388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.8290572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.8290572, "x": 54.90623460202116, "y": 11.065144205310764, "z": null, "yaw": 2.022160393316969, "pitch": null, "roll": null}, "v": 0.9582067207218244, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25709193723245594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2404374895274812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.8590572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417162430731421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9571191643808388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.8590572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 50.90623460202116, "y": 6.065144205310764, "z": null, "yaw": 2.022160393316969, "pitch": null, "roll": null}, "v": 0.9582067207218244, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25709193723245594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2404374895274812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.8790572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23970757582467642, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.957016405546886, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.8790572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 50.90623460202116, "y": 6.065144205310764, "z": null, "yaw": 2.022160393316969, "pitch": null, "roll": null}, "v": 0.9582067207218244, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25709193723245594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2404374895274812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.8990571} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23970757582467642, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9569280327931063, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.8990571} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 50.90623460202116, "y": 6.065144205310764, "z": null, "yaw": 2.022160393316969, "pitch": null, "roll": null}, "v": 0.9582067207218244, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25709193723245594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2404374895274812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.9190571} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23970757582467642, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9568397211397576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.9190571} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.939057, "x": 54.85912165671652, "y": 11.15930899112701, "z": null, "yaw": 2.049762082259516, "pitch": null, "roll": null}, "v": 0.956663280959167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25698521037931393, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24005020276175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.939057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23438921664018705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.956663280959167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.939057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 50.85912165671652, "y": 6.159308991127009, "z": null, "yaw": 2.049762082259516, "pitch": null, "roll": null}, "v": 0.956663280959167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25698521037931393, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24005020276175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.959057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23604586862886856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9558225195373206, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.959057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 50.85912165671652, "y": 6.159308991127009, "z": null, "yaw": 2.049762082259516, "pitch": null, "roll": null}, "v": 0.956663280959167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25698521037931393, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24005020276175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.979057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23604586862886856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9539273714403664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.979057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 50.85912165671652, "y": 6.159308991127009, "z": null, "yaw": 2.049762082259516, "pitch": null, "roll": null}, "v": 0.956663280959167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25698521037931393, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24005020276175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.019057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23604586862886856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9536122768009522, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.019057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 50.85912165671652, "y": 6.159308991127009, "z": null, "yaw": 2.049762082259516, "pitch": null, "roll": null}, "v": 0.956663280959167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25698521037931393, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24005020276175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.039057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23604586862886856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9526682981193733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.039057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.049057, "x": 54.80954970058305, "y": 11.25191133823656, "z": null, "yaw": 2.0773637712020627, "pitch": null, "roll": null}, "v": 0.9529827403105572, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567308980488261, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.239126665142447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.059057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2422452397966766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9526682981193733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.059057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 50.80954970058305, "y": 6.25191133823656, "z": null, "yaw": 2.0773637712020627, "pitch": null, "roll": null}, "v": 0.9529827403105572, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567308980488261, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.239126665142447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.079057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402952194116792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9528878533853967, "gear": 1, "accelerator_pedal_position": 0.2422452397966766, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.079057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 50.80954970058305, "y": 6.25191133823656, "z": null, "yaw": 2.0773637712020627, "pitch": null, "roll": null}, "v": 0.9529827403105572, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567308980488261, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.239126665142447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.099057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402952194116792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9528390611458211, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.099057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 50.80954970058305, "y": 6.25191133823656, "z": null, "yaw": 2.0773637712020627, "pitch": null, "roll": null}, "v": 0.9529827403105572, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567308980488261, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.239126665142447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.119057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402952194116792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95274157772669, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.119057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 50.80954970058305, "y": 6.25191133823656, "z": null, "yaw": 2.0773637712020627, "pitch": null, "roll": null}, "v": 0.9529827403105572, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567308980488261, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.239126665142447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.139057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402952194116792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95254701446428, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.139057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.159057, "x": 54.75755700338367, "y": 11.342905534800188, "z": null, "yaw": 2.1049654601446095, "pitch": null, "roll": null}, "v": 0.95254701446428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567008088708621, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23901733087632726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.159057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24187893620002393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95254701446428, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.159057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 50.75755700338367, "y": 6.342905534800188, "z": null, "yaw": 2.1049654601446095, "pitch": null, "roll": null}, "v": 0.95254701446428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567008088708621, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23901733087632726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.179057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138251991929213, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9527057798304825, "gear": 1, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.179057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 50.75755700338367, "y": 6.342905534800188, "z": null, "yaw": 2.1049654601446095, "pitch": null, "roll": null}, "v": 0.95254701446428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567008088708621, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23901733087632726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.2090569} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138251991929213, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9527057798304825, "gear": 1, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.2090569} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 50.75755700338367, "y": 6.342905534800188, "z": null, "yaw": 2.1049654601446095, "pitch": null, "roll": null}, "v": 0.95254701446428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567008088708621, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23901733087632726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.2290568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138251991929213, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9527636092025897, "gear": 1, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.2290568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 50.75755700338367, "y": 6.342905534800188, "z": null, "yaw": 2.1049654601446095, "pitch": null, "roll": null}, "v": 0.95254701446428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567008088708621, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23901733087632726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.2490568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138251991929213, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9528020955912275, "gear": 1, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.2490568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.2690568, "x": 54.703076519506574, "y": 11.432423874158975, "z": null, "yaw": 2.1325671490871563, "pitch": null, "roll": null}, "v": 0.9528213188550514, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "acceleration": 0.0019209988961763624, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23908616055332405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.2690568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23711395599300314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9528405288440132, "gear": 1, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.2690568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 50.703076519506574, "y": 6.4324238741589745, "z": null, "yaw": 2.1325671490871563, "pitch": null, "roll": null}, "v": 0.9528213188550514, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "acceleration": 0.0019209988961763624, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23908616055332405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.2890568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23844883018160704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9523455227702198, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.2890568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 50.703076519506574, "y": 6.4324238741589745, "z": null, "yaw": 2.1325671490871563, "pitch": null, "roll": null}, "v": 0.9528213188550514, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "acceleration": 0.0019209988961763624, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23908616055332405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.3090568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23844883018160704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.952181705695711, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.3090568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 50.703076519506574, "y": 6.4324238741589745, "z": null, "yaw": 2.1325671490871563, "pitch": null, "roll": null}, "v": 0.9528213188550514, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "acceleration": 0.0019209988961763624, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23908616055332405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.3290567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23844883018160704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9516909327860951, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.3290567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 50.703076519506574, "y": 6.4324238741589745, "z": null, "yaw": 2.1325671490871563, "pitch": null, "roll": null}, "v": 0.9528213188550514, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "acceleration": 0.0019209988961763624, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23908616055332405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.3490567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23844883018160704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9515275676428977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.3490567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 50.703076519506574, "y": 6.4324238741589745, "z": null, "yaw": 2.1325671490871563, "pitch": null, "roll": null}, "v": 0.9528213188550514, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "acceleration": 0.0019209988961763624, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23908616055332405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.3690567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23844883018160704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9512011755969039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.3690567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.3790567, "x": 54.64618597792596, "y": 11.5203441358152, "z": null, "yaw": 2.160168838029703, "pitch": null, "roll": null}, "v": 0.9510381485278102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25659664302594254, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23863871952874136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.3890567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2434090894178821, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9507124318821993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.3890567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 50.64618597792596, "y": 6.520344135815201, "z": null, "yaw": 2.160168838029703, "pitch": null, "roll": null}, "v": 0.9510381485278102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25659664302594254, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23863871952874136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.4090567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24185285200752454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9508597583420624, "gear": 1, "accelerator_pedal_position": 0.2434090894178821, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.4090567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 50.64618597792596, "y": 6.520344135815201, "z": null, "yaw": 2.160168838029703, "pitch": null, "roll": null}, "v": 0.9510381485278102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25659664302594254, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23863871952874136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.4290566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24185285200752454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9510095347516458, "gear": 1, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.4290566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 50.64618597792596, "y": 6.520344135815201, "z": null, "yaw": 2.160168838029703, "pitch": null, "roll": null}, "v": 0.9510381485278102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25659664302594254, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23863871952874136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.4490566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24185285200752454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9510593913212214, "gear": 1, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.4490566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 50.64618597792596, "y": 6.520344135815201, "z": null, "yaw": 2.160168838029703, "pitch": null, "roll": null}, "v": 0.9510381485278102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25659664302594254, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23863871952874136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.4690566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24185285200752454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9511590012495831, "gear": 1, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.4690566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.4890566, "x": 54.586955527586525, "y": 11.606565417077631, "z": null, "yaw": 2.18777052697225, "pitch": null, "roll": null}, "v": 0.9512584737185125, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "acceleration": 0.004968474522889954, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23869400450492292, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.4890566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23507388227415385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9513081584637414, "gear": 1, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.4890566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.586955527586525, "y": 6.606565417077631, "z": null, "yaw": 2.18777052697225, "pitch": null, "roll": null}, "v": 0.9512584737185125, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "acceleration": 0.004968474522889954, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23869400450492292, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.5090566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719307208019108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9505603463152034, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.5090566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.586955527586525, "y": 6.606565417077631, "z": null, "yaw": 2.18777052697225, "pitch": null, "roll": null}, "v": 0.9512584737185125, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "acceleration": 0.004968474522889954, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23869400450492292, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.5290565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719307208019108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9500783733437889, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.5290565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.586955527586525, "y": 6.606565417077631, "z": null, "yaw": 2.18777052697225, "pitch": null, "roll": null}, "v": 0.9512584737185125, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "acceleration": 0.004968474522889954, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23869400450492292, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.5490565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719307208019108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9498376362705794, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.5490565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.586955527586525, "y": 6.606565417077631, "z": null, "yaw": 2.18777052697225, "pitch": null, "roll": null}, "v": 0.9512584737185125, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "acceleration": 0.004968474522889954, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23869400450492292, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.5690565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719307208019108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9491164211856492, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.5690565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.586955527586525, "y": 6.606565417077631, "z": null, "yaw": 2.18777052697225, "pitch": null, "roll": null}, "v": 0.9512584737185125, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "acceleration": 0.004968474522889954, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23869400450492292, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.5890565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719307208019108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9486364399807549, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.5890565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.5990565, "x": 54.5254255862397, "y": 11.69104160526827, "z": null, "yaw": 2.2153722159147966, "pitch": null, "roll": null}, "v": 0.9486364399807549, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25643093295163133, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23803607214468242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.6090565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24272920320561145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9481571206828218, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.6090565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 50.5254255862397, "y": 6.6910416052682695, "z": null, "yaw": 2.2153722159147966, "pitch": null, "roll": null}, "v": 0.9486364399807549, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25643093295163133, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23803607214468242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.6290565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2409901152100573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9482637171302809, "gear": 1, "accelerator_pedal_position": 0.24272920320561145, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.6290565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 50.5254255862397, "y": 6.6910416052682695, "z": null, "yaw": 2.2153722159147966, "pitch": null, "roll": null}, "v": 0.9486364399807549, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25643093295163133, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23803607214468242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.6490564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2409901152100573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9482572114220442, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.6490564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 50.5254255862397, "y": 6.6910416052682695, "z": null, "yaw": 2.2153722159147966, "pitch": null, "roll": null}, "v": 0.9486364399807549, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25643093295163133, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23803607214468242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.6690564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2409901152100573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9482528817575708, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.6690564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 50.5254255862397, "y": 6.6910416052682695, "z": null, "yaw": 2.2153722159147966, "pitch": null, "roll": null}, "v": 0.9486364399807549, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25643093295163133, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23803607214468242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.6890564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2409901152100573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9482485580629512, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.6890564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.7090564, "x": 54.46170937077643, "y": 11.773628735777631, "z": null, "yaw": 2.2429739048573434, "pitch": null, "roll": null}, "v": 0.9482463984517614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564040322443555, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23793820119051923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.7090564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24564679386461996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9482442403299465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.7090564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 50.46170937077643, "y": 6.773628735777631, "z": null, "yaw": 2.2429739048573434, "pitch": null, "roll": null}, "v": 0.9482463984517614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564040322443555, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23793820119051923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.7290564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419023579471144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9488218126567377, "gear": 1, "accelerator_pedal_position": 0.24564679386461996, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.7290564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 50.46170937077643, "y": 6.773628735777631, "z": null, "yaw": 2.2429739048573434, "pitch": null, "roll": null}, "v": 0.9482463984517614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564040322443555, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23793820119051923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.7490563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419023579471144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9490192652043615, "gear": 1, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.7490563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 50.46170937077643, "y": 6.773628735777631, "z": null, "yaw": 2.2429739048573434, "pitch": null, "roll": null}, "v": 0.9482463984517614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564040322443555, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23793820119051923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.7690563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419023579471144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9496108059940488, "gear": 1, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.7690563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 50.46170937077643, "y": 6.773628735777631, "z": null, "yaw": 2.2429739048573434, "pitch": null, "roll": null}, "v": 0.9482463984517614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564040322443555, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23793820119051923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.7890563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419023579471144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9500044866705679, "gear": 1, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.7890563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 50.46170937077643, "y": 6.773628735777631, "z": null, "yaw": 2.2429739048573434, "pitch": null, "roll": null}, "v": 0.9482463984517614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564040322443555, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23793820119051923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.8090563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419023579471144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9503976242699718, "gear": 1, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.8090563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.8190563, "x": 54.3956752016473, "y": 11.854502089755112, "z": null, "yaw": 2.27057559379989, "pitch": null, "roll": null}, "v": 0.9503976242699718, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "acceleration": 0.01963653606126775, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23847799633487762, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.8290563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367765858357609, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9507902194796264, "gear": 1, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.8290563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 50.3956752016473, "y": 6.854502089755112, "z": null, "yaw": 2.27057559379989, "pitch": null, "roll": null}, "v": 0.9503976242699718, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "acceleration": 0.01963653606126775, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23847799633487762, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.8490562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23910077324235512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9505229607804758, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.8490562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 50.3956752016473, "y": 6.854502089755112, "z": null, "yaw": 2.27057559379989, "pitch": null, "roll": null}, "v": 0.9503976242699718, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "acceleration": 0.01963653606126775, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23847799633487762, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.8690562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23910077324235512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.950157775277314, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.8690562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 50.3956752016473, "y": 6.854502089755112, "z": null, "yaw": 2.27057559379989, "pitch": null, "roll": null}, "v": 0.9503976242699718, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "acceleration": 0.01963653606126775, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23847799633487762, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.8890562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23910077324235512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9499147380768778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.8890562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 50.3956752016473, "y": 6.854502089755112, "z": null, "yaw": 2.27057559379989, "pitch": null, "roll": null}, "v": 0.9503976242699718, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "acceleration": 0.01963653606126775, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23847799633487762, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.9090562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23910077324235512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9496720361496898, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.9090562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.9290562, "x": 54.327360089310055, "y": 11.9336093431591, "z": null, "yaw": 2.298177282742437, "pitch": null, "roll": null}, "v": 0.9495508107616376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564940079602627, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23826551012533773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.9290562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24164728048732473, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9494296690096822, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.9290562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 50.327360089310055, "y": 6.9336093431591, "z": null, "yaw": 2.298177282742437, "pitch": null, "roll": null}, "v": 0.9495508107616376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564940079602627, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23826551012533773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.9490561} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24084857496482878, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9495058397785264, "gear": 1, "accelerator_pedal_position": 0.24164728048732473, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.9490561} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 50.327360089310055, "y": 6.9336093431591, "z": null, "yaw": 2.298177282742437, "pitch": null, "roll": null}, "v": 0.9495508107616376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564940079602627, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23826551012533773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.9690561} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24084857496482878, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9494702449909456, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.9690561} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 50.327360089310055, "y": 6.9336093431591, "z": null, "yaw": 2.298177282742437, "pitch": null, "roll": null}, "v": 0.9495508107616376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564940079602627, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23826551012533773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.989056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24084857496482878, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9494347238225749, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.989056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 50.327360089310055, "y": 6.9336093431591, "z": null, "yaw": 2.298177282742437, "pitch": null, "roll": null}, "v": 0.9495508107616376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564940079602627, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23826551012533773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.019056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24084857496482878, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9494347238225749, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.019056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.039056, "x": 54.256944209287575, "y": 12.01073891650125, "z": null, "yaw": 2.3257789716849837, "pitch": null, "roll": null}, "v": 0.9494110838676438, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564843682550896, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23823044923202025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.049056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23767430071148346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9493992761203948, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.049056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 50.256944209287575, "y": 7.01073891650125, "z": null, "yaw": 2.3257789716849837, "pitch": null, "roll": null}, "v": 0.9494110838676438, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564843682550896, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23823044923202025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.069056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23866578008045974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9489790376387408, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.069056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 50.256944209287575, "y": 7.01073891650125, "z": null, "yaw": 2.3257789716849837, "pitch": null, "roll": null}, "v": 0.9494110838676438, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564843682550896, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23823044923202025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.089056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23866578008045974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.948535540535437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.089056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 50.256944209287575, "y": 7.01073891650125, "z": null, "yaw": 2.3257789716849837, "pitch": null, "roll": null}, "v": 0.9494110838676438, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564843682550896, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23823044923202025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.109056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23866578008045974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9483879120530321, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.109056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 50.256944209287575, "y": 7.01073891650125, "z": null, "yaw": 2.3257789716849837, "pitch": null, "roll": null}, "v": 0.9494110838676438, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564843682550896, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23823044923202025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.129056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23866578008045974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9480929604683476, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.129056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.149056, "x": 54.184485599229745, "y": 12.085835106639463, "z": null, "yaw": 2.3533806606275305, "pitch": null, "roll": null}, "v": 0.9477984155602814, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2563731391433999, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23782579133213547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.149056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24596371201176898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9477984155602814, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.149056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 50.184485599229745, "y": 7.085835106639463, "z": null, "yaw": 2.3533806606275305, "pitch": null, "roll": null}, "v": 0.9477984155602814, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2563731391433999, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23782579133213547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.169056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367754532872266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9484162036949743, "gear": 1, "accelerator_pedal_position": 0.24596371201176898, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.169056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 50.184485599229745, "y": 7.085835106639463, "z": null, "yaw": 2.3533806606275305, "pitch": null, "roll": null}, "v": 0.9477984155602814, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2563731391433999, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23782579133213547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.189056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367754532872266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9487474677225071, "gear": 1, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.189056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 50.184485599229745, "y": 7.085835106639463, "z": null, "yaw": 2.3533806606275305, "pitch": null, "roll": null}, "v": 0.9477984155602814, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2563731391433999, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23782579133213547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.209056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367754532872266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9490782749402195, "gear": 1, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.209056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 50.184485599229745, "y": 7.085835106639463, "z": null, "yaw": 2.3533806606275305, "pitch": null, "roll": null}, "v": 0.9477984155602814, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2563731391433999, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23782579133213547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.229056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367754532872266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9494086259342895, "gear": 1, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.229056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 50.184485599229745, "y": 7.085835106639463, "z": null, "yaw": 2.3533806606275305, "pitch": null, "roll": null}, "v": 0.9477984155602814, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2563731391433999, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23782579133213547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.2490559} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367754532872266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9497385212902678, "gear": 1, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.2490559} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.2590559, "x": 54.109967771378855, "y": 12.158915686747338, "z": null, "yaw": 2.3809823495700773, "pitch": null, "roll": null}, "v": 0.9499032982867855, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "acceleration": 0.016466330629216097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.238353957861931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.2690558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2453367610916796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9500679615930777, "gear": 1, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.2690558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 50.109967771378855, "y": 7.1589156867473385, "z": null, "yaw": 2.3809823495700773, "pitch": null, "roll": null}, "v": 0.9499032982867855, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "acceleration": 0.016466330629216097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.238353957861931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.2890558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24482551525715168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9506042778378082, "gear": 1, "accelerator_pedal_position": 0.2453367610916796, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.2890558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 50.109967771378855, "y": 7.1589156867473385, "z": null, "yaw": 2.3809823495700773, "pitch": null, "roll": null}, "v": 0.9499032982867855, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "acceleration": 0.016466330629216097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.238353957861931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.3090558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24482551525715168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9510759704443027, "gear": 1, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.3090558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 50.109967771378855, "y": 7.1589156867473385, "z": null, "yaw": 2.3809823495700773, "pitch": null, "roll": null}, "v": 0.9499032982867855, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "acceleration": 0.016466330629216097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.238353957861931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.3290558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24482551525715168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.951547012158944, "gear": 1, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.3290558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 50.109967771378855, "y": 7.1589156867473385, "z": null, "yaw": 2.3809823495700773, "pitch": null, "roll": null}, "v": 0.9499032982867855, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "acceleration": 0.016466330629216097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.238353957861931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.3490558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24482551525715168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9520174037911807, "gear": 1, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.3490558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.3690557, "x": 54.03328445190242, "y": 12.230075905866313, "z": null, "yaw": 2.408584038512624, "pitch": null, "roll": null}, "v": 0.9524871461497115, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "acceleration": 0.023462795413908166, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900230845272513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.3690557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2398109364950726, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9524871461497115, "gear": 1, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.3690557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 50.03328445190242, "y": 7.230075905866313, "z": null, "yaw": 2.408584038512624, "pitch": null, "roll": null}, "v": 0.9524871461497115, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "acceleration": 0.023462795413908166, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900230845272513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.3890557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138691075491103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.952329634111719, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.3890557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 50.03328445190242, "y": 7.230075905866313, "z": null, "yaw": 2.408584038512624, "pitch": null, "roll": null}, "v": 0.9524871461497115, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "acceleration": 0.023462795413908166, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900230845272513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.4090557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138691075491103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9523692682877809, "gear": 1, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.4090557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 50.03328445190242, "y": 7.230075905866313, "z": null, "yaw": 2.408584038512624, "pitch": null, "roll": null}, "v": 0.9524871461497115, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "acceleration": 0.023462795413908166, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900230845272513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.4290557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138691075491103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.952408847750171, "gear": 1, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.4290557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 50.03328445190242, "y": 7.230075905866313, "z": null, "yaw": 2.408584038512624, "pitch": null, "roll": null}, "v": 0.9524871461497115, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "acceleration": 0.023462795413908166, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900230845272513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.4490557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138691075491103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9524483725737933, "gear": 1, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.4490557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 50.03328445190242, "y": 7.230075905866313, "z": null, "yaw": 2.408584038512624, "pitch": null, "roll": null}, "v": 0.9524871461497115, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "acceleration": 0.023462795413908166, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900230845272513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.4690557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138691075491103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9524878428334511, "gear": 1, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.4690557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.4790556, "x": 53.95455537928009, "y": 12.299191055068736, "z": null, "yaw": 2.436185727455171, "pitch": null, "roll": null}, "v": 0.9525075575251418, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "acceleration": 0.0019701078705116615, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900743016577528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.4890556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24418146324110607, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9525272586038469, "gear": 1, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.4890556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 49.95455537928009, "y": 7.299191055068736, "z": null, "yaw": 2.436185727455171, "pitch": null, "roll": null}, "v": 0.9525075575251418, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "acceleration": 0.0019701078705116615, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900743016577528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.5090556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243308235486857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9529158184132608, "gear": 1, "accelerator_pedal_position": 0.24418146324110607, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.5090556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 49.95455537928009, "y": 7.299191055068736, "z": null, "yaw": 2.436185727455171, "pitch": null, "roll": null}, "v": 0.9525075575251418, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "acceleration": 0.0019701078705116615, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900743016577528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.5290556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243308235486857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.953194725979662, "gear": 1, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.5290556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 49.95455537928009, "y": 7.299191055068736, "z": null, "yaw": 2.436185727455171, "pitch": null, "roll": null}, "v": 0.9525075575251418, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "acceleration": 0.0019701078705116615, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900743016577528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.5490556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243308235486857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9534732484380186, "gear": 1, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.5490556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 49.95455537928009, "y": 7.299191055068736, "z": null, "yaw": 2.436185727455171, "pitch": null, "roll": null}, "v": 0.9525075575251418, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "acceleration": 0.0019701078705116615, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900743016577528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.5690556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243308235486857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9537513862890581, "gear": 1, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.5690556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.5890555, "x": 53.87388390242983, "y": 12.366160517051526, "z": null, "yaw": 2.4637874163977176, "pitch": null, "roll": null}, "v": 0.9540291400329449, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "acceleration": 0.013873298790889, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2393892324119644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.5890555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23643410889212568, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9540291400329449, "gear": 1, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.5890555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.87388390242983, "y": 7.366160517051526, "z": null, "yaw": 2.4637874163977176, "pitch": null, "roll": null}, "v": 0.9540291400329449, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "acceleration": 0.013873298790889, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2393892324119644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.6090555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23858752929758592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9534475411313221, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.6090555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.87388390242983, "y": 7.366160517051526, "z": null, "yaw": 2.4637874163977176, "pitch": null, "roll": null}, "v": 0.9540291400329449, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "acceleration": 0.013873298790889, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2393892324119644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.6290555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23858752929758592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9531358299922147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.6290555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.87388390242983, "y": 7.366160517051526, "z": null, "yaw": 2.4637874163977176, "pitch": null, "roll": null}, "v": 0.9540291400329449, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "acceleration": 0.013873298790889, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2393892324119644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.6490555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23858752929758592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.952824549266506, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.6490555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.87388390242983, "y": 7.366160517051526, "z": null, "yaw": 2.4637874163977176, "pitch": null, "roll": null}, "v": 0.9540291400329449, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "acceleration": 0.013873298790889, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2393892324119644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.6690555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23858752929758592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9525136983211325, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.6690555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.87388390242983, "y": 7.366160517051526, "z": null, "yaw": 2.4637874163977176, "pitch": null, "roll": null}, "v": 0.9540291400329449, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "acceleration": 0.013873298790889, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2393892324119644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.6890554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23858752929758592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9522032765240654, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.6890554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.6990554, "x": 53.791409557310125, "y": 12.430867710901826, "z": null, "yaw": 2.4913891053402644, "pitch": null, "roll": null}, "v": 0.9520482263589202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2566663695710777, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23889217274785102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.7090554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24446224908519457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9518932832443086, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.7090554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 49.791409557310125, "y": 7.4308677109018255, "z": null, "yaw": 2.4913891053402644, "pitch": null, "roll": null}, "v": 0.9520482263589202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2566663695710777, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23889217274785102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.7290554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426195577718598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9523178043369139, "gear": 1, "accelerator_pedal_position": 0.24446224908519457, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.7290554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 49.791409557310125, "y": 7.4308677109018255, "z": null, "yaw": 2.4913891053402644, "pitch": null, "roll": null}, "v": 0.9520482263589202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2566663695710777, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23889217274785102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.7490554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426195577718598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9525114825260718, "gear": 1, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.7490554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 49.791409557310125, "y": 7.4308677109018255, "z": null, "yaw": 2.4913891053402644, "pitch": null, "roll": null}, "v": 0.9520482263589202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2566663695710777, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23889217274785102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.7690554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426195577718598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9527048933408551, "gear": 1, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.7690554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 49.791409557310125, "y": 7.4308677109018255, "z": null, "yaw": 2.4913891053402644, "pitch": null, "roll": null}, "v": 0.9520482263589202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2566663695710777, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23889217274785102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.7890553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426195577718598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9528980371354187, "gear": 1, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.7890553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.8090553, "x": 53.70722771610914, "y": 12.493238411779704, "z": null, "yaw": 2.518990794282811, "pitch": null, "roll": null}, "v": 0.9530909142634899, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "acceleration": 0.00963386745243311, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23915380863154273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.8090553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25897325795932447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9530909142634899, "gear": 1, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.8090553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.70722771610914, "y": 7.4932384117797035, "z": null, "yaw": 2.518990794282811, "pitch": null, "roll": null}, "v": 0.9530909142634899, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "acceleration": 0.00963386745243311, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23915380863154273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.8290553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538663232549051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9553270315924703, "gear": 1, "accelerator_pedal_position": 0.25897325795932447, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.8290553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.70722771610914, "y": 7.4932384117797035, "z": null, "yaw": 2.518990794282811, "pitch": null, "roll": null}, "v": 0.9530909142634899, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "acceleration": 0.00963386745243311, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23915380863154273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.8490553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538663232549051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9569219136822225, "gear": 1, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.8490553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.70722771610914, "y": 7.4932384117797035, "z": null, "yaw": 2.518990794282811, "pitch": null, "roll": null}, "v": 0.9530909142634899, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "acceleration": 0.00963386745243311, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23915380863154273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.8690553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538663232549051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9585145914354866, "gear": 1, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.8690553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.70722771610914, "y": 7.4932384117797035, "z": null, "yaw": 2.518990794282811, "pitch": null, "roll": null}, "v": 0.9530909142634899, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "acceleration": 0.00963386745243311, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23915380863154273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.8890553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538663232549051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616933420634841, "gear": 1, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.8890553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.70722771610914, "y": 7.4932384117797035, "z": null, "yaw": 2.518990794282811, "pitch": null, "roll": null}, "v": 0.9530909142634899, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "acceleration": 0.00963386745243311, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23915380863154273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.9090552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538663232549051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616933420634841, "gear": 1, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.9090552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.9190552, "x": 53.620891441693324, "y": 12.553584794028998, "z": null, "yaw": 2.546592483225358, "pitch": null, "roll": null}, "v": 0.962486655187467, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "acceleration": 0.07927638196964387, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.241511429707619, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.9290552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23371694127757187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9631366169669723, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.9290552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 49.620891441693324, "y": 7.553584794028998, "z": null, "yaw": 2.546592483225358, "pitch": null, "roll": null}, "v": 0.962486655187467, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "acceleration": 0.07927638196964387, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.241511429707619, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.9690552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400461157828098, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9626695942740428, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.9690552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 49.620891441693324, "y": 7.553584794028998, "z": null, "yaw": 2.546592483225358, "pitch": null, "roll": null}, "v": 0.962486655187467, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "acceleration": 0.07927638196964387, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.241511429707619, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.9890552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400461157828098, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.962385386330925, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.9890552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 49.620891441693324, "y": 7.553584794028998, "z": null, "yaw": 2.546592483225358, "pitch": null, "roll": null}, "v": 0.962486655187467, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "acceleration": 0.07927638196964387, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.241511429707619, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.0090551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400461157828098, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.962385386330925, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.0090551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.029055, "x": 53.53244290289095, "y": 12.611844561047773, "z": null, "yaw": 2.5741941721679047, "pitch": null, "roll": null}, "v": 0.9622435774072978, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25737130589298085, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24145043555055468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.029055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23978749293358823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9621565826567173, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.029055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 49.53244290289095, "y": 7.611844561047773, "z": null, "yaw": 2.5741941721679047, "pitch": null, "roll": null}, "v": 0.9622435774072978, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25737130589298085, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24145043555055468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.049055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986747100238107, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619877724575715, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.049055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 49.53244290289095, "y": 7.611844561047773, "z": null, "yaw": 2.5741941721679047, "pitch": null, "roll": null}, "v": 0.9622435774072978, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25737130589298085, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24145043555055468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.069055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986747100238107, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619059534615557, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.069055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 49.53244290289095, "y": 7.611844561047773, "z": null, "yaw": 2.5741941721679047, "pitch": null, "roll": null}, "v": 0.9622435774072978, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25737130589298085, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24145043555055468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.089055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986747100238107, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616608362149122, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.089055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 49.53244290289095, "y": 7.611844561047773, "z": null, "yaw": 2.5741941721679047, "pitch": null, "roll": null}, "v": 0.9622435774072978, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25737130589298085, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24145043555055468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.109055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986747100238107, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9615792435780626, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.109055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 49.53244290289095, "y": 7.611844561047773, "z": null, "yaw": 2.5741941721679047, "pitch": null, "roll": null}, "v": 0.9622435774072978, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25737130589298085, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24145043555055468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.129055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986747100238107, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613348044370389, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.129055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.139055, "x": 53.44251743559071, "y": 12.667580759088082, "z": null, "yaw": 2.6017958611104515, "pitch": null, "roll": null}, "v": 0.9613348044370389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730838628407193, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24122240219742302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.149055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441005682155044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961253437511847, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.149055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 49.44251743559071, "y": 7.667580759088082, "z": null, "yaw": 2.6017958611104515, "pitch": null, "roll": null}, "v": 0.9613348044370389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730838628407193, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24122240219742302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.169055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427745784865713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616198266032282, "gear": 1, "accelerator_pedal_position": 0.2441005682155044, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.169055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 49.44251743559071, "y": 7.667580759088082, "z": null, "yaw": 2.6017958611104515, "pitch": null, "roll": null}, "v": 0.9613348044370389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730838628407193, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24122240219742302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.189055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427745784865713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619200085981247, "gear": 1, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.189055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 49.44251743559071, "y": 7.667580759088082, "z": null, "yaw": 2.6017958611104515, "pitch": null, "roll": null}, "v": 0.9613348044370389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730838628407193, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24122240219742302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.209055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427745784865713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620199307389422, "gear": 1, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.209055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 49.44251743559071, "y": 7.667580759088082, "z": null, "yaw": 2.6017958611104515, "pitch": null, "roll": null}, "v": 0.9613348044370389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730838628407193, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24122240219742302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.229055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427745784865713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623192822320612, "gear": 1, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.229055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 49.44251743559071, "y": 7.667580759088082, "z": null, "yaw": 2.6017958611104515, "pitch": null, "roll": null}, "v": 0.9613348044370389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730838628407193, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24122240219742302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.239055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427745784865713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623192822320612, "gear": 1, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.239055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.249055, "x": 53.3510903398005, "y": 12.72081198028997, "z": null, "yaw": 2.6293975500529982, "pitch": null, "roll": null}, "v": 0.9624189279062603, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "acceleration": 0.009957667217835142, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2414944352771754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.269055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23472032412233093, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9626180122943945, "gear": 1, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.269055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 49.3510903398005, "y": 7.7208119802899695, "z": null, "yaw": 2.6293975500529982, "pitch": null, "roll": null}, "v": 0.9624189279062603, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "acceleration": 0.009957667217835142, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2414944352771754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.2890549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23724103336582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618103878399131, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.2890549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 49.3510903398005, "y": 7.7208119802899695, "z": null, "yaw": 2.6293975500529982, "pitch": null, "roll": null}, "v": 0.9624189279062603, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "acceleration": 0.009957667217835142, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2414944352771754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.3090549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23724103336582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613188609885247, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.3090549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 49.3510903398005, "y": 7.7208119802899695, "z": null, "yaw": 2.6293975500529982, "pitch": null, "roll": null}, "v": 0.9624189279062603, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "acceleration": 0.009957667217835142, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2414944352771754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.3190548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23724103336582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9608280144581984, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.3190548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 49.3510903398005, "y": 7.7208119802899695, "z": null, "yaw": 2.6293975500529982, "pitch": null, "roll": null}, "v": 0.9624189279062603, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "acceleration": 0.009957667217835142, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2414944352771754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.3490548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23724103336582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598483582106906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.3490548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.3590548, "x": 53.258251367101124, "y": 12.771488575810691, "z": null, "yaw": 2.656999238995545, "pitch": null, "roll": null}, "v": 0.9600930179946444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572224369317529, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24091080762364078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.3690548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2420668918834898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598483582106906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.3690548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 49.258251367101124, "y": 7.771488575810691, "z": null, "yaw": 2.656999238995545, "pitch": null, "roll": null}, "v": 0.9600930179946444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572224369317529, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24091080762364078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.3890548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24055075953309002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599625700342023, "gear": 1, "accelerator_pedal_position": 0.2420668918834898, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.3890548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 49.258251367101124, "y": 7.771488575810691, "z": null, "yaw": 2.656999238995545, "pitch": null, "roll": null}, "v": 0.9600930179946444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572224369317529, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24091080762364078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.4090548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24055075953309002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598871728746529, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.4090548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 49.258251367101124, "y": 7.771488575810691, "z": null, "yaw": 2.656999238995545, "pitch": null, "roll": null}, "v": 0.9600930179946444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572224369317529, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24091080762364078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.4290547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24055075953309002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598118800258352, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.4290547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 49.258251367101124, "y": 7.771488575810691, "z": null, "yaw": 2.656999238995545, "pitch": null, "roll": null}, "v": 0.9600930179946444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572224369317529, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24091080762364078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.4490547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24055075953309002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9597366913411702, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.4490547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.4690547, "x": 53.16421627874305, "y": 12.819497716654213, "z": null, "yaw": 2.684600927938092, "pitch": null, "roll": null}, "v": 0.9596616066742911, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571925843269614, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24080255597754363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.4690547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24444276272495935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9596616066742911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.4690547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 49.16421627874305, "y": 7.8194977166542134, "z": null, "yaw": 2.684600927938092, "pitch": null, "roll": null}, "v": 0.9596616066742911, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571925843269614, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24080255597754363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.4890547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24322501829884513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960072957961259, "gear": 1, "accelerator_pedal_position": 0.24444276272495935, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.4890547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 49.16421627874305, "y": 7.8194977166542134, "z": null, "yaw": 2.684600927938092, "pitch": null, "roll": null}, "v": 0.9596616066742911, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571925843269614, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24080255597754363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.5090547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24322501829884513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603315747577869, "gear": 1, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.5090547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 49.16421627874305, "y": 7.8194977166542134, "z": null, "yaw": 2.684600927938092, "pitch": null, "roll": null}, "v": 0.9596616066742911, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571925843269614, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24080255597754363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.5290546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24322501829884513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9605898337249199, "gear": 1, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.5290546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 49.16421627874305, "y": 7.8194977166542134, "z": null, "yaw": 2.684600927938092, "pitch": null, "roll": null}, "v": 0.9596616066742911, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571925843269614, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24080255597754363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.5490546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24322501829884513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9608477353310911, "gear": 1, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.5490546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 49.16421627874305, "y": 7.8194977166542134, "z": null, "yaw": 2.684600927938092, "pitch": null, "roll": null}, "v": 0.9596616066742911, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571925843269614, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24080255597754363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.5690546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24322501829884513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9611052800441958, "gear": 1, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.5690546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.5790546, "x": 53.06883458893053, "y": 12.864920221186871, "z": null, "yaw": 2.7122026168806386, "pitch": null, "roll": null}, "v": 0.9612339187119187, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "acceleration": 0.012854961967363354, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411970875028456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.5890546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24721504793163343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613624683315923, "gear": 1, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.5890546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 49.06883458893053, "y": 7.864920221186871, "z": null, "yaw": 2.7122026168806386, "pitch": null, "roll": null}, "v": 0.9612339187119187, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "acceleration": 0.012854961967363354, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411970875028456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.6090546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24597360376110572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9621178817148396, "gear": 1, "accelerator_pedal_position": 0.24721504793163343, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.6090546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 49.06883458893053, "y": 7.864920221186871, "z": null, "yaw": 2.7122026168806386, "pitch": null, "roll": null}, "v": 0.9612339187119187, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "acceleration": 0.012854961967363354, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411970875028456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.6290545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24597360376110572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627171225945054, "gear": 1, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.6290545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 49.06883458893053, "y": 7.864920221186871, "z": null, "yaw": 2.7122026168806386, "pitch": null, "roll": null}, "v": 0.9612339187119187, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "acceleration": 0.012854961967363354, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411970875028456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.6490545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24597360376110572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9633155337968116, "gear": 1, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.6490545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 49.06883458893053, "y": 7.864920221186871, "z": null, "yaw": 2.7122026168806386, "pitch": null, "roll": null}, "v": 0.9612339187119187, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "acceleration": 0.012854961967363354, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411970875028456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.6690545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24597360376110572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963913116327297, "gear": 1, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.6690545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.6890545, "x": 52.972008473061955, "y": 12.907793149671118, "z": null, "yaw": 2.7398043058231853, "pitch": null, "roll": null}, "v": 0.9645098711907027, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "acceleration": 0.029806737031132458, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24201910406020896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.6890545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2614319492231952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645098711907027, "gear": 1, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.6890545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.972008473061955, "y": 7.907793149671118, "z": null, "yaw": 2.7398043058231853, "pitch": null, "roll": null}, "v": 0.9645098711907027, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "acceleration": 0.029806737031132458, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24201910406020896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.7090545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25661255731022065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9670374229779131, "gear": 1, "accelerator_pedal_position": 0.2614319492231952, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.7090545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.972008473061955, "y": 7.907793149671118, "z": null, "yaw": 2.7398043058231853, "pitch": null, "roll": null}, "v": 0.9645098711907027, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "acceleration": 0.029806737031132458, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24201910406020896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.7290545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25661255731022065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9689592563128921, "gear": 1, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.7290545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.972008473061955, "y": 7.907793149671118, "z": null, "yaw": 2.7398043058231853, "pitch": null, "roll": null}, "v": 0.9645098711907027, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "acceleration": 0.029806737031132458, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24201910406020896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.7490544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25661255731022065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9708784242375416, "gear": 1, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.7490544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.972008473061955, "y": 7.907793149671118, "z": null, "yaw": 2.7398043058231853, "pitch": null, "roll": null}, "v": 0.9645098711907027, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "acceleration": 0.029806737031132458, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24201910406020896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.7690544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25661255731022065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9727949289757751, "gear": 1, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.7690544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.972008473061955, "y": 7.907793149671118, "z": null, "yaw": 2.7398043058231853, "pitch": null, "roll": null}, "v": 0.9645098711907027, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "acceleration": 0.029806737031132458, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24201910406020896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.7890544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25661255731022065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9747087727545508, "gear": 1, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.7890544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.7990544, "x": 52.873308955288536, "y": 12.948273680785173, "z": null, "yaw": 2.767405994765732, "pitch": null, "roll": null}, "v": 0.9756646974808939, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "acceleration": 0.09552603229572937, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24481812265539096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.8090544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22917514175507545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9766199578038512, "gear": 1, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.8090544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 48.873308955288536, "y": 7.948273680785173, "z": null, "yaw": 2.767405994765732, "pitch": null, "roll": null}, "v": 0.9756646974808939, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "acceleration": 0.09552603229572937, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24481812265539096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.8290544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23778804798398828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.975100001813931, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.8290544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 48.873308955288536, "y": 7.948273680785173, "z": null, "yaw": 2.767405994765732, "pitch": null, "roll": null}, "v": 0.9756646974808939, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "acceleration": 0.09552603229572937, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24481812265539096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.8490543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23778804798398828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9746583973178543, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.8490543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 48.873308955288536, "y": 7.948273680785173, "z": null, "yaw": 2.767405994765732, "pitch": null, "roll": null}, "v": 0.9756646974808939, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "acceleration": 0.09552603229572937, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24481812265539096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.8690543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23778804798398828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9742174063979164, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.8690543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 48.873308955288536, "y": 7.948273680785173, "z": null, "yaw": 2.767405994765732, "pitch": null, "roll": null}, "v": 0.9756646974808939, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "acceleration": 0.09552603229572937, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24481812265539096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.8890543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23778804798398828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9737770281238374, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.8890543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.9090543, "x": 52.77302042804887, "y": 12.98621130710534, "z": null, "yaw": 2.795007683708279, "pitch": null, "roll": null}, "v": 0.9733372615669538, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581407173258943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2442341120905701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.9090543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23173438825833667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9733372615669538, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.9090543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.77302042804887, "y": 7.986211307105339, "z": null, "yaw": 2.795007683708279, "pitch": null, "roll": null}, "v": 0.9733372615669538, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581407173258943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2442341120905701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.9290543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233618071479279, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9721416611335959, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.9290543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.77302042804887, "y": 7.986211307105339, "z": null, "yaw": 2.795007683708279, "pitch": null, "roll": null}, "v": 0.9733372615669538, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581407173258943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2442341120905701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.9490542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233618071479279, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9711830994443146, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.9490542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.77302042804887, "y": 7.986211307105339, "z": null, "yaw": 2.795007683708279, "pitch": null, "roll": null}, "v": 0.9733372615669538, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581407173258943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2442341120905701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.9690542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233618071479279, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.970225868322147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.9690542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.77302042804887, "y": 7.986211307105339, "z": null, "yaw": 2.795007683708279, "pitch": null, "roll": null}, "v": 0.9733372615669538, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581407173258943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2442341120905701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.9890542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233618071479279, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9692699655537605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.9890542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.77302042804887, "y": 7.986211307105339, "z": null, "yaw": 2.795007683708279, "pitch": null, "roll": null}, "v": 0.9733372615669538, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581407173258943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2442341120905701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.0090542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233618071479279, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9683153889304196, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.0090542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.0190542, "x": 52.67214509170796, "y": 13.02122090225478, "z": null, "yaw": 2.8226093726508257, "pitch": null, "roll": null}, "v": 0.9678385972341653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25775904536467026, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24285436279499636, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.0290542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.240519530226935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9673621362479735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.0290542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 48.67214509170796, "y": 8.02122090225478, "z": null, "yaw": 2.8226093726508257, "pitch": null, "roll": null}, "v": 0.9678385972341653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25775904536467026, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24285436279499636, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.0490541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23834373934367165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9672725885495621, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.0490541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 48.67214509170796, "y": 8.02122090225478, "z": null, "yaw": 2.8226093726508257, "pitch": null, "roll": null}, "v": 0.9678385972341653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25775904536467026, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24285436279499636, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.0690541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23834373934367165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669112854406802, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.0690541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 48.67214509170796, "y": 8.02122090225478, "z": null, "yaw": 2.8226093726508257, "pitch": null, "roll": null}, "v": 0.9678385972341653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25775904536467026, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24285436279499636, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.089054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23834373934367165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966550483213471, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.089054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 48.67214509170796, "y": 8.02122090225478, "z": null, "yaw": 2.8226093726508257, "pitch": null, "roll": null}, "v": 0.9678385972341653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25775904536467026, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24285436279499636, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.109054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23834373934367165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661901811214992, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.109054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.129054, "x": 52.57074664210171, "y": 13.05330420610513, "z": null, "yaw": 2.8502110615933725, "pitch": null, "roll": null}, "v": 0.9658303784195804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576198021197601, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24235045160364413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.129054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23262174186755175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658303784195804, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.129054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 48.57074664210171, "y": 8.05330420610513, "z": null, "yaw": 2.8502110615933725, "pitch": null, "roll": null}, "v": 0.9658303784195804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576198021197601, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24235045160364413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.149054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2344029050844153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647560725470289, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.149054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 48.57074664210171, "y": 8.05330420610513, "z": null, "yaw": 2.8502110615933725, "pitch": null, "roll": null}, "v": 0.9658303784195804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576198021197601, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24235045160364413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.169054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2344029050844153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639058234287221, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.169054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 48.57074664210171, "y": 8.05330420610513, "z": null, "yaw": 2.8502110615933725, "pitch": null, "roll": null}, "v": 0.9658303784195804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576198021197601, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24235045160364413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.189054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2344029050844153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9630567520477581, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.189054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 48.57074664210171, "y": 8.05330420610513, "z": null, "yaw": 2.8502110615933725, "pitch": null, "roll": null}, "v": 0.9658303784195804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576198021197601, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24235045160364413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.209054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2344029050844153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622088564845043, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.209054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 48.57074664210171, "y": 8.05330420610513, "z": null, "yaw": 2.8502110615933725, "pitch": null, "roll": null}, "v": 0.9658303784195804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576198021197601, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24235045160364413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.229054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2344029050844153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613621348231843, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.229054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.239054, "x": 52.468857305370676, "y": 13.082475752761193, "z": null, "yaw": 2.8778127505359192, "pitch": null, "roll": null}, "v": 0.9609392136081215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257281002402904, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411231387882566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.249054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24111002264114542, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9605165851518684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.249054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 48.468857305370676, "y": 8.082475752761193, "z": null, "yaw": 2.8778127505359192, "pitch": null, "roll": null}, "v": 0.9609392136081215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257281002402904, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411231387882566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.269054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23899710703348903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9605103051487462, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.269054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 48.468857305370676, "y": 8.082475752761193, "z": null, "yaw": 2.8778127505359192, "pitch": null, "roll": null}, "v": 0.9609392136081215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257281002402904, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411231387882566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.289054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23899710703348903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9602400107797202, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.289054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 48.468857305370676, "y": 8.082475752761193, "z": null, "yaw": 2.8778127505359192, "pitch": null, "roll": null}, "v": 0.9609392136081215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257281002402904, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411231387882566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.309054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23899710703348903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599700904019014, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.309054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 48.468857305370676, "y": 8.082475752761193, "z": null, "yaw": 2.8778127505359192, "pitch": null, "roll": null}, "v": 0.9609392136081215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257281002402904, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411231387882566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.3290539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23899710703348903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9597005434686865, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.3290539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.3490539, "x": 52.366553765706286, "y": 13.108732966422554, "z": null, "yaw": 2.905414439478466, "pitch": null, "roll": null}, "v": 0.9594313694343491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717665399826417, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24074478382590844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.3490539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24139047182645046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9594313694343491, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.3490539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 48.366553765706286, "y": 8.108732966422554, "z": null, "yaw": 2.905414439478466, "pitch": null, "roll": null}, "v": 0.9594313694343491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717665399826417, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24074478382590844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.3690538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24063732741461807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.959461634858928, "gear": 1, "accelerator_pedal_position": 0.24139047182645046, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.3690538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 48.366553765706286, "y": 8.108732966422554, "z": null, "yaw": 2.905414439478466, "pitch": null, "roll": null}, "v": 0.9594313694343491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717665399826417, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24074478382590844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.3890538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24063732741461807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.959397747934126, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.3890538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 48.366553765706286, "y": 8.108732966422554, "z": null, "yaw": 2.905414439478466, "pitch": null, "roll": null}, "v": 0.9594313694343491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717665399826417, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24074478382590844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.4090538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24063732741461807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9593339493832631, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.4090538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 48.366553765706286, "y": 8.108732966422554, "z": null, "yaw": 2.905414439478466, "pitch": null, "roll": null}, "v": 0.9594313694343491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717665399826417, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24074478382590844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.4290538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24063732741461807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9592702390824651, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.4290538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 48.366553765706286, "y": 8.108732966422554, "z": null, "yaw": 2.905414439478466, "pitch": null, "roll": null}, "v": 0.9594313694343491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717665399826417, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24074478382590844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.4490538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24063732741461807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9592066169080362, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.4490538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.4590538, "x": 52.263656016463656, "y": 13.132135707689947, "z": null, "yaw": 2.933016128421013, "pitch": null, "roll": null}, "v": 0.9591748388296039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715890565591815, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2406804140263046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.4690537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23683516144975067, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9591430827364583, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.4690537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 48.263656016463656, "y": 8.132135707689947, "z": null, "yaw": 2.933016128421013, "pitch": null, "roll": null}, "v": 0.9591748388296039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715890565591815, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2406804140263046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.4890537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23802245167510255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958409738794713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.4890537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 48.263656016463656, "y": 8.132135707689947, "z": null, "yaw": 2.933016128421013, "pitch": null, "roll": null}, "v": 0.9591748388296039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715890565591815, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2406804140263046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.4990537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23802245167510255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9582150822322679, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.4990537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 48.263656016463656, "y": 8.132135707689947, "z": null, "yaw": 2.933016128421013, "pitch": null, "roll": null}, "v": 0.9591748388296039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715890565591815, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2406804140263046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.5290537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23802245167510255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9574378013423906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.5290537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 48.263656016463656, "y": 8.132135707689947, "z": null, "yaw": 2.933016128421013, "pitch": null, "roll": null}, "v": 0.9591748388296039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715890565591815, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2406804140263046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.5490537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23802245167510255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9574378013423906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.5490537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.5690536, "x": 52.16027235060678, "y": 13.152666256340236, "z": null, "yaw": 2.9606178173635596, "pitch": null, "roll": null}, "v": 0.9570499667057745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257011944723004, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401472316680807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.5790536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24361961679982821, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9570124910245736, "gear": 1, "accelerator_pedal_position": 0.24361961679982821, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.5790536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 48.16027235060678, "y": 8.152666256340236, "z": null, "yaw": 2.9606178173635596, "pitch": null, "roll": null}, "v": 0.9570499667057745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257011944723004, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401472316680807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.5990536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24186315350007864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9571686235382529, "gear": 1, "accelerator_pedal_position": 0.24361961679982821, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.5990536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 48.16027235060678, "y": 8.152666256340236, "z": null, "yaw": 2.9606178173635596, "pitch": null, "roll": null}, "v": 0.9570499667057745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257011944723004, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401472316680807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.6190536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24186315350007864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9572610827714628, "gear": 1, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.6190536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 48.16027235060678, "y": 8.152666256340236, "z": null, "yaw": 2.9606178173635596, "pitch": null, "roll": null}, "v": 0.9570499667057745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257011944723004, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401472316680807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.6390536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24186315350007864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.957353414187449, "gear": 1, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.6390536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 48.16027235060678, "y": 8.152666256340236, "z": null, "yaw": 2.9606178173635596, "pitch": null, "roll": null}, "v": 0.9570499667057745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257011944723004, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401472316680807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.6590536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24186315350007864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9574456179594996, "gear": 1, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.6590536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.6790535, "x": 52.05646998058152, "y": 13.170316609022036, "z": null, "yaw": 2.9882195063061063, "pitch": null, "roll": null}, "v": 0.9575376942606768, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "acceleration": 0.004599040303157054, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24026961443407274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.6790535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23962658435737114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9575376942606768, "gear": 1, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.6790535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 48.05646998058152, "y": 8.170316609022036, "z": null, "yaw": 2.9882195063061063, "pitch": null, "roll": null}, "v": 0.9575376942606768, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "acceleration": 0.004599040303157054, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24026961443407274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.6990535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24032719889129245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9573501687830878, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.6990535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 48.05646998058152, "y": 8.170316609022036, "z": null, "yaw": 2.9882195063061063, "pitch": null, "roll": null}, "v": 0.9575376942606768, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "acceleration": 0.004599040303157054, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24026961443407274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.7190535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24032719889129245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9572504490948456, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.7190535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 48.05646998058152, "y": 8.170316609022036, "z": null, "yaw": 2.9882195063061063, "pitch": null, "roll": null}, "v": 0.9575376942606768, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "acceleration": 0.004599040303157054, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24026961443407274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.7390535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24032719889129245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9571011279811004, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.7390535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 48.05646998058152, "y": 8.170316609022036, "z": null, "yaw": 2.9882195063061063, "pitch": null, "roll": null}, "v": 0.9575376942606768, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "acceleration": 0.004599040303157054, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24026961443407274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.7590535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24032719889129245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9570514230908973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.7590535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 48.05646998058152, "y": 8.170316609022036, "z": null, "yaw": 2.9882195063061063, "pitch": null, "roll": null}, "v": 0.9575376942606768, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "acceleration": 0.004599040303157054, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24026961443407274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.7790534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24032719889129245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.956952116386394, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.7790534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.7890534, "x": 51.95222225641988, "y": 13.185095477477912, "z": null, "yaw": 3.015821195248653, "pitch": null, "roll": null}, "v": 0.956902514523601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257001749949196, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24011023231111475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.7990534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24114949289837356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9568529469548148, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.7990534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 47.95222225641988, "y": 8.185095477477912, "z": null, "yaw": 3.015821195248653, "pitch": null, "roll": null}, "v": 0.956902514523601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257001749949196, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24011023231111475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.8190534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408903298950833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9568566658217349, "gear": 1, "accelerator_pedal_position": 0.24114949289837356, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.8190534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 47.95222225641988, "y": 8.185095477477912, "z": null, "yaw": 3.015821195248653, "pitch": null, "roll": null}, "v": 0.956902514523601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257001749949196, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24011023231111475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.8390534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408903298950833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9568279953713835, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.8390534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 47.95222225641988, "y": 8.185095477477912, "z": null, "yaw": 3.015821195248653, "pitch": null, "roll": null}, "v": 0.956902514523601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257001749949196, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24011023231111475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.8590534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408903298950833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9567993645509364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.8590534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 47.95222225641988, "y": 8.185095477477912, "z": null, "yaw": 3.015821195248653, "pitch": null, "roll": null}, "v": 0.956902514523601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257001749949196, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24011023231111475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.8790534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408903298950833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.956770773305287, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.8790534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.8990533, "x": 51.84764886002732, "y": 13.19698671900107, "z": null, "yaw": 3.0434228841912, "pitch": null, "roll": null}, "v": 0.9567422215794066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569906678644973, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2400700108930662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.8990533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23490671922434847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9567422215794066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.8990533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.84764886002732, "y": 8.19698671900107, "z": null, "yaw": 3.0434228841912, "pitch": null, "roll": null}, "v": 0.9567422215794066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569906678644973, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2400700108930662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.9190533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677604468034344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9559660165169448, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.9190533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.84764886002732, "y": 8.19698671900107, "z": null, "yaw": 3.0434228841912, "pitch": null, "roll": null}, "v": 0.9567422215794066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569906678644973, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2400700108930662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.9390533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677604468034344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9554244690948361, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.9390533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.84764886002732, "y": 8.19698671900107, "z": null, "yaw": 3.0434228841912, "pitch": null, "roll": null}, "v": 0.9567422215794066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569906678644973, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2400700108930662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.9590533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677604468034344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.954883669953888, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.9590533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.84764886002732, "y": 8.19698671900107, "z": null, "yaw": 3.0434228841912, "pitch": null, "roll": null}, "v": 0.9567422215794066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569906678644973, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2400700108930662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.9790533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677604468034344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9543436179432204, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.9790533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.84764886002732, "y": 8.19698671900107, "z": null, "yaw": 3.0434228841912, "pitch": null, "roll": null}, "v": 0.9567422215794066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569906678644973, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2400700108930662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.9990532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677604468034344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9538043119140284, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.9990532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.0090532, "x": 51.7429665961659, "y": 13.205972744901963, "z": null, "yaw": 3.0710245731337467, "pitch": null, "roll": null}, "v": 0.9535349382840502, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676903569948617, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23926522511243845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.0190532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24296769976387056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9532657507195769, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.0190532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 47.7429665961659, "y": 8.205972744901963, "z": null, "yaw": 3.0710245731337467, "pitch": null, "roll": null}, "v": 0.9535349382840502, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676903569948617, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23926522511243845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.0390532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102172466613708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9535016228386012, "gear": 1, "accelerator_pedal_position": 0.24296769976387056, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.0390532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 47.7429665961659, "y": 8.205972744901963, "z": null, "yaw": 3.0710245731337467, "pitch": null, "roll": null}, "v": 0.9535349382840502, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676903569948617, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23926522511243845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.0590532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102172466613708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9534940063613375, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.0590532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 47.7429665961659, "y": 8.205972744901963, "z": null, "yaw": 3.0710245731337467, "pitch": null, "roll": null}, "v": 0.9535349382840502, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676903569948617, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23926522511243845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.0790532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102172466613708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9534864004018294, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.0790532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 47.7429665961659, "y": 8.205972744901963, "z": null, "yaw": 3.0710245731337467, "pitch": null, "roll": null}, "v": 0.9535349382840502, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676903569948617, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23926522511243845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.0990531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102172466613708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9534788049455297, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.0990531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.1190531, "x": 51.63826547554641, "y": 13.212054504465192, "z": null, "yaw": 3.0986262620762934, "pitch": null, "roll": null}, "v": 0.9534712199779113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676463467215727, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23924923663183847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.1190531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24307438994102273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9534712199779113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.1190531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.63826547554641, "y": 8.212054504465192, "z": null, "yaw": 3.0986262620762934, "pitch": null, "roll": null}, "v": 0.9534712199779113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676463467215727, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23924923663183847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.139053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24243271157053742, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9538043662246157, "gear": 1, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.139053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.63826547554641, "y": 8.212054504465192, "z": null, "yaw": 3.0986262620762934, "pitch": null, "roll": null}, "v": 0.9534712199779113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676463467215727, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23924923663183847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.159053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24243271157053742, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9538885342377591, "gear": 1, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.159053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.63826547554641, "y": 8.212054504465192, "z": null, "yaw": 3.0986262620762934, "pitch": null, "roll": null}, "v": 0.9534712199779113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676463467215727, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23924923663183847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.179053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24243271157053742, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9541406895880788, "gear": 1, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.179053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.63826547554641, "y": 8.212054504465192, "z": null, "yaw": 3.0986262620762934, "pitch": null, "roll": null}, "v": 0.9534712199779113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676463467215727, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23924923663183847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.199053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24243271157053742, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9542246252708906, "gear": 1, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.199053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.63826547554641, "y": 8.212054504465192, "z": null, "yaw": 3.0986262620762934, "pitch": null, "roll": null}, "v": 0.9534712199779113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676463467215727, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23924923663183847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.219053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24243271157053742, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9543923227176574, "gear": 1, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.219053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.229053, "x": 51.53338156468397, "y": 13.215245829038127, "z": null, "yaw": 3.12622795101884, "pitch": null, "roll": null}, "v": 0.9544760845588909, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "acceleration": 0.008370397127965501, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23950138171905289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.239053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2391441767654747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9545597885301705, "gear": 1, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.239053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 47.53338156468397, "y": 8.215245829038127, "z": null, "yaw": 3.12622795101884, "pitch": null, "roll": null}, "v": 0.9544760845588909, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "acceleration": 0.008370397127965501, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23950138171905289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.259053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24017531534391073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9543160981712462, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.259053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 47.53338156468397, "y": 8.215245829038127, "z": null, "yaw": 3.12622795101884, "pitch": null, "roll": null}, "v": 0.9544760845588909, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "acceleration": 0.008370397127965501, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23950138171905289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.279053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24017531534391073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9542015922153345, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.279053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 47.53338156468397, "y": 8.215245829038127, "z": null, "yaw": 3.12622795101884, "pitch": null, "roll": null}, "v": 0.9544760845588909, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "acceleration": 0.008370397127965501, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23950138171905289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.299053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24017531534391073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9540872444167464, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.299053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 47.53338156468397, "y": 8.215245829038127, "z": null, "yaw": 3.12622795101884, "pitch": null, "roll": null}, "v": 0.9544760845588909, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "acceleration": 0.008370397127965501, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23950138171905289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.319053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24017531534391073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9539730545518044, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.319053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.339053, "x": 51.42842127512275, "y": 13.215541832539603, "z": null, "yaw": 3.153829639961387, "pitch": null, "roll": null}, "v": 0.9538590223971615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567914214659428, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23934654573863223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.339053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24522288070588955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9538590223971615, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.339053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 47.42842127512275, "y": 8.215541832539603, "z": null, "yaw": 3.153829639961387, "pitch": null, "roll": null}, "v": 0.9538590223971615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567914214659428, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23934654573863223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.359053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24364338405857494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9543758754739498, "gear": 1, "accelerator_pedal_position": 0.24522288070588955, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.359053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 47.42842127512275, "y": 8.215541832539603, "z": null, "yaw": 3.153829639961387, "pitch": null, "roll": null}, "v": 0.9538590223971615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567914214659428, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23934654573863223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.3790529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24364338405857494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9546946457876182, "gear": 1, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.3790529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 47.42842127512275, "y": 8.215541832539603, "z": null, "yaw": 3.153829639961387, "pitch": null, "roll": null}, "v": 0.9538590223971615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567914214659428, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23934654573863223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.3990529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24364338405857494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.955012975761986, "gear": 1, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.3990529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 47.42842127512275, "y": 8.215541832539603, "z": null, "yaw": 3.153829639961387, "pitch": null, "roll": null}, "v": 0.9538590223971615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567914214659428, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23934654573863223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.4190528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24364338405857494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9553308659648045, "gear": 1, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.4190528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 47.42842127512275, "y": 8.215541832539603, "z": null, "yaw": 3.153829639961387, "pitch": null, "roll": null}, "v": 0.9538590223971615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567914214659428, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23934654573863223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.4390528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24364338405857494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9556483169632087, "gear": 1, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.4390528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.4490528, "x": 51.32342594553087, "y": 13.21293870433291, "z": null, "yaw": 3.1814313289039338, "pitch": null, "roll": null}, "v": 0.9558068779378166, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "acceleration": 0.01584513859007014, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983531030897934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.4590528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2374064855603862, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9559653293237172, "gear": 1, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.4590528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 47.32342594553087, "y": 8.21293870433291, "z": null, "yaw": 3.1814313289039338, "pitch": null, "roll": null}, "v": 0.9558068779378166, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "acceleration": 0.01584513859007014, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983531030897934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.4790528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23936224713887144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9555025607284214, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.4790528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 47.32342594553087, "y": 8.21293870433291, "z": null, "yaw": 3.1814313289039338, "pitch": null, "roll": null}, "v": 0.9558068779378166, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "acceleration": 0.01584513859007014, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983531030897934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.4990528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23936224713887144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9552848172974607, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.4990528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 47.32342594553087, "y": 8.21293870433291, "z": null, "yaw": 3.1814313289039338, "pitch": null, "roll": null}, "v": 0.9558068779378166, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "acceleration": 0.01584513859007014, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983531030897934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.5190527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23936224713887144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9550673747134825, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.5190527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 47.32342594553087, "y": 8.21293870433291, "z": null, "yaw": 3.1814313289039338, "pitch": null, "roll": null}, "v": 0.9558068779378166, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "acceleration": 0.01584513859007014, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983531030897934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.5390527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23936224713887144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.954850232541913, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.5390527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.5590527, "x": 51.21848857152962, "y": 13.207436868498162, "z": null, "yaw": 3.2090330178464805, "pitch": null, "roll": null}, "v": 0.9546333903488576, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25684491861713243, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23954085358708493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.5590527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24487787680880663, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9546333903488576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.5590527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 47.21848857152962, "y": 8.207436868498162, "z": null, "yaw": 3.2090330178464805, "pitch": null, "roll": null}, "v": 0.9546333903488576, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25684491861713243, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23954085358708493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.5790527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24315018674624547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9551060632244441, "gear": 1, "accelerator_pedal_position": 0.24487787680880663, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.5790527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 47.21848857152962, "y": 8.207436868498162, "z": null, "yaw": 3.2090330178464805, "pitch": null, "roll": null}, "v": 0.9546333903488576, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25684491861713243, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23954085358708493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.5990527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24315018674624547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9553621964571213, "gear": 1, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.5990527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 47.21848857152962, "y": 8.207436868498162, "z": null, "yaw": 3.2090330178464805, "pitch": null, "roll": null}, "v": 0.9546333903488576, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25684491861713243, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23954085358708493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.6190526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24315018674624547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9556179758054452, "gear": 1, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.6190526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 47.21848857152962, "y": 8.207436868498162, "z": null, "yaw": 3.2090330178464805, "pitch": null, "roll": null}, "v": 0.9546333903488576, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25684491861713243, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23954085358708493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.6390526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24315018674624547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.955873401732197, "gear": 1, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.6390526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 47.21848857152962, "y": 8.207436868498162, "z": null, "yaw": 3.2090330178464805, "pitch": null, "roll": null}, "v": 0.9546333903488576, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25684491861713243, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23954085358708493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.6590526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24315018674624547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.956128474699627, "gear": 1, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.6590526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.6690526, "x": 51.11372730746967, "y": 13.19903906426047, "z": null, "yaw": 3.2366347067890273, "pitch": null, "roll": null}, "v": 0.9562558789679044, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "acceleration": 0.012731620155032097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23994797564322812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.6790526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23686295459713977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9563831951694548, "gear": 1, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.6790526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 47.11372730746967, "y": 8.19903906426047, "z": null, "yaw": 3.2366347067890273, "pitch": null, "roll": null}, "v": 0.9562558789679044, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "acceleration": 0.012731620155032097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23994797564322812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.6990526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23883332235520255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9558519312173335, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.6990526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 47.11372730746967, "y": 8.19903906426047, "z": null, "yaw": 3.2366347067890273, "pitch": null, "roll": null}, "v": 0.9562558789679044, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "acceleration": 0.012731620155032097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23994797564322812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.7190526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23883332235520255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9555676122859915, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.7190526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 47.11372730746967, "y": 8.19903906426047, "z": null, "yaw": 3.2366347067890273, "pitch": null, "roll": null}, "v": 0.9562558789679044, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "acceleration": 0.012731620155032097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23994797564322812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.7390525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23883332235520255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9552836862202454, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.7390525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 47.11372730746967, "y": 8.19903906426047, "z": null, "yaw": 3.2366347067890273, "pitch": null, "roll": null}, "v": 0.9562558789679044, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "acceleration": 0.012731620155032097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23994797564322812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.7590525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23883332235520255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9550001524450074, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.7590525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.7790525, "x": 51.00922238001774, "y": 13.187752401124227, "z": null, "yaw": 3.264236395731574, "pitch": null, "roll": null}, "v": 0.9547170103861184, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.256850696218512, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23956183589851981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.7790525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2444249111879179, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9547170103861184, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.7790525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 47.00922238001774, "y": 8.187752401124227, "z": null, "yaw": 3.264236395731574, "pitch": null, "roll": null}, "v": 0.9547170103861184, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.256850696218512, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23956183589851981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.7990525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267222098901658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9551329666051436, "gear": 1, "accelerator_pedal_position": 0.2444249111879179, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.7990525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 47.00922238001774, "y": 8.187752401124227, "z": null, "yaw": 3.264236395731574, "pitch": null, "roll": null}, "v": 0.9547170103861184, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.256850696218512, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23956183589851981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.8190525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267222098901658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9553293375921834, "gear": 1, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.8190525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 47.00922238001774, "y": 8.187752401124227, "z": null, "yaw": 3.264236395731574, "pitch": null, "roll": null}, "v": 0.9547170103861184, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.256850696218512, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23956183589851981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.8390524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267222098901658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9555254372662864, "gear": 1, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.8390524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 47.00922238001774, "y": 8.187752401124227, "z": null, "yaw": 3.264236395731574, "pitch": null, "roll": null}, "v": 0.9547170103861184, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.256850696218512, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23956183589851981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.8590524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267222098901658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.955721265986931, "gear": 1, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.8590524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 47.00922238001774, "y": 8.187752401124227, "z": null, "yaw": 3.264236395731574, "pitch": null, "roll": null}, "v": 0.9547170103861184, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.256850696218512, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23956183589851981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.8790524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267222098901658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9559168241131629, "gear": 1, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.8790524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.8890524, "x": 50.90509091163594, "y": 13.173588166149909, "z": null, "yaw": 3.291838084674121, "pitch": null, "roll": null}, "v": 0.9560145018154577, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "acceleration": 0.009761018813766065, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2398874082152311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.8990524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2477862500711028, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9561121120035954, "gear": 1, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.8990524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 46.90509091163594, "y": 8.173588166149909, "z": null, "yaw": 3.291838084674121, "pitch": null, "roll": null}, "v": 0.9560145018154577, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "acceleration": 0.009761018813766065, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2398874082152311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.9190524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24619259824552508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9569461627019952, "gear": 1, "accelerator_pedal_position": 0.2477862500711028, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.9190524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 46.90509091163594, "y": 8.173588166149909, "z": null, "yaw": 3.291838084674121, "pitch": null, "roll": null}, "v": 0.9560145018154577, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "acceleration": 0.009761018813766065, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2398874082152311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.9390523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24619259824552508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.957579922954999, "gear": 1, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.9390523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 46.90509091163594, "y": 8.173588166149909, "z": null, "yaw": 3.291838084674121, "pitch": null, "roll": null}, "v": 0.9560145018154577, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "acceleration": 0.009761018813766065, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2398874082152311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.9590523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24619259824552508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9582128070405241, "gear": 1, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.9590523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 46.90509091163594, "y": 8.173588166149909, "z": null, "yaw": 3.291838084674121, "pitch": null, "roll": null}, "v": 0.9560145018154577, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "acceleration": 0.009761018813766065, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2398874082152311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.9790523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24619259824552508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958844816009702, "gear": 1, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.9790523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.9990523, "x": 50.80115605675843, "y": 13.156516462806595, "z": null, "yaw": 3.3194397736166676, "pitch": null, "roll": null}, "v": 0.9594759509128751, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "acceleration": 0.0315240004850863, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24075597040866184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.9990523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.261237348525884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9594759509128751, "gear": 1, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.9990523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.80115605675843, "y": 8.156516462806595, "z": null, "yaw": 3.3194397736166676, "pitch": null, "roll": null}, "v": 0.9594759509128751, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "acceleration": 0.0315240004850863, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24075597040866184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.0190523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25654782979767665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961986155850044, "gear": 1, "accelerator_pedal_position": 0.261237348525884, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.0190523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.80115605675843, "y": 8.156516462806595, "z": null, "yaw": 3.3194397736166676, "pitch": null, "roll": null}, "v": 0.9594759509128751, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "acceleration": 0.0315240004850863, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24075597040866184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.0390522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25654782979767665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639068996646298, "gear": 1, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.0390522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.80115605675843, "y": 8.156516462806595, "z": null, "yaw": 3.3194397736166676, "pitch": null, "roll": null}, "v": 0.9594759509128751, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "acceleration": 0.0315240004850863, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24075597040866184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.0590522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25654782979767665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965824983458766, "gear": 1, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.0590522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.80115605675843, "y": 8.156516462806595, "z": null, "yaw": 3.3194397736166676, "pitch": null, "roll": null}, "v": 0.9594759509128751, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "acceleration": 0.0315240004850863, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24075597040866184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.0790522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25654782979767665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9677404094451819, "gear": 1, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.0790522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.80115605675843, "y": 8.156516462806595, "z": null, "yaw": 3.3194397736166676, "pitch": null, "roll": null}, "v": 0.9594759509128751, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "acceleration": 0.0315240004850863, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24075597040866184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.0990522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25654782979767665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9696531798396554, "gear": 1, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.0990522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.1090522, "x": 50.69695144645333, "y": 13.136430541024437, "z": null, "yaw": 3.3470414625592144, "pitch": null, "roll": null}, "v": 0.970608569883173, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "acceleration": 0.09547269778201378, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24354941664442614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.1190522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2681682277445767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9715632968609932, "gear": 1, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.1190522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 46.69695144645333, "y": 8.136430541024437, "z": null, "yaw": 3.3470414625592144, "pitch": null, "roll": null}, "v": 0.970608569883173, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "acceleration": 0.09547269778201378, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24354941664442614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.1390522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2645754260257471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9749228080212063, "gear": 1, "accelerator_pedal_position": 0.2681682277445767, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.1390522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 46.69695144645333, "y": 8.136430541024437, "z": null, "yaw": 3.3470414625592144, "pitch": null, "roll": null}, "v": 0.970608569883173, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "acceleration": 0.09547269778201378, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24354941664442614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.1590521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2645754260257471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9778287082298537, "gear": 1, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.1590521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 46.69695144645333, "y": 8.136430541024437, "z": null, "yaw": 3.3470414625592144, "pitch": null, "roll": null}, "v": 0.970608569883173, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "acceleration": 0.09547269778201378, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24354941664442614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.179052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2645754260257471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9807305681992734, "gear": 1, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.179052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 46.69695144645333, "y": 8.136430541024437, "z": null, "yaw": 3.3470414625592144, "pitch": null, "roll": null}, "v": 0.970608569883173, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "acceleration": 0.09547269778201378, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24354941664442614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.199052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2645754260257471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9836283901796964, "gear": 1, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.199052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.219052, "x": 50.591946735567966, "y": 13.113166246956236, "z": null, "yaw": 3.374643151501761, "pitch": null, "roll": null}, "v": 0.9865221764322755, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "acceleration": 0.14453804379337865, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24754252953463002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.219052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9865221764322755, "gear": 1, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.219052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 46.591946735567966, "y": 8.113166246956236, "z": null, "yaw": 3.374643151501761, "pitch": null, "roll": null}, "v": 0.9865221764322755, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "acceleration": 0.14453804379337865, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24754252953463002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.239052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2307216961246149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9813428148093084, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.239052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 46.591946735567966, "y": 8.113166246956236, "z": null, "yaw": 3.374643151501761, "pitch": null, "roll": null}, "v": 0.9865221764322755, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "acceleration": 0.14453804379337865, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24754252953463002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.259052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2307216961246149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9800095415413302, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.259052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 46.591946735567966, "y": 8.113166246956236, "z": null, "yaw": 3.374643151501761, "pitch": null, "roll": null}, "v": 0.9865221764322755, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "acceleration": 0.14453804379337865, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24754252953463002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.279052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2307216961246149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9786781237266672, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.279052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 46.591946735567966, "y": 8.113166246956236, "z": null, "yaw": 3.374643151501761, "pitch": null, "roll": null}, "v": 0.9865221764322755, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "acceleration": 0.14453804379337865, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24754252953463002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.299052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2307216961246149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9773485580743496, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.299052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 46.591946735567966, "y": 8.113166246956236, "z": null, "yaw": 3.374643151501761, "pitch": null, "roll": null}, "v": 0.9865221764322755, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "acceleration": 0.14453804379337865, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24754252953463002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.319052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2307216961246149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9760208413009448, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.319052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.329052, "x": 50.487398099349186, "y": 13.086963012010914, "z": null, "yaw": 3.402244840444308, "pitch": null, "roll": null}, "v": 0.9753576752198174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25828110970709295, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24474108326494845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.339052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23040807477849384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.974694970130535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.339052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 46.487398099349186, "y": 8.086963012010914, "z": null, "yaw": 3.402244840444308, "pitch": null, "roll": null}, "v": 0.9753576752198174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25828110970709295, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24474108326494845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.359052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23046721852991198, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9733317522455273, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.359052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 46.487398099349186, "y": 8.086963012010914, "z": null, "yaw": 3.402244840444308, "pitch": null, "roll": null}, "v": 0.9753576752198174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25828110970709295, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24474108326494845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.379052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23046721852991198, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.971977818253247, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.379052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 46.487398099349186, "y": 8.086963012010914, "z": null, "yaw": 3.402244840444308, "pitch": null, "roll": null}, "v": 0.9753576752198174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25828110970709295, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24474108326494845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.399052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23046721852991198, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9706257641228853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.399052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 46.487398099349186, "y": 8.086963012010914, "z": null, "yaw": 3.402244840444308, "pitch": null, "roll": null}, "v": 0.9753576752198174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25828110970709295, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24474108326494845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.419052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23046721852991198, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.969275586513392, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.419052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.4390519, "x": 50.38444827017854, "y": 13.058117936436949, "z": null, "yaw": 3.4298465293868547, "pitch": null, "roll": null}, "v": 0.9679272820913979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2577651963387383, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24287661599357135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.4390519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385757803437075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9679272820913979, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.4390519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 46.38444827017854, "y": 8.058117936436949, "z": null, "yaw": 3.4298465293868547, "pitch": null, "roll": null}, "v": 0.9679272820913979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2577651963387383, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24287661599357135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.4590518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23601605743019355, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9675940663017087, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.4590518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 46.38444827017854, "y": 8.058117936436949, "z": null, "yaw": 3.4298465293868547, "pitch": null, "roll": null}, "v": 0.9679272820913979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2577651963387383, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24287661599357135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.4790518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23601605743019355, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669414581246167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.4790518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 46.38444827017854, "y": 8.058117936436949, "z": null, "yaw": 3.4298465293868547, "pitch": null, "roll": null}, "v": 0.9679272820913979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2577651963387383, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24287661599357135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.4990518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23601605743019355, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662897546980719, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.4990518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 46.38444827017854, "y": 8.058117936436949, "z": null, "yaw": 3.4298465293868547, "pitch": null, "roll": null}, "v": 0.9679272820913979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2577651963387383, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24287661599357135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.5190518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23601605743019355, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656389545979354, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.5190518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 46.38444827017854, "y": 8.058117936436949, "z": null, "yaw": 3.4298465293868547, "pitch": null, "roll": null}, "v": 0.9679272820913979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2577651963387383, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24287661599357135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.5390518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23601605743019355, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649890564027483, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.5390518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.5490518, "x": 50.28290212407345, "y": 13.026617871857878, "z": null, "yaw": 3.4574482183294015, "pitch": null, "roll": null}, "v": 0.9646644450760363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575389971697404, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205789042658732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.5590518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2292451020648066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964340058693726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.5590518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 46.28290212407345, "y": 8.026617871857878, "z": null, "yaw": 3.4574482183294015, "pitch": null, "roll": null}, "v": 0.9646644450760363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575389971697404, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205789042658732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.5790517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134971703793322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628458837998826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.5790517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 46.28290212407345, "y": 8.026617871857878, "z": null, "yaw": 3.4574482183294015, "pitch": null, "roll": null}, "v": 0.9646644450760363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575389971697404, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205789042658732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.5990517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134971703793322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961616763841564, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.5990517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 46.28290212407345, "y": 8.026617871857878, "z": null, "yaw": 3.4574482183294015, "pitch": null, "roll": null}, "v": 0.9646644450760363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575389971697404, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205789042658732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.6190517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134971703793322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603893453420362, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.6190517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 46.28290212407345, "y": 8.026617871857878, "z": null, "yaw": 3.4574482183294015, "pitch": null, "roll": null}, "v": 0.9646644450760363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575389971697404, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205789042658732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.6390517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134971703793322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9591636253435722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.6390517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.6590517, "x": 50.18277605395547, "y": 12.992502727895685, "z": null, "yaw": 3.4850499072719483, "pitch": null, "roll": null}, "v": 0.9579396008950392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570734628343814, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2403704626332147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.6590517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24852348444190517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9579396008950392, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.6590517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 46.18277605395547, "y": 7.992502727895685, "z": null, "yaw": 3.4850499072719483, "pitch": null, "roll": null}, "v": 0.9579396008950392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570734628343814, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2403704626332147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.6790516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313340187738247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9588632476702814, "gear": 1, "accelerator_pedal_position": 0.24852348444190517, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.6790516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 46.18277605395547, "y": 7.992502727895685, "z": null, "yaw": 3.4850499072719483, "pitch": null, "roll": null}, "v": 0.9579396008950392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570734628343814, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2403704626332147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.6990516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313340187738247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9591120898093137, "gear": 1, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.6990516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 46.18277605395547, "y": 7.992502727895685, "z": null, "yaw": 3.4850499072719483, "pitch": null, "roll": null}, "v": 0.9579396008950392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570734628343814, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2403704626332147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.7190516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313340187738247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9593605877644958, "gear": 1, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.7190516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 46.18277605395547, "y": 7.992502727895685, "z": null, "yaw": 3.4850499072719483, "pitch": null, "roll": null}, "v": 0.9579396008950392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570734628343814, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2403704626332147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.7390516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313340187738247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9596087419871908, "gear": 1, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.7390516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 46.18277605395547, "y": 7.992502727895685, "z": null, "yaw": 3.4850499072719483, "pitch": null, "roll": null}, "v": 0.9579396008950392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570734628343814, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2403704626332147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.7590516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313340187738247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598565529282397, "gear": 1, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.7590516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.7690516, "x": 50.08388899822574, "y": 12.95573138726454, "z": null, "yaw": 3.512651596214495, "pitch": null, "roll": null}, "v": 0.959980329808892, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "acceleration": 0.012369122906995877, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24088253140318042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.7790515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23410574171796467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960104021037962, "gear": 1, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.7790515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 46.08388899822574, "y": 7.9557313872645405, "z": null, "yaw": 3.512651596214495, "pitch": null, "roll": null}, "v": 0.959980329808892, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "acceleration": 0.012369122906995877, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24088253140318042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.7990515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369339461717112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9592230796863823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.7990515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 46.08388899822574, "y": 7.9557313872645405, "z": null, "yaw": 3.512651596214495, "pitch": null, "roll": null}, "v": 0.959980329808892, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "acceleration": 0.012369122906995877, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24088253140318042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.8190515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369339461717112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9586967602165549, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.8190515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 46.08388899822574, "y": 7.9557313872645405, "z": null, "yaw": 3.512651596214495, "pitch": null, "roll": null}, "v": 0.959980329808892, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "acceleration": 0.012369122906995877, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24088253140318042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.8390515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369339461717112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9581711686743515, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.8390515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 46.08388899822574, "y": 7.9557313872645405, "z": null, "yaw": 3.512651596214495, "pitch": null, "roll": null}, "v": 0.959980329808892, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "acceleration": 0.012369122906995877, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24088253140318042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.8590515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369339461717112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9576463039425493, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.8590515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.8790514, "x": 49.98609488572707, "y": 12.916262605614635, "z": null, "yaw": 3.540253285157042, "pitch": null, "roll": null}, "v": 0.957122164905929, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570169366308386, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401653479613796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.8790514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23672027321518221, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.957122164905929, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.8790514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.98609488572707, "y": 7.9162626056146355, "z": null, "yaw": 3.540253285157042, "pitch": null, "roll": null}, "v": 0.957122164905929, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570169366308386, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401653479613796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.8990514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677716094160572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9565720505646556, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.8990514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.98609488572707, "y": 7.9162626056146355, "z": null, "yaw": 3.540253285157042, "pitch": null, "roll": null}, "v": 0.957122164905929, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570169366308386, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401653479613796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.9190514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677716094160572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9560298051027091, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.9190514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.98609488572707, "y": 7.9162626056146355, "z": null, "yaw": 3.540253285157042, "pitch": null, "roll": null}, "v": 0.957122164905929, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570169366308386, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401653479613796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.9390514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677716094160572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9554883090176804, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.9390514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.98609488572707, "y": 7.9162626056146355, "z": null, "yaw": 3.540253285157042, "pitch": null, "roll": null}, "v": 0.957122164905929, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570169366308386, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401653479613796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.9590514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677716094160572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9549475611566927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.9590514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.98609488572707, "y": 7.9162626056146355, "z": null, "yaw": 3.540253285157042, "pitch": null, "roll": null}, "v": 0.957122164905929, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570169366308386, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401653479613796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.9790514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677716094160572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.954407560368948, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.9790514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.9890513, "x": 49.88972796501033, "y": 12.874241008266301, "z": null, "yaw": 3.5678549740995886, "pitch": null, "roll": null}, "v": 0.954137839768485, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25681068216120495, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23941650783276908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.9990513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2318440368008311, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9538683055057233, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.9990513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 45.88972796501033, "y": 7.874241008266301, "z": null, "yaw": 3.5678549740995886, "pitch": null, "roll": null}, "v": 0.954137839768485, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25681068216120495, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23941650783276908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.0190513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23337532637533318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9527133678561669, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.0190513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 45.88972796501033, "y": 7.874241008266301, "z": null, "yaw": 3.5678549740995886, "pitch": null, "roll": null}, "v": 0.954137839768485, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25681068216120495, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23941650783276908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.0390513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23337532637533318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9517513699748251, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.0390513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 45.88972796501033, "y": 7.874241008266301, "z": null, "yaw": 3.5678549740995886, "pitch": null, "roll": null}, "v": 0.954137839768485, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25681068216120495, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23941650783276908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.0590513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23337532637533318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9507906999585249, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.0590513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 45.88972796501033, "y": 7.874241008266301, "z": null, "yaw": 3.5678549740995886, "pitch": null, "roll": null}, "v": 0.954137839768485, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25681068216120495, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23941650783276908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.0790513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23337532637533318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.94983135560536, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.0790513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.0990512, "x": 49.794953885458895, "y": 12.829762577743626, "z": null, "yaw": 3.5954566630421354, "pitch": null, "roll": null}, "v": 0.9488733347179905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564472727892879, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23809551482513067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.0990512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23991115972928737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9488733347179905, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.0990512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.794953885458895, "y": 7.829762577743626, "z": null, "yaw": 3.5954566630421354, "pitch": null, "roll": null}, "v": 0.9488733347179905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564472727892879, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23809551482513067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.1190512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23785053998653324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9487333325295153, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.1190512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.794953885458895, "y": 7.829762577743626, "z": null, "yaw": 3.5954566630421354, "pitch": null, "roll": null}, "v": 0.9488733347179905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564472727892879, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23809551482513067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.1390512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23785053998653324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9483360347687746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.1390512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.794953885458895, "y": 7.829762577743626, "z": null, "yaw": 3.5954566630421354, "pitch": null, "roll": null}, "v": 0.9488733347179905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564472727892879, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23809551482513067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.1590512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23785053998653324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.947939284841316, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.1590512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.794953885458895, "y": 7.829762577743626, "z": null, "yaw": 3.5954566630421354, "pitch": null, "roll": null}, "v": 0.9488733347179905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564472727892879, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23809551482513067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.1790512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23785053998653324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9475430819287903, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.1790512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.794953885458895, "y": 7.829762577743626, "z": null, "yaw": 3.5954566630421354, "pitch": null, "roll": null}, "v": 0.9488733347179905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564472727892879, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23809551482513067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.1990511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23785053998653324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9471474252142374, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.1990511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.2090511, "x": 49.70180478487369, "y": 12.782866474232145, "z": null, "yaw": 3.623058351984682, "pitch": null, "roll": null}, "v": 0.9469498014262797, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25631462933552673, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23761285330159945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.2190511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24266828543439972, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9467523138820828, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.2190511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 45.70180478487369, "y": 7.782866474232145, "z": null, "yaw": 3.623058351984682, "pitch": null, "roll": null}, "v": 0.9469498014262797, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25631462933552673, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23761285330159945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.239051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24115610681779184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9469597577322454, "gear": 1, "accelerator_pedal_position": 0.24266828543439972, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.239051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 45.70180478487369, "y": 7.782866474232145, "z": null, "yaw": 3.623058351984682, "pitch": null, "roll": null}, "v": 0.9469498014262797, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25631462933552673, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23761285330159945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.259051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24115610681779184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9469779584942832, "gear": 1, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.259051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 45.70180478487369, "y": 7.782866474232145, "z": null, "yaw": 3.623058351984682, "pitch": null, "roll": null}, "v": 0.9469498014262797, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25631462933552673, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23761285330159945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.279051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24115610681779184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9469961341699542, "gear": 1, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.279051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 45.70180478487369, "y": 7.782866474232145, "z": null, "yaw": 3.623058351984682, "pitch": null, "roll": null}, "v": 0.9469498014262797, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25631462933552673, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23761285330159945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.299051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24115610681779184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9470142847937031, "gear": 1, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.299051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.319051, "x": 49.61009698857563, "y": 12.733476951042066, "z": null, "yaw": 3.650660040927229, "pitch": null, "roll": null}, "v": 0.9470324103999277, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "acceleration": 0.0009053432277235651, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23763358191245848, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.319051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23466416851461727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9470324103999277, "gear": 1, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.319051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.61009698857563, "y": 7.733476951042066, "z": null, "yaw": 3.650660040927229, "pitch": null, "roll": null}, "v": 0.9470324103999277, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "acceleration": 0.0009053432277235651, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23763358191245848, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.339051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23669318531708383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9462392984433756, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.339051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.61009698857563, "y": 7.733476951042066, "z": null, "yaw": 3.650660040927229, "pitch": null, "roll": null}, "v": 0.9470324103999277, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "acceleration": 0.0009053432277235651, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23763358191245848, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.359051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23669318531708383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9457008191771432, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.359051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.61009698857563, "y": 7.733476951042066, "z": null, "yaw": 3.650660040927229, "pitch": null, "roll": null}, "v": 0.9470324103999277, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "acceleration": 0.0009053432277235651, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23763358191245848, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.379051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23669318531708383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.945163081859545, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.379051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.61009698857563, "y": 7.733476951042066, "z": null, "yaw": 3.650660040927229, "pitch": null, "roll": null}, "v": 0.9470324103999277, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "acceleration": 0.0009053432277235651, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23763358191245848, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.399051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23669318531708383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9446260853526552, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.399051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.61009698857563, "y": 7.733476951042066, "z": null, "yaw": 3.650660040927229, "pitch": null, "roll": null}, "v": 0.9470324103999277, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "acceleration": 0.0009053432277235651, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23763358191245848, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.419051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23669318531708383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9440898285205941, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.419051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.429051, "x": 49.519928516168946, "y": 12.68165745952173, "z": null, "yaw": 3.6782617298697757, "pitch": null, "roll": null}, "v": 0.9438219771282199, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560990981015132, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23682800572576318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.439051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501101318340698, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9435543102295225, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.439051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 45.519928516168946, "y": 7.68165745952173, "z": null, "yaw": 3.6782617298697757, "pitch": null, "roll": null}, "v": 0.9438219771282199, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560990981015132, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23682800572576318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.459051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24590627197714826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9446960701120033, "gear": 1, "accelerator_pedal_position": 0.2501101318340698, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.459051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 45.519928516168946, "y": 7.68165745952173, "z": null, "yaw": 3.6782617298697757, "pitch": null, "roll": null}, "v": 0.9438219771282199, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560990981015132, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23682800572576318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.4790509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24590627197714826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9453109560141038, "gear": 1, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.4790509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 45.519928516168946, "y": 7.68165745952173, "z": null, "yaw": 3.6782617298697757, "pitch": null, "roll": null}, "v": 0.9438219771282199, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560990981015132, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23682800572576318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.4990509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24590627197714826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9459249948566976, "gear": 1, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.4990509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 45.519928516168946, "y": 7.68165745952173, "z": null, "yaw": 3.6782617298697757, "pitch": null, "roll": null}, "v": 0.9438219771282199, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560990981015132, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23682800572576318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.5190508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24590627197714826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9465381876559181, "gear": 1, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.5190508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.5390508, "x": 49.43124648190866, "y": 12.627380671245348, "z": null, "yaw": 3.7058634188123225, "pitch": null, "roll": null}, "v": 0.9471505354271224, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "acceleration": 0.030585731718221598, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2376632223693399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.5390508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2333479522301551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9471505354271224, "gear": 1, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.5390508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 45.43124648190866, "y": 7.627380671245348, "z": null, "yaw": 3.7058634188123225, "pitch": null, "roll": null}, "v": 0.9471505354271224, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "acceleration": 0.030585731718221598, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2376632223693399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.5590508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728389823356985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.946192790333155, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.5590508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 45.43124648190866, "y": 7.627380671245348, "z": null, "yaw": 3.7058634188123225, "pitch": null, "roll": null}, "v": 0.9471505354271224, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "acceleration": 0.030585731718221598, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2376632223693399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.5790508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728389823356985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9457281888231541, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.5790508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 45.43124648190866, "y": 7.627380671245348, "z": null, "yaw": 3.7058634188123225, "pitch": null, "roll": null}, "v": 0.9471505354271224, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "acceleration": 0.030585731718221598, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2376632223693399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.5990508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728389823356985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9452642274702897, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.5990508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 45.43124648190866, "y": 7.627380671245348, "z": null, "yaw": 3.7058634188123225, "pitch": null, "roll": null}, "v": 0.9471505354271224, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "acceleration": 0.030585731718221598, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2376632223693399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.6190507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728389823356985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9448009053064387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.6190507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 45.43124648190866, "y": 7.627380671245348, "z": null, "yaw": 3.7058634188123225, "pitch": null, "roll": null}, "v": 0.9471505354271224, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "acceleration": 0.030585731718221598, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2376632223693399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.6390507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728389823356985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9443382213651675, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.6390507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.6490507, "x": 49.3440656423518, "y": 12.570659191269725, "z": null, "yaw": 3.7334651077548693, "pitch": null, "roll": null}, "v": 0.94410711842645, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2561187384319575, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23689955464774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.6590507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24202690969204654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9438761746817286, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.6590507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 45.3440656423518, "y": 7.5706591912697245, "z": null, "yaw": 3.7334651077548693, "pitch": null, "roll": null}, "v": 0.94410711842645, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2561187384319575, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23689955464774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.6790507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24053423114724637, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9440074365509593, "gear": 1, "accelerator_pedal_position": 0.24202690969204654, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.6790507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 45.3440656423518, "y": 7.5706591912697245, "z": null, "yaw": 3.7334651077548693, "pitch": null, "roll": null}, "v": 0.94410711842645, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2561187384319575, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23689955464774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.6990507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24053423114724637, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9439519970996508, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.6990507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 45.3440656423518, "y": 7.5706591912697245, "z": null, "yaw": 3.7334651077548693, "pitch": null, "roll": null}, "v": 0.94410711842645, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2561187384319575, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23689955464774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.7190506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24053423114724637, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9438966339946709, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.7190506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 45.3440656423518, "y": 7.5706591912697245, "z": null, "yaw": 3.7334651077548693, "pitch": null, "roll": null}, "v": 0.94410711842645, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2561187384319575, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23689955464774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.7390506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24053423114724637, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9438413471296566, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.7390506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.7590506, "x": 49.25863187194749, "y": 12.51165499189019, "z": null, "yaw": 3.761066796697416, "pitch": null, "roll": null}, "v": 0.9437861363983963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25609662953249795, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23681901241052616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.7590506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24630352643333842, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9437861363983963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.7590506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 45.25863187194749, "y": 7.51165499189019, "z": null, "yaw": 3.761066796697416, "pitch": null, "roll": null}, "v": 0.9437861363983963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25609662953249795, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23681901241052616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.7790506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449951502865963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9444519152418391, "gear": 1, "accelerator_pedal_position": 0.24630352643333842, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.7790506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 45.25863187194749, "y": 7.51165499189019, "z": null, "yaw": 3.761066796697416, "pitch": null, "roll": null}, "v": 0.9437861363983963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25609662953249795, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23681901241052616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.7990506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449951502865963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9448913534017912, "gear": 1, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.7990506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 45.25863187194749, "y": 7.51165499189019, "z": null, "yaw": 3.761066796697416, "pitch": null, "roll": null}, "v": 0.9437861363983963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25609662953249795, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23681901241052616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.8190506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449951502865963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9453301862629575, "gear": 1, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.8190506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 45.25863187194749, "y": 7.51165499189019, "z": null, "yaw": 3.761066796697416, "pitch": null, "roll": null}, "v": 0.9437861363983963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25609662953249795, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23681901241052616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.8390505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449951502865963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9457684145820964, "gear": 1, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.8390505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 45.25863187194749, "y": 7.51165499189019, "z": null, "yaw": 3.761066796697416, "pitch": null, "roll": null}, "v": 0.9437861363983963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25609662953249795, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23681901241052616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.8590505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449951502865963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9462060391152418, "gear": 1, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.8590505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.8690505, "x": 49.17475729688604, "y": 12.450240078634442, "z": null, "yaw": 3.788668485639963, "pitch": null, "roll": null}, "v": 0.9464246251981296, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "acceleration": 0.021843541957401902, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23748107374805927, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.8790505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494233476042687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9466430606177036, "gear": 1, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.8790505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 45.17475729688604, "y": 7.450240078634442, "z": null, "yaw": 3.788668485639963, "pitch": null, "roll": null}, "v": 0.9464246251981296, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "acceleration": 0.021843541957401902, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23748107374805927, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.8990505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24789373879346233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9476947467594459, "gear": 1, "accelerator_pedal_position": 0.2494233476042687, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.8990505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 45.17475729688604, "y": 7.450240078634442, "z": null, "yaw": 3.788668485639963, "pitch": null, "roll": null}, "v": 0.9464246251981296, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "acceleration": 0.021843541957401902, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23748107374805927, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.9190505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24789373879346233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.948553847982761, "gear": 1, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.9190505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 45.17475729688604, "y": 7.450240078634442, "z": null, "yaw": 3.788668485639963, "pitch": null, "roll": null}, "v": 0.9464246251981296, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "acceleration": 0.021843541957401902, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23748107374805927, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.9390504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24789373879346233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9494117646257997, "gear": 1, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.9390504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 45.17475729688604, "y": 7.450240078634442, "z": null, "yaw": 3.788668485639963, "pitch": null, "roll": null}, "v": 0.9464246251981296, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "acceleration": 0.021843541957401902, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23748107374805927, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.9590504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24789373879346233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9502684980276253, "gear": 1, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.9590504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.9790504, "x": 49.09231017500992, "y": 12.386300847951501, "z": null, "yaw": 3.8162701745825096, "pitch": null, "roll": null}, "v": 0.951124049526672, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "acceleration": 0.04273329540692572, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2386602741891999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.9790504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24308130730165736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.951124049526672, "gear": 1, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.9790504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 45.09231017500992, "y": 7.386300847951501, "z": null, "yaw": 3.8162701745825096, "pitch": null, "roll": null}, "v": 0.951124049526672, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "acceleration": 0.04273329540692572, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2386602741891999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.9990504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460140039352177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9513770741446519, "gear": 1, "accelerator_pedal_position": 0.24308130730165736, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.9990504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 45.09231017500992, "y": 7.386300847951501, "z": null, "yaw": 3.8162701745825096, "pitch": null, "roll": null}, "v": 0.951124049526672, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "acceleration": 0.04273329540692572, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2386602741891999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.0190504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460140039352177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9518196956292452, "gear": 1, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.0190504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 45.09231017500992, "y": 7.386300847951501, "z": null, "yaw": 3.8162701745825096, "pitch": null, "roll": null}, "v": 0.951124049526672, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "acceleration": 0.04273329540692572, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2386602741891999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.0390503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460140039352177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9522617062045542, "gear": 1, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.0390503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 45.09231017500992, "y": 7.386300847951501, "z": null, "yaw": 3.8162701745825096, "pitch": null, "roll": null}, "v": 0.951124049526672, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "acceleration": 0.04273329540692572, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2386602741891999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.0590503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460140039352177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.952703106635638, "gear": 1, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.0590503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 45.09231017500992, "y": 7.386300847951501, "z": null, "yaw": 3.8162701745825096, "pitch": null, "roll": null}, "v": 0.951124049526672, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "acceleration": 0.04273329540692572, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2386602741891999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.0790503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460140039352177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9531438976868227, "gear": 1, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.0790503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.0890503, "x": 49.0113578503601, "y": 12.319864198681184, "z": null, "yaw": 3.8438718635250564, "pitch": null, "roll": null}, "v": 0.9533640649336047, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "acceleration": 0.022001518809763476, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23922234881182416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.0990503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25076407142396107, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9535840801217024, "gear": 1, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.0990503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 45.0113578503601, "y": 7.319864198681184, "z": null, "yaw": 3.8438718635250564, "pitch": null, "roll": null}, "v": 0.9533640649336047, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "acceleration": 0.022001518809763476, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23922234881182416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.1190503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488459685492192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9547937225088888, "gear": 1, "accelerator_pedal_position": 0.25076407142396107, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.1190503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 45.0113578503601, "y": 7.319864198681184, "z": null, "yaw": 3.8438718635250564, "pitch": null, "roll": null}, "v": 0.9533640649336047, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "acceleration": 0.022001518809763476, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23922234881182416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.1390502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488459685492192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9557620139807186, "gear": 1, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.1390502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 45.0113578503601, "y": 7.319864198681184, "z": null, "yaw": 3.8438718635250564, "pitch": null, "roll": null}, "v": 0.9533640649336047, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "acceleration": 0.022001518809763476, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23922234881182416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.1590502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488459685492192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9567289675348648, "gear": 1, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.1590502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 45.0113578503601, "y": 7.319864198681184, "z": null, "yaw": 3.8438718635250564, "pitch": null, "roll": null}, "v": 0.9533640649336047, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "acceleration": 0.022001518809763476, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23922234881182416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.1790502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488459685492192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9576945846460984, "gear": 1, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.1790502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.1990502, "x": 48.93196604184634, "y": 12.250953946143964, "z": null, "yaw": 3.871473552467603, "pitch": null, "roll": null}, "v": 0.9586588667887022, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "acceleration": 0.0481640918644588, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2405509440283408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.1990502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252133051014317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9586588667887022, "gear": 1, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.1990502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.93196604184634, "y": 7.250953946143964, "z": null, "yaw": 3.871473552467603, "pitch": null, "roll": null}, "v": 0.9586588667887022, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "acceleration": 0.0481640918644588, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2405509440283408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.2190502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25112413597839833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960032558609382, "gear": 1, "accelerator_pedal_position": 0.252133051014317, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.2190502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.93196604184634, "y": 7.250953946143964, "z": null, "yaw": 3.871473552467603, "pitch": null, "roll": null}, "v": 0.9586588667887022, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "acceleration": 0.0481640918644588, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2405509440283408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.2390501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25112413597839833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612782793339049, "gear": 1, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.2390501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.93196604184634, "y": 7.250953946143964, "z": null, "yaw": 3.871473552467603, "pitch": null, "roll": null}, "v": 0.9586588667887022, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "acceleration": 0.0481640918644588, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2405509440283408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.2590501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25112413597839833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9625222760960933, "gear": 1, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.2590501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.93196604184634, "y": 7.250953946143964, "z": null, "yaw": 3.871473552467603, "pitch": null, "roll": null}, "v": 0.9586588667887022, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "acceleration": 0.0481640918644588, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2405509440283408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.27905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25112413597839833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9637645506629547, "gear": 1, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.27905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.93196604184634, "y": 7.250953946143964, "z": null, "yaw": 3.871473552467603, "pitch": null, "roll": null}, "v": 0.9586588667887022, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "acceleration": 0.0481640918644588, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2405509440283408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.29905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25112413597839833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650051048016204, "gear": 1, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.29905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.30905, "x": 48.854007976535186, "y": 12.17942115403078, "z": null, "yaw": 3.89907524141015, "pitch": null, "roll": null}, "v": 0.9656247372626402, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "acceleration": 0.06192030166972201, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2422988512104837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.31905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2646245530951389, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662439402793375, "gear": 1, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.31905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 44.854007976535186, "y": 7.179421154030781, "z": null, "yaw": 3.89907524141015, "pitch": null, "roll": null}, "v": 0.9656247372626402, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "acceleration": 0.06192030166972201, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2422988512104837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.33905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042978682720974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9703663748782213, "gear": 1, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.33905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 44.854007976535186, "y": 7.179421154030781, "z": null, "yaw": 3.89907524141015, "pitch": null, "roll": null}, "v": 0.9656247372626402, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "acceleration": 0.06192030166972201, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2422988512104837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.35905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042978682720974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9715638922773334, "gear": 1, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.35905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 44.854007976535186, "y": 7.179421154030781, "z": null, "yaw": 3.89907524141015, "pitch": null, "roll": null}, "v": 0.9656247372626402, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "acceleration": 0.06192030166972201, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2422988512104837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.37905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042978682720974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9739564334414513, "gear": 1, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.37905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 44.854007976535186, "y": 7.179421154030781, "z": null, "yaw": 3.89907524141015, "pitch": null, "roll": null}, "v": 0.9656247372626402, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "acceleration": 0.06192030166972201, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2422988512104837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.39905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042978682720974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.976345651699251, "gear": 1, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.39905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.41905, "x": 48.77729588381564, "y": 12.105026885556137, "z": null, "yaw": 3.9266769303526967, "pitch": null, "roll": null}, "v": 0.9787315493832339, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "acceleration": 0.11917043574331804, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24558767076667504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.41905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24324126666543702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.925549256315893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9787315493832339, "gear": 1, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.41905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.77729588381564, "y": 7.105026885556137, "z": null, "yaw": 3.9266769303526967, "pitch": null, "roll": null}, "v": 0.9787315493832339, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "acceleration": 0.11917043574331804, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24558767076667504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.43905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24865819195417774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.925549256315893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.978966311380683, "gear": 1, "accelerator_pedal_position": 0.24324126666543702, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.43905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.77729588381564, "y": 7.105026885556137, "z": null, "yaw": 3.9266769303526967, "pitch": null, "roll": null}, "v": 0.9787315493832339, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "acceleration": 0.11917043574331804, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24558767076667504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.45905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24865819195417774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.925549256315893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9798776268810976, "gear": 1, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.45905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.77729588381564, "y": 7.105026885556137, "z": null, "yaw": 3.9266769303526967, "pitch": null, "roll": null}, "v": 0.9787315493832339, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "acceleration": 0.11917043574331804, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24558767076667504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.47905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24865819195417774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.925549256315893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9807876743993891, "gear": 1, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.47905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.77729588381564, "y": 7.105026885556137, "z": null, "yaw": 3.9266769303526967, "pitch": null, "roll": null}, "v": 0.9787315493832339, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "acceleration": 0.11917043574331804, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24558767076667504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.49905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24865819195417774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.925549256315893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9816964553686377, "gear": 1, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.49905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.77729588381564, "y": 7.105026885556137, "z": null, "yaw": 3.9266769303526967, "pitch": null, "roll": null}, "v": 0.9787315493832339, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "acceleration": 0.11917043574331804, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24558767076667504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.51905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24865819195417774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.925549256315893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9826039712213114, "gear": 1, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.51905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.5290499, "x": 48.70197851453948, "y": 12.027842360976964, "z": null, "yaw": 3.9542786192952435, "pitch": null, "roll": null}, "v": 0.9830572551764108, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "acceleration": 0.045296821285240485, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2466730960917682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.5390499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575953615014369, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.609741275512887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9845214491354574, "gear": 1, "accelerator_pedal_position": 0.2575953615014369, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.5390499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 44.70197851453948, "y": 7.027842360976964, "z": null, "yaw": 3.9542786192952435, "pitch": null, "roll": null}, "v": 0.9830572551764108, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "acceleration": 0.045296821285240485, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2466730960917682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.5590498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25481755152172564, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.609741275512887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9855319702563486, "gear": 1, "accelerator_pedal_position": 0.2575953615014369, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.5590498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 44.70197851453948, "y": 7.027842360976964, "z": null, "yaw": 3.9542786192952435, "pitch": null, "roll": null}, "v": 0.9830572551764108, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "acceleration": 0.045296821285240485, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2466730960917682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.5790498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25481755152172564, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.609741275512887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9872037945805878, "gear": 1, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.5790498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 44.70197851453948, "y": 7.027842360976964, "z": null, "yaw": 3.9542786192952435, "pitch": null, "roll": null}, "v": 0.9830572551764108, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "acceleration": 0.045296821285240485, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2466730960917682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.5990498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25481755152172564, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.609741275512887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9888732880005929, "gear": 1, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.5990498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 44.70197851453948, "y": 7.027842360976964, "z": null, "yaw": 3.9542786192952435, "pitch": null, "roll": null}, "v": 0.9830572551764108, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "acceleration": 0.045296821285240485, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2466730960917682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.6190498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25481755152172564, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.609741275512887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9905404526516812, "gear": 1, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.6190498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.6390498, "x": 48.62831844111934, "y": 11.948063643706952, "z": null, "yaw": 3.9818803082377903, "pitch": null, "roll": null}, "v": 0.9922052906708547, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "acceleration": 0.08315471908889005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24896856182043212, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.6390498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25584681345287014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.22611132996549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9922052906708547, "gear": 1, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.6390498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.62831844111934, "y": 6.948063643706952, "z": null, "yaw": 3.9818803082377903, "pitch": null, "roll": null}, "v": 0.9922052906708547, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "acceleration": 0.08315471908889005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24896856182043212, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.6590497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555707388409565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.22611132996549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9939964169971418, "gear": 1, "accelerator_pedal_position": 0.25584681345287014, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.6590497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.62831844111934, "y": 6.948063643706952, "z": null, "yaw": 3.9818803082377903, "pitch": null, "roll": null}, "v": 0.9922052906708547, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "acceleration": 0.08315471908889005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24896856182043212, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.6790497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555707388409565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.22611132996549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9957488364546603, "gear": 1, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.6790497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.62831844111934, "y": 6.948063643706952, "z": null, "yaw": 3.9818803082377903, "pitch": null, "roll": null}, "v": 0.9922052906708547, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "acceleration": 0.08315471908889005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24896856182043212, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.6990497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555707388409565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.22611132996549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9974988066684576, "gear": 1, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.6990497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.62831844111934, "y": 6.948063643706952, "z": null, "yaw": 3.9818803082377903, "pitch": null, "roll": null}, "v": 0.9922052906708547, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "acceleration": 0.08315471908889005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24896856182043212, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.7190497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555707388409565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.22611132996549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9992463298371538, "gear": 1, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.7190497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.62831844111934, "y": 6.948063643706952, "z": null, "yaw": 3.9818803082377903, "pitch": null, "roll": null}, "v": 0.9922052906708547, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "acceleration": 0.08315471908889005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24896856182043212, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.7390497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555707388409565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.22611132996549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0027340438440153, "gear": 1, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.7390497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.7490497, "x": 48.556203743968034, "y": 11.865498744781602, "z": null, "yaw": 4.009481997180338, "pitch": null, "roll": null}, "v": 1.0018630311951846, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "acceleration": 0.08710126488308245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2513919250007993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.7590497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27148930816489786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.8706557638633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0027340438440153, "gear": 1, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.7590497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 44.556203743968034, "y": 6.865498744781602, "z": null, "yaw": 4.009481997180338, "pitch": null, "roll": null}, "v": 1.0018630311951846, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "acceleration": 0.08710126488308245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2513919250007993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.7790496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26654425515844876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.8706557638633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0064650705225247, "gear": 1, "accelerator_pedal_position": 0.27148930816489786, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.7790496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 44.556203743968034, "y": 6.865498744781602, "z": null, "yaw": 4.009481997180338, "pitch": null, "roll": null}, "v": 1.0018630311951846, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "acceleration": 0.08710126488308245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2513919250007993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.7990496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26654425515844876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.8706557638633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0095729525672037, "gear": 1, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.7990496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 44.556203743968034, "y": 6.865498744781602, "z": null, "yaw": 4.009481997180338, "pitch": null, "roll": null}, "v": 1.0018630311951846, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "acceleration": 0.08710126488308245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2513919250007993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.8190496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26654425515844876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.8706557638633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0126764741731349, "gear": 1, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.8190496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 44.556203743968034, "y": 6.865498744781602, "z": null, "yaw": 4.009481997180338, "pitch": null, "roll": null}, "v": 1.0018630311951846, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "acceleration": 0.08710126488308245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2513919250007993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.8390496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26654425515844876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.8706557638633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0173235857207445, "gear": 1, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.8390496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.8590496, "x": 48.48549491926457, "y": 11.77988206016589, "z": null, "yaw": 4.03708368612289, "pitch": null, "roll": null}, "v": 1.0188704451474808, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "acceleration": 0.15457710264298036, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25565950090651235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.8590496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26222273880165103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.321791492463738, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0188704451474808, "gear": 1, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.8590496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 44.48549491926457, "y": 6.779882060165891, "z": null, "yaw": 4.03708368612289, "pitch": null, "roll": null}, "v": 1.0188704451474808, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "acceleration": 0.15457710264298036, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25565950090651235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.8790495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26363291584797494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.321791492463738, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.021420899705112, "gear": 1, "accelerator_pedal_position": 0.26222273880165103, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.332727799287383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.8790495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 44.48549491926457, "y": 6.779882060165891, "z": null, "yaw": 4.03708368612289, "pitch": null, "roll": null}, "v": 1.0188704451474808, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "acceleration": 0.15457710264298036, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25565950090651235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.8990495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26363291584797494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.321791492463738, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0241439737231914, "gear": 1, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.256740587603522, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.8990495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 44.48549491926457, "y": 6.779882060165891, "z": null, "yaw": 4.03708368612289, "pitch": null, "roll": null}, "v": 1.0188704451474808, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "acceleration": 0.15457710264298036, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25565950090651235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.9190495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26363291584797494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.321791492463738, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.026863211233345, "gear": 1, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.180424959826725, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.9190495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 44.48549491926457, "y": 6.779882060165891, "z": null, "yaw": 4.03708368612289, "pitch": null, "roll": null}, "v": 1.0188704451474808, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "acceleration": 0.15457710264298036, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25565950090651235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.9390495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26363291584797494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.321791492463738, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0295786146841257, "gear": 1, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.103780915956989, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.9390495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 44.48549491926457, "y": 6.779882060165891, "z": null, "yaw": 4.03708368612289, "pitch": null, "roll": null}, "v": 1.0188704451474808, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "acceleration": 0.15457710264298036, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25565950090651235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.9590495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26363291584797494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.321791492463738, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0322901865331393, "gear": 1, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.026808455994315, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.9590495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.9690495, "x": 48.41607124987378, "y": 11.69097120607302, "z": null, "yaw": 4.063913919626914, "pitch": null, "roll": null}, "v": 1.03364453637745, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "acceleration": 0.13533928695514125, "steering_wheel_angle": 9.988199069978124, "front_wheel_angle": 0.542709992703555, "heading_rate": 0.2435199349245484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.9790494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26831795207898684, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.777543950715653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0366431802159601, "gear": 1, "accelerator_pedal_position": 0.26831795207898684, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.911774579139028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.9790494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 44.41607124987378, "y": 6.690971206073019, "z": null, "yaw": 4.063913919626914, "pitch": null, "roll": null}, "v": 1.03364453637745, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "acceleration": 0.13533928695514125, "steering_wheel_angle": 9.988199069978124, "front_wheel_angle": 0.542709992703555, "heading_rate": 0.2435199349245484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.9990494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26690597458089993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.777543950715653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.03828726772248, "gear": 1, "accelerator_pedal_position": 0.26831795207898684, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.873963817728118, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.9990494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 44.41607124987378, "y": 6.690971206073019, "z": null, "yaw": 4.063913919626914, "pitch": null, "roll": null}, "v": 1.03364453637745, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "acceleration": 0.13533928695514125, "steering_wheel_angle": 9.988199069978124, "front_wheel_angle": 0.542709992703555, "heading_rate": 0.2435199349245484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.0190494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26690597458089993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.777543950715653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0413955187677355, "gear": 1, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.798109013072589, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.0190494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 44.41607124987378, "y": 6.690971206073019, "z": null, "yaw": 4.063913919626914, "pitch": null, "roll": null}, "v": 1.03364453637745, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "acceleration": 0.13533928695514125, "steering_wheel_angle": 9.988199069978124, "front_wheel_angle": 0.542709992703555, "heading_rate": 0.2435199349245484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.0390494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26690597458089993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.777543950715653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0444993693195248, "gear": 1, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.721943165972126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.0390494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 44.41607124987378, "y": 6.690971206073019, "z": null, "yaw": 4.063913919626914, "pitch": null, "roll": null}, "v": 1.03364453637745, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "acceleration": 0.13533928695514125, "steering_wheel_angle": 9.988199069978124, "front_wheel_angle": 0.542709992703555, "heading_rate": 0.2435199349245484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.0590494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26690597458089993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.777543950715653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0475988217556378, "gear": 1, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.645466276426719, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.0590494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.0790493, "x": 48.34795274867498, "y": 11.598878849228061, "z": null, "yaw": 4.089100089785886, "pitch": null, "roll": null}, "v": 1.050693878466867, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "acceleration": 0.15458807094480365, "steering_wheel_angle": 9.568678344436375, "front_wheel_angle": 0.5151189661271693, "heading_rate": 0.23234234764717868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.0790493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27234103234471707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.216852320958267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.050693878466867, "gear": 1, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.568678344436375, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.0790493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 44.34795274867498, "y": 6.598878849228061, "z": null, "yaw": 4.089100089785886, "pitch": null, "roll": null}, "v": 1.050693878466867, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "acceleration": 0.15458807094480365, "steering_wheel_angle": 9.568678344436375, "front_wheel_angle": 0.5151189661271693, "heading_rate": 0.23234234764717868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.0990493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27070296737408106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.216852320958267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0544636827330385, "gear": 1, "accelerator_pedal_position": 0.27234103234471707, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.493602118789335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.0990493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 44.34795274867498, "y": 6.598878849228061, "z": null, "yaw": 4.089100089785886, "pitch": null, "roll": null}, "v": 1.050693878466867, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "acceleration": 0.15458807094480365, "steering_wheel_angle": 9.568678344436375, "front_wheel_angle": 0.5151189661271693, "heading_rate": 0.23234234764717868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.1190493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27070296737408106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.216852320958267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0580234451687516, "gear": 1, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.418230926302698, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.1190493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 44.34795274867498, "y": 6.598878849228061, "z": null, "yaw": 4.089100089785886, "pitch": null, "roll": null}, "v": 1.050693878466867, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "acceleration": 0.15458807094480365, "steering_wheel_angle": 9.568678344436375, "front_wheel_angle": 0.5151189661271693, "heading_rate": 0.23234234764717868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.1390493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27070296737408106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.216852320958267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.065127782535438, "gear": 1, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.266603640810626, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.1390493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 44.34795274867498, "y": 6.598878849228061, "z": null, "yaw": 4.089100089785886, "pitch": null, "roll": null}, "v": 1.050693878466867, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "acceleration": 0.15458807094480365, "steering_wheel_angle": 9.568678344436375, "front_wheel_angle": 0.5151189661271693, "heading_rate": 0.23234234764717868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.1590493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27070296737408106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.216852320958267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.065127782535438, "gear": 1, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.266603640810626, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.1590493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 44.34795274867498, "y": 6.598878849228061, "z": null, "yaw": 4.089100089785886, "pitch": null, "roll": null}, "v": 1.050693878466867, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "acceleration": 0.15458807094480365, "steering_wheel_angle": 9.568678344436375, "front_wheel_angle": 0.5151189661271693, "heading_rate": 0.23234234764717868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.1790493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27070296737408106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.216852320958267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0704427550014275, "gear": 1, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.152108888737626, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.1790493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.1890492, "x": 48.280945116959785, "y": 11.503490517874942, "z": null, "yaw": 4.112739951095686, "pitch": null, "roll": null}, "v": 1.0704427550014275, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "acceleration": 0.17691293142058473, "steering_wheel_angle": 9.152108888737626, "front_wheel_angle": 0.48831751358539627, "heading_rate": 0.22212896583534397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.1990492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27930843640409675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.720717847132163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0722118843156334, "gear": 1, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.113796487960158, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.1990492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 44.280945116959785, "y": 6.503490517874942, "z": null, "yaw": 4.112739951095686, "pitch": null, "roll": null}, "v": 1.0704427550014275, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "acceleration": 0.17691293142058473, "steering_wheel_angle": 9.152108888737626, "front_wheel_angle": 0.48831751358539627, "heading_rate": 0.22212896583534397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.2190492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2766895428392165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.720717847132163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0768216514900806, "gear": 1, "accelerator_pedal_position": 0.27930843640409675, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.038652761578113, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.2190492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 44.280945116959785, "y": 6.503490517874942, "z": null, "yaw": 4.112739951095686, "pitch": null, "roll": null}, "v": 1.0704427550014275, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "acceleration": 0.17691293142058473, "steering_wheel_angle": 9.152108888737626, "front_wheel_angle": 0.48831751358539627, "heading_rate": 0.22212896583534397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.2390492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2766895428392165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.720717847132163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0810975832903003, "gear": 1, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.96322696793884, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.2390492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 44.280945116959785, "y": 6.503490517874942, "z": null, "yaw": 4.112739951095686, "pitch": null, "roll": null}, "v": 1.0704427550014275, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "acceleration": 0.17691293142058473, "steering_wheel_angle": 9.152108888737626, "front_wheel_angle": 0.48831751358539627, "heading_rate": 0.22212896583534397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.2590492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2766895428392165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.720717847132163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0853673941000357, "gear": 1, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.88751910704234, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.2590492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 44.280945116959785, "y": 6.503490517874942, "z": null, "yaw": 4.112739951095686, "pitch": null, "roll": null}, "v": 1.0704427550014275, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "acceleration": 0.17691293142058473, "steering_wheel_angle": 9.152108888737626, "front_wheel_angle": 0.48831751358539627, "heading_rate": 0.22212896583534397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.2790492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2766895428392165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.720717847132163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0917606366861052, "gear": 1, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.773428439590285, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.2790492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.2990491, "x": 48.21484464058674, "y": 11.404641989350615, "z": null, "yaw": 4.134912873671614, "pitch": null, "roll": null}, "v": 1.0938886586664316, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "acceleration": 0.21264928583619092, "steering_wheel_angle": 8.735257183477652, "front_wheel_angle": 0.46205478476360506, "heading_rate": 0.21280003719203341, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.2990491} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2827366520068352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0960151515247936, "gear": 1, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.697015410550712, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.2990491} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 44.21484464058674, "y": 6.4046419893506155, "z": null, "yaw": 4.134912873671614, "pitch": null, "roll": null}, "v": 1.0938886586664316, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "acceleration": 0.21264928583619092, "steering_wheel_angle": 8.735257183477652, "front_wheel_angle": 0.46205478476360506, "heading_rate": 0.21280003719203341, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.3190491} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2809309163200963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0985180597782211, "gear": 1, "accelerator_pedal_position": 0.2827366520068352, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.659590602341442, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.3190491} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 44.21484464058674, "y": 6.4046419893506155, "z": null, "yaw": 4.134912873671614, "pitch": null, "roll": null}, "v": 1.0938886586664316, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "acceleration": 0.21264928583619092, "steering_wheel_angle": 8.735257183477652, "front_wheel_angle": 0.46205478476360506, "heading_rate": 0.21280003719203341, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.339049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2809309163200963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1056776488131126, "gear": 1, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.546912434361376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.339049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 44.21484464058674, "y": 6.4046419893506155, "z": null, "yaw": 4.134912873671614, "pitch": null, "roll": null}, "v": 1.0938886586664316, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "acceleration": 0.21264928583619092, "steering_wheel_angle": 8.735257183477652, "front_wheel_angle": 0.46205478476360506, "heading_rate": 0.21280003719203341, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.359049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2809309163200963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.110442111992091, "gear": 1, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.471457202914458, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.359049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 44.21484464058674, "y": 6.4046419893506155, "z": null, "yaw": 4.134912873671614, "pitch": null, "roll": null}, "v": 1.0938886586664316, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "acceleration": 0.21264928583619092, "steering_wheel_angle": 8.735257183477652, "front_wheel_angle": 0.46205478476360506, "heading_rate": 0.21280003719203341, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.379049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2809309163200963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1128217650376926, "gear": 1, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.433628651352937, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.379049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 44.21484464058674, "y": 6.4046419893506155, "z": null, "yaw": 4.134912873671614, "pitch": null, "roll": null}, "v": 1.0938886586664316, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "acceleration": 0.21264928583619092, "steering_wheel_angle": 8.735257183477652, "front_wheel_angle": 0.46205478476360506, "heading_rate": 0.21280003719203341, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.399049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2809309163200963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1175759145806041, "gear": 1, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.357769676553767, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.399049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2809309163200963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1199504113008347, "gear": 1, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.319739253316122, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.409049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.409049, "x": 48.149430954311306, "y": 11.302109489451567, "z": null, "yaw": 4.155690003732978, "pitch": null, "roll": null}, "v": 1.1199504113008347, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "acceleration": 0.23727781719783103, "steering_wheel_angle": 8.319739253316122, "front_wheel_angle": 0.4363973531863847, "heading_rate": 0.2040352097430939, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.429049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28741988954144254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.584364742071587, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1274691514702315, "gear": 1, "accelerator_pedal_position": 0.28741988954144254, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.206163417694526, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.429049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 44.149430954311306, "y": 6.302109489451567, "z": null, "yaw": 4.155690003732978, "pitch": null, "roll": null}, "v": 1.1199504113008347, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "acceleration": 0.23727781719783103, "steering_wheel_angle": 8.319739253316122, "front_wheel_angle": 0.4363973531863847, "heading_rate": 0.2040352097430939, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.449049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854860867865649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.584364742071587, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1302420413220848, "gear": 1, "accelerator_pedal_position": 0.28741988954144254, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.168786203648196, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.449049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 44.149430954311306, "y": 6.302109489451567, "z": null, "yaw": 4.155690003732978, "pitch": null, "roll": null}, "v": 1.1199504113008347, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "acceleration": 0.23727781719783103, "steering_wheel_angle": 8.319739253316122, "front_wheel_angle": 0.4363973531863847, "heading_rate": 0.2040352097430939, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.469049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854860867865649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.584364742071587, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.135540145973479, "gear": 1, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.093839485827084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.469049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 44.149430954311306, "y": 6.302109489451567, "z": null, "yaw": 4.155690003732978, "pitch": null, "roll": null}, "v": 1.1199504113008347, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "acceleration": 0.23727781719783103, "steering_wheel_angle": 8.319739253316122, "front_wheel_angle": 0.4363973531863847, "heading_rate": 0.2040352097430939, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.489049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854860867865649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.584364742071587, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1408305516430137, "gear": 1, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.01863638170137, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.489049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 44.149430954311306, "y": 6.302109489451567, "z": null, "yaw": 4.155690003732978, "pitch": null, "roll": null}, "v": 1.1199504113008347, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "acceleration": 0.23727781719783103, "steering_wheel_angle": 8.319739253316122, "front_wheel_angle": 0.4363973531863847, "heading_rate": 0.2040352097430939, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.509049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854860867865649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.584364742071587, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1461132583272402, "gear": 1, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.943176891271053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.509049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.519049, "x": 48.084539466149295, "y": 11.195723217903817, "z": null, "yaw": 4.175135197863339, "pitch": null, "roll": null}, "v": 1.1487517245621455, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "acceleration": 0.26365415094107825, "steering_wheel_angle": 7.905351001191668, "front_wheel_angle": 0.4112982457106558, "heading_rate": 0.1957255603683291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.529049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29488033053746715, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.038879095354681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1546100231031875, "gear": 1, "accelerator_pedal_position": 0.29488033053746715, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.830310749226504, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.529049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 44.084539466149295, "y": 6.195723217903817, "z": null, "yaw": 4.175135197863339, "pitch": null, "roll": null}, "v": 1.1487517245621455, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "acceleration": 0.26365415094107825, "steering_wheel_angle": 7.905351001191668, "front_wheel_angle": 0.4112982457106558, "heading_rate": 0.1957255603683291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.549049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29204930159275205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.038879095354681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1578294263196827, "gear": 1, "accelerator_pedal_position": 0.29488033053746715, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.793099071359932, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.549049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 44.084539466149295, "y": 6.195723217903817, "z": null, "yaw": 4.175135197863339, "pitch": null, "roll": null}, "v": 1.1487517245621455, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "acceleration": 0.26365415094107825, "steering_wheel_angle": 7.905351001191668, "front_wheel_angle": 0.4112982457106558, "heading_rate": 0.1957255603683291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.569049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29204930159275205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.038879095354681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1669430804222725, "gear": 1, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.681095562418533, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.569049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 44.084539466149295, "y": 6.195723217903817, "z": null, "yaw": 4.175135197863339, "pitch": null, "roll": null}, "v": 1.1487517245621455, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "acceleration": 0.26365415094107825, "steering_wheel_angle": 7.905351001191668, "front_wheel_angle": 0.4112982457106558, "heading_rate": 0.1957255603683291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.5890489} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29204930159275205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.038879095354681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1730077232040772, "gear": 1, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.606119493672868, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.5890489} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 44.084539466149295, "y": 6.195723217903817, "z": null, "yaw": 4.175135197863339, "pitch": null, "roll": null}, "v": 1.1487517245621455, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "acceleration": 0.26365415094107825, "steering_wheel_angle": 7.905351001191668, "front_wheel_angle": 0.4112982457106558, "heading_rate": 0.1957255603683291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.6090488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29204930159275205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.038879095354681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.179063462743328, "gear": 1, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.530897774699419, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.6090488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.6290488, "x": 48.019947492129425, "y": 11.085190281307652, "z": null, "yaw": 4.1933100965130095, "pitch": null, "roll": null}, "v": 1.1820879932965858, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "acceleration": 0.3022304150509114, "steering_wheel_angle": 7.493194796377276, "front_wheel_angle": 0.3867916483021223, "heading_rate": 0.18807638141869282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.6290488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3021390982584432, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.260628899765484, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1851102974470948, "gear": 1, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.455430405498184, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.6290488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 44.019947492129425, "y": 6.085190281307652, "z": null, "yaw": 4.1933100965130095, "pitch": null, "roll": null}, "v": 1.1820879932965858, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "acceleration": 0.3022304150509114, "steering_wheel_angle": 7.493194796377276, "front_wheel_angle": 0.3867916483021223, "heading_rate": 0.18807638141869282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.6490488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.299108226234662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.260628899765484, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.192408985176824, "gear": 1, "accelerator_pedal_position": 0.3021390982584432, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.381885913860536, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.6490488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 44.019947492129425, "y": 6.085190281307652, "z": null, "yaw": 4.1933100965130095, "pitch": null, "roll": null}, "v": 1.1820879932965858, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "acceleration": 0.3022304150509114, "steering_wheel_angle": 7.493194796377276, "front_wheel_angle": 0.3867916483021223, "heading_rate": 0.18807638141869282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.6690488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.299108226234662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.260628899765484, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1993181833377682, "gear": 1, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.308109620513345, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.6690488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 44.019947492129425, "y": 6.085190281307652, "z": null, "yaw": 4.1933100965130095, "pitch": null, "roll": null}, "v": 1.1820879932965858, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "acceleration": 0.3022304150509114, "steering_wheel_angle": 7.493194796377276, "front_wheel_angle": 0.3867916483021223, "heading_rate": 0.18807638141869282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.6890488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.299108226234662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.260628899765484, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2027689519752771, "gear": 1, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.2711345481986704, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.6890488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 44.019947492129425, "y": 6.085190281307652, "z": null, "yaw": 4.1933100965130095, "pitch": null, "roll": null}, "v": 1.1820879932965858, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "acceleration": 0.3022304150509114, "steering_wheel_angle": 7.493194796377276, "front_wheel_angle": 0.3867916483021223, "heading_rate": 0.18807638141869282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.7090487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.299108226234662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.260628899765484, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2131059302065268, "gear": 1, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.159861628690331, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.7090487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 44.019947492129425, "y": 6.085190281307652, "z": null, "yaw": 4.1933100965130095, "pitch": null, "roll": null}, "v": 1.1820879932965858, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "acceleration": 0.3022304150509114, "steering_wheel_angle": 7.493194796377276, "front_wheel_angle": 0.3867916483021223, "heading_rate": 0.18807638141869282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.7290487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.299108226234662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.260628899765484, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2165464787812996, "gear": 1, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.122654754666113, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.7290487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.7390487, "x": 47.95540742551599, "y": 10.970139591604212, "z": null, "yaw": 4.210271036133182, "pitch": null, "roll": null}, "v": 1.2199844711480718, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "acceleration": 0.3435435693108093, "steering_wheel_angle": 7.08538993021451, "front_wheel_angle": 0.36296896062683853, "heading_rate": 0.1809943485364955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.7490487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3138439361467991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.384672593197659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2268527854005802, "gear": 1, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.010686430029145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.7490487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 43.95540742551599, "y": 5.970139591604212, "z": null, "yaw": 4.210271036133182, "pitch": null, "roll": null}, "v": 1.2199844711480718, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "acceleration": 0.3435435693108093, "steering_wheel_angle": 7.08538993021451, "front_wheel_angle": 0.36296896062683853, "heading_rate": 0.1809943485364955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.7690487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3093792801096016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.384672593197659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2355521458557144, "gear": 1, "accelerator_pedal_position": 0.3138439361467991, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.938024480186795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.7690487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 43.95540742551599, "y": 5.970139591604212, "z": null, "yaw": 4.210271036133182, "pitch": null, "roll": null}, "v": 1.2199844711480718, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "acceleration": 0.3435435693108093, "steering_wheel_angle": 7.08538993021451, "front_wheel_angle": 0.36296896062683853, "heading_rate": 0.1809943485364955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.7890487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3093792801096016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.384672593197659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2436806466702974, "gear": 1, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.8651445594513545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.7890487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 43.95540742551599, "y": 5.970139591604212, "z": null, "yaw": 4.210271036133182, "pitch": null, "roll": null}, "v": 1.2199844711480718, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "acceleration": 0.3435435693108093, "steering_wheel_angle": 7.08538993021451, "front_wheel_angle": 0.36296896062683853, "heading_rate": 0.1809943485364955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.8090487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3093792801096016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.384672593197659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2517969864420655, "gear": 1, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.792046667822824, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.8090487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 43.95540742551599, "y": 5.970139591604212, "z": null, "yaw": 4.210271036133182, "pitch": null, "roll": null}, "v": 1.2199844711480718, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "acceleration": 0.3435435693108093, "steering_wheel_angle": 7.08538993021451, "front_wheel_angle": 0.36296896062683853, "heading_rate": 0.1809943485364955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.8290486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3093792801096016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.384672593197659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2558505933861681, "gear": 1, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.755415982923649, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.8290486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.8490486, "x": 47.89065927590672, "y": 10.85013853919351, "z": null, "yaw": 4.226072811269136, "pitch": null, "roll": null}, "v": 1.2639486763608245, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "acceleration": 0.40444740430222575, "steering_wheel_angle": 6.681991134955484, "front_wheel_angle": 0.33979871317852905, "heading_rate": 0.17453868277273563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.8490486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32522989232989297, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.730071888423394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2679931504038469, "gear": 1, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.6451969718864925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.8490486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.89065927590672, "y": 5.850138539193511, "z": null, "yaw": 4.226072811269136, "pitch": null, "roll": null}, "v": 1.2639486763608245, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "acceleration": 0.40444740430222575, "steering_wheel_angle": 6.681991134955484, "front_wheel_angle": 0.33979871317852905, "heading_rate": 0.17453868277273563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.8690486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3204410854576133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.730071888423394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.278053537759683, "gear": 1, "accelerator_pedal_position": 0.32522989232989297, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.5730386984479745, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.8690486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.89065927590672, "y": 5.850138539193511, "z": null, "yaw": 4.226072811269136, "pitch": null, "roll": null}, "v": 1.2639486763608245, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "acceleration": 0.40444740430222575, "steering_wheel_angle": 6.681991134955484, "front_wheel_angle": 0.33979871317852905, "heading_rate": 0.17453868277273563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.8890486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3204410854576133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.730071888423394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.287500363091348, "gear": 1, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.500671758301662, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.8890486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.89065927590672, "y": 5.850138539193511, "z": null, "yaw": 4.226072811269136, "pitch": null, "roll": null}, "v": 1.2639486763608245, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "acceleration": 0.40444740430222575, "steering_wheel_angle": 6.681991134955484, "front_wheel_angle": 0.33979871317852905, "heading_rate": 0.17453868277273563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.9090486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3204410854576133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.730071888423394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.292218415032407, "gear": 1, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.464410038213082, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.9090486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.89065927590672, "y": 5.850138539193511, "z": null, "yaw": 4.226072811269136, "pitch": null, "roll": null}, "v": 1.2639486763608245, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "acceleration": 0.40444740430222575, "steering_wheel_angle": 6.681991134955484, "front_wheel_angle": 0.33979871317852905, "heading_rate": 0.17453868277273563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.9290485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3204410854576133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.730071888423394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.306351107017601, "gear": 1, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.355311877885651, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.9290485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.89065927590672, "y": 5.850138539193511, "z": null, "yaw": 4.226072811269136, "pitch": null, "roll": null}, "v": 1.2639486763608245, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "acceleration": 0.40444740430222575, "steering_wheel_angle": 6.681991134955484, "front_wheel_angle": 0.33979871317852905, "heading_rate": 0.17453868277273563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.9490485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3204410854576133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.730071888423394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3157549979224281, "gear": 1, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.282318937615951, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.9490485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.9590485, "x": 47.82532810826379, "y": 10.724495040791501, "z": null, "yaw": 4.240767900659373, "pitch": null, "roll": null}, "v": 1.3157549979224281, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "acceleration": 0.46965692206838305, "steering_wheel_angle": 6.282318937615951, "front_wheel_angle": 0.3172112188282205, "heading_rate": 0.16873386660353465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.9690485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34164128410380723, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.867781719278015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.325144549966524, "gear": 1, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.209117330638456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.9690485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 43.82532810826379, "y": 5.724495040791501, "z": null, "yaw": 4.240767900659373, "pitch": null, "roll": null}, "v": 1.3157549979224281, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "acceleration": 0.46965692206838305, "steering_wheel_angle": 6.282318937615951, "front_wheel_angle": 0.3172112188282205, "heading_rate": 0.16873386660353465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.9890485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3352125560948148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.867781719278015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3371687595011985, "gear": 1, "accelerator_pedal_position": 0.34164128410380723, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.1376905230095975, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.9890485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 43.82532810826379, "y": 5.724495040791501, "z": null, "yaw": 4.240767900659373, "pitch": null, "roll": null}, "v": 1.3157549979224281, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "acceleration": 0.46965692206838305, "steering_wheel_angle": 6.282318937615951, "front_wheel_angle": 0.3172112188282205, "heading_rate": 0.16873386660353465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.0090485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3352125560948148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.867781719278015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3483712528184477, "gear": 1, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.066066157087064, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.0090485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 43.82532810826379, "y": 5.724495040791501, "z": null, "yaw": 4.240767900659373, "pitch": null, "roll": null}, "v": 1.3157549979224281, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "acceleration": 0.46965692206838305, "steering_wheel_angle": 6.282318937615951, "front_wheel_angle": 0.3172112188282205, "heading_rate": 0.16873386660353465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.0290484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3352125560948148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.867781719278015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.359556520775487, "gear": 1, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.994244232870858, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.0290484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 43.82532810826379, "y": 5.724495040791501, "z": null, "yaw": 4.240767900659373, "pitch": null, "roll": null}, "v": 1.3157549979224281, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "acceleration": 0.46965692206838305, "steering_wheel_angle": 6.282318937615951, "front_wheel_angle": 0.3172112188282205, "heading_rate": 0.16873386660353465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.0490484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3352125560948148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.867781719278015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3707245398338674, "gear": 1, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.922224750360978, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.0490484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.0690484, "x": 47.75905758466241, "y": 10.592495810161582, "z": null, "yaw": 4.254397465591249, "pitch": null, "roll": null}, "v": 1.3763020737434661, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "acceleration": 0.5573212979235135, "steering_wheel_angle": 5.886140924745911, "front_wheel_angle": 0.29516655480828474, "heading_rate": 0.16346176436170984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.0690484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3745018889060496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.6317026761136026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3818752867227013, "gear": 1, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.850007709557423, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.0690484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.75905758466241, "y": 5.592495810161582, "z": null, "yaw": 4.254397465591249, "pitch": null, "roll": null}, "v": 1.3763020737434661, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "acceleration": 0.5573212979235135, "steering_wheel_angle": 5.886140924745911, "front_wheel_angle": 0.29516655480828474, "heading_rate": 0.16346176436170984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.0890484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36245683028655185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.6317026761136026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3979179952481242, "gear": 1, "accelerator_pedal_position": 0.3745018889060496, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.7802108805419765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.0890484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.75905758466241, "y": 5.592495810161582, "z": null, "yaw": 4.254397465591249, "pitch": null, "roll": null}, "v": 1.3763020737434661, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "acceleration": 0.5573212979235135, "steering_wheel_angle": 5.886140924745911, "front_wheel_angle": 0.29516655480828474, "heading_rate": 0.16346176436170984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.1090484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36245683028655185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.6317026761136026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.412430681690742, "gear": 1, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.710230500352911, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.1090484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.75905758466241, "y": 5.592495810161582, "z": null, "yaw": 4.254397465591249, "pitch": null, "roll": null}, "v": 1.3763020737434661, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "acceleration": 0.5573212979235135, "steering_wheel_angle": 5.886140924745911, "front_wheel_angle": 0.29516655480828474, "heading_rate": 0.16346176436170984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.1290483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36245683028655185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.6317026761136026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4196785221997479, "gear": 1, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.675171478568271, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.1290483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.75905758466241, "y": 5.592495810161582, "z": null, "yaw": 4.254397465591249, "pitch": null, "roll": null}, "v": 1.3763020737434661, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "acceleration": 0.5573212979235135, "steering_wheel_angle": 5.886140924745911, "front_wheel_angle": 0.29516655480828474, "heading_rate": 0.16346176436170984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.1490483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36245683028655185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.6317026761136026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4413879600374433, "gear": 1, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.569719086453922, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.1490483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.75905758466241, "y": 5.592495810161582, "z": null, "yaw": 4.254397465591249, "pitch": null, "roll": null}, "v": 1.3763020737434661, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "acceleration": 0.5573212979235135, "steering_wheel_angle": 5.886140924745911, "front_wheel_angle": 0.29516655480828474, "heading_rate": 0.16346176436170984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.1690483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36245683028655185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.6317026761136026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4558324554099087, "gear": 1, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.499188052743999, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.1690483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.1790483, "x": 47.69119289521759, "y": 10.452761420004242, "z": null, "yaw": 4.267009681493933, "pitch": null, "roll": null}, "v": 1.4558324554099087, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "acceleration": 0.7213690851382051, "steering_wheel_angle": 5.499188052743999, "front_wheel_angle": 0.27395235975958354, "heading_rate": 0.15981054371545497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.1890483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4029483470438081, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5629049675973187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4702541246784606, "gear": 1, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.428473467860456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.1890483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 43.69119289521759, "y": 5.452761420004242, "z": null, "yaw": 4.267009681493933, "pitch": null, "roll": null}, "v": 1.4558324554099087, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "acceleration": 0.7213690851382051, "steering_wheel_angle": 5.499188052743999, "front_wheel_angle": 0.27395235975958354, "heading_rate": 0.15981054371545497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.2090483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3906061862891976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5629049675973187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4897123465422157, "gear": 1, "accelerator_pedal_position": 0.4029483470438081, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.359656103894982, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.2090483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 43.69119289521759, "y": 5.452761420004242, "z": null, "yaw": 4.267009681493933, "pitch": null, "roll": null}, "v": 1.4558324554099087, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "acceleration": 0.7213690851382051, "steering_wheel_angle": 5.499188052743999, "front_wheel_angle": 0.27395235975958354, "heading_rate": 0.15981054371545497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.2290483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3906061862891976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5629049675973187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.507597412425396, "gear": 1, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.290665791527113, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.2290483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 43.69119289521759, "y": 5.452761420004242, "z": null, "yaw": 4.267009681493933, "pitch": null, "roll": null}, "v": 1.4558324554099087, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "acceleration": 0.7213690851382051, "steering_wheel_angle": 5.499188052743999, "front_wheel_angle": 0.27395235975958354, "heading_rate": 0.15981054371545497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.2490482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3906061862891976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5629049675973187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.516529215366463, "gear": 1, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.256105779692279, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.2490482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 43.69119289521759, "y": 5.452761420004242, "z": null, "yaw": 4.267009681493933, "pitch": null, "roll": null}, "v": 1.4558324554099087, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "acceleration": 0.7213690851382051, "steering_wheel_angle": 5.499188052743999, "front_wheel_angle": 0.27395235975958354, "heading_rate": 0.15981054371545497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.2690482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3906061862891976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5629049675973187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5343713100879162, "gear": 1, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.186856044720812, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.2690482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.2890482, "x": 47.62098625293405, "y": 10.303612723936526, "z": null, "yaw": 4.278649254254395, "pitch": null, "roll": null}, "v": 1.5521846555925343, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "acceleration": 0.8895866594772888, "steering_wheel_angle": 5.117433361346948, "front_wheel_angle": 0.25331719555926807, "heading_rate": 0.1569637060322646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.2890482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3315622271498644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.111680195795285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5573902747410988, "gear": 1, "accelerator_pedal_position": 0.3315622271498644, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.082168635587574, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.2890482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 43.62098625293405, "y": 5.303612723936526, "z": null, "yaw": 4.278649254254395, "pitch": null, "roll": null}, "v": 1.5521846555925343, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "acceleration": 0.8895866594772888, "steering_wheel_angle": 5.117433361346948, "front_wheel_angle": 0.25331719555926807, "heading_rate": 0.1569637060322646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.3090482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3503992717653075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.111680195795285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5677888464410477, "gear": 1, "accelerator_pedal_position": 0.3315622271498644, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.011505805185807, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.3090482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 43.62098625293405, "y": 5.303612723936526, "z": null, "yaw": 4.278649254254395, "pitch": null, "roll": null}, "v": 1.5521846555925343, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "acceleration": 0.8895866594772888, "steering_wheel_angle": 5.117433361346948, "front_wheel_angle": 0.25331719555926807, "heading_rate": 0.1569637060322646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.3290482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3503992717653075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.111680195795285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5805241875561706, "gear": 1, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.940665136273344, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.3290482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 43.62098625293405, "y": 5.303612723936526, "z": null, "yaw": 4.278649254254395, "pitch": null, "roll": null}, "v": 1.5521846555925343, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "acceleration": 0.8895866594772888, "steering_wheel_angle": 5.117433361346948, "front_wheel_angle": 0.25331719555926807, "heading_rate": 0.1569637060322646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.3490481} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3503992717653075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.111680195795285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5868840742769792, "gear": 1, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.9051781123756015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.3490481} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 43.62098625293405, "y": 5.303612723936526, "z": null, "yaw": 4.278649254254395, "pitch": null, "roll": null}, "v": 1.5521846555925343, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "acceleration": 0.8895866594772888, "steering_wheel_angle": 5.117433361346948, "front_wheel_angle": 0.25331719555926807, "heading_rate": 0.1569637060322646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.369048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3503992717653075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.111680195795285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6059325528384985, "gear": 1, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.798450282916334, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.369048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 43.62098625293405, "y": 5.303612723936526, "z": null, "yaw": 4.278649254254395, "pitch": null, "roll": null}, "v": 1.5521846555925343, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "acceleration": 0.8895866594772888, "steering_wheel_angle": 5.117433361346948, "front_wheel_angle": 0.25331719555926807, "heading_rate": 0.1569637060322646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.389048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3503992717653075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.111680195795285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6186055157929324, "gear": 1, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.727076098471787, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.389048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.399048, "x": 47.54867757999823, "y": 10.145431621012044, "z": null, "yaw": 4.289340691627053, "pitch": null, "roll": null}, "v": 1.6186055157929324, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "acceleration": 0.6328663345859721, "steering_wheel_angle": 4.727076098471787, "front_wheel_angle": 0.2325065936915265, "heading_rate": 0.14971401324949746, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.409048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2413277498141269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6065919304736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.631257625425901, "gear": 1, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.655524075516545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.409048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 43.54867757999823, "y": 5.145431621012044, "z": null, "yaw": 4.289340691627053, "pitch": null, "roll": null}, "v": 1.6186055157929324, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "acceleration": 0.6328663345859721, "steering_wheel_angle": 4.727076098471787, "front_wheel_angle": 0.2325065936915265, "heading_rate": 0.14971401324949746, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.429048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27568397840541986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6065919304736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.63075888083252, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.618091757765735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.429048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 43.54867757999823, "y": 5.145431621012044, "z": null, "yaw": 4.289340691627053, "pitch": null, "roll": null}, "v": 1.6186055157929324, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "acceleration": 0.6328663345859721, "steering_wheel_angle": 4.727076098471787, "front_wheel_angle": 0.2325065936915265, "heading_rate": 0.14971401324949746, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.449048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27568397840541986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6065919304736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6357015890674385, "gear": 1, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.505503876744024, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.449048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 43.54867757999823, "y": 5.145431621012044, "z": null, "yaw": 4.289340691627053, "pitch": null, "roll": null}, "v": 1.6186055157929324, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "acceleration": 0.6328663345859721, "steering_wheel_angle": 4.727076098471787, "front_wheel_angle": 0.2325065936915265, "heading_rate": 0.14971401324949746, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.469048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27568397840541986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6065919304736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6389899200524516, "gear": 1, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.43020284958848, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.469048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 43.54867757999823, "y": 5.145431621012044, "z": null, "yaw": 4.289340691627053, "pitch": null, "roll": null}, "v": 1.6186055157929324, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "acceleration": 0.6328663345859721, "steering_wheel_angle": 4.727076098471787, "front_wheel_angle": 0.2325065936915265, "heading_rate": 0.14971401324949746, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.489048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27568397840541986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6065919304736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6422728102241353, "gear": 1, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.354707870586745, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.489048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.509048, "x": 47.47565661434227, "y": 9.981270551737543, "z": null, "yaw": 4.29907491384199, "pitch": null, "roll": null}, "v": 1.6439122164710418, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "acceleration": 0.1638047804556947, "steering_wheel_angle": 4.316887649143557, "front_wheel_angle": 0.21094134284121993, "heading_rate": 0.13750217972008974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.509048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22026173788040435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.575176725792542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6455502642755988, "gear": 1, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.279018939738822, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.509048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 43.47565661434227, "y": 4.981270551737543, "z": null, "yaw": 4.29907491384199, "pitch": null, "roll": null}, "v": 1.6439122164710418, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "acceleration": 0.1638047804556947, "steering_wheel_angle": 4.316887649143557, "front_wheel_angle": 0.21094134284121993, "heading_rate": 0.13750217972008974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.529048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23768574800009196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.575176725792542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6418973787280127, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.200802472231201, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.529048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 43.47565661434227, "y": 4.981270551737543, "z": null, "yaw": 4.29907491384199, "pitch": null, "roll": null}, "v": 1.6439122164710418, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "acceleration": 0.1638047804556947, "steering_wheel_angle": 4.316887649143557, "front_wheel_angle": 0.21094134284121993, "heading_rate": 0.13750217972008974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.549048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23768574800009196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.575176725792542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.641162206588427, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.161616970445664, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.549048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 43.47565661434227, "y": 4.981270551737543, "z": null, "yaw": 4.29907491384199, "pitch": null, "roll": null}, "v": 1.6439122164710418, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "acceleration": 0.1638047804556947, "steering_wheel_angle": 4.316887649143557, "front_wheel_angle": 0.21094134284121993, "heading_rate": 0.13750217972008974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.569048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23768574800009196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.575176725792542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6389603414058036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.043751392962147, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.569048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 43.47565661434227, "y": 4.981270551737543, "z": null, "yaw": 4.29907491384199, "pitch": null, "roll": null}, "v": 1.6439122164710418, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "acceleration": 0.1638047804556947, "steering_wheel_angle": 4.316887649143557, "front_wheel_angle": 0.21094134284121993, "heading_rate": 0.13750217972008974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.589048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23768574800009196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.575176725792542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6374954678669555, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.9649167812007127, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.589048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 43.47565661434227, "y": 4.981270551737543, "z": null, "yaw": 4.29907491384199, "pitch": null, "roll": null}, "v": 1.6439122164710418, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "acceleration": 0.1638047804556947, "steering_wheel_angle": 4.316887649143557, "front_wheel_angle": 0.21094134284121993, "heading_rate": 0.13750217972008974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.609048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23768574800009196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.575176725792542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6360330179025762, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.8858761213546744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.609048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.6190479, "x": 47.40383916445726, "y": 9.815697594816973, "z": null, "yaw": 4.307821929558391, "pitch": null, "roll": null}, "v": 1.6360330179025762, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30856769125180294, "steering_wheel_angle": 3.8858761213546744, "front_wheel_angle": 0.18860160825499162, "heading_rate": 0.12198039307054723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.6290479} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22893981980716782, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.064634965717654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6345729866478085, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.806629413424032, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.6290479} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 43.40383916445726, "y": 4.815697594816973, "z": null, "yaw": 4.307821929558391, "pitch": null, "roll": null}, "v": 1.6360330179025762, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30856769125180294, "steering_wheel_angle": 3.8858761213546744, "front_wheel_angle": 0.18860160825499162, "heading_rate": 0.12198039307054723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.6490479} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23164030447171352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.064634965717654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6320225801248607, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.725892547846874, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.6490479} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 43.40383916445726, "y": 4.815697594816973, "z": null, "yaw": 4.307821929558391, "pitch": null, "roll": null}, "v": 1.6360330179025762, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30856769125180294, "steering_wheel_angle": 3.8858761213546744, "front_wheel_angle": 0.18860160825499162, "heading_rate": 0.12198039307054723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.6690478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23164030447171352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.064634965717654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6309177380940767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.6854443325827204, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.6690478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 43.40383916445726, "y": 4.815697594816973, "z": null, "yaw": 4.307821929558391, "pitch": null, "roll": null}, "v": 1.6360330179025762, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30856769125180294, "steering_wheel_angle": 3.8858761213546744, "front_wheel_angle": 0.18860160825499162, "heading_rate": 0.12198039307054723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.6890478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23164030447171352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.064634965717654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6276086855567038, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.563780556887964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.6890478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 43.40383916445726, "y": 4.815697594816973, "z": null, "yaw": 4.307821929558391, "pitch": null, "roll": null}, "v": 1.6360330179025762, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30856769125180294, "steering_wheel_angle": 3.8858761213546744, "front_wheel_angle": 0.18860160825499162, "heading_rate": 0.12198039307054723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.7090478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23164030447171352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.064634965717654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.625407201863684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.4824054315062125, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.7090478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.7290478, "x": 47.33381696021285, "y": 9.650525604353186, "z": null, "yaw": 4.315566365104971, "pitch": null, "roll": null}, "v": 1.6243078224350473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30759915014198924, "steering_wheel_angle": 3.441638086339762, "front_wheel_angle": 0.16590537555816484, "heading_rate": 0.10624272760233394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.7290478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2272153489544632, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.547378008645228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6232093499631095, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.400817552856262, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.7290478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 43.33381696021285, "y": 4.650525604353186, "z": null, "yaw": 4.315566365104971, "pitch": null, "roll": null}, "v": 1.6243078224350473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30759915014198924, "steering_wheel_angle": 3.441638086339762, "front_wheel_angle": 0.16590537555816484, "heading_rate": 0.10624272760233394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.7490478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854972137299595, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.547378008645228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6204622304868899, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.3176699632216904, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.7490478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 43.33381696021285, "y": 4.650525604353186, "z": null, "yaw": 4.315566365104971, "pitch": null, "roll": null}, "v": 1.6243078224350473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30759915014198924, "steering_wheel_angle": 3.441638086339762, "front_wheel_angle": 0.16590537555816484, "heading_rate": 0.10624272760233394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.7690477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854972137299595, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.547378008645228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6178863655068105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2343025654953066, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.7690477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 43.33381696021285, "y": 4.650525604353186, "z": null, "yaw": 4.315566365104971, "pitch": null, "roll": null}, "v": 1.6243078224350473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30759915014198924, "steering_wheel_angle": 3.441638086339762, "front_wheel_angle": 0.16590537555816484, "heading_rate": 0.10624272760233394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.7890477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854972137299595, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.547378008645228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6153147422905216, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.1507153596771094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.7890477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 43.33381696021285, "y": 4.650525604353186, "z": null, "yaw": 4.315566365104971, "pitch": null, "roll": null}, "v": 1.6243078224350473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30759915014198924, "steering_wheel_angle": 3.441638086339762, "front_wheel_angle": 0.16590537555816484, "heading_rate": 0.10624272760233394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.8090477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854972137299595, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.547378008645228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6140305183335224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.1088393287335823, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.8090477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 43.33381696021285, "y": 4.650525604353186, "z": null, "yaw": 4.315566365104971, "pitch": null, "roll": null}, "v": 1.6243078224350473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30759915014198924, "steering_wheel_angle": 3.441638086339762, "front_wheel_angle": 0.16590537555816484, "heading_rate": 0.10624272760233394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.8290477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854972137299595, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.547378008645228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6101841826611536, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.982881523765279, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.8290477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.8390477, "x": 47.26554903788969, "y": 9.4861698697564, "z": null, "yaw": 4.322299161128889, "pitch": null, "roll": null}, "v": 1.6101841826611536, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30643614015397935, "steering_wheel_angle": 2.982881523765279, "front_wheel_angle": 0.14280312172477497, "heading_rate": 0.0904356304943579, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.8490477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02563242291431804, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.944461894923022, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.607625227076145, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.898634893671645, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.8490477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 43.26554903788969, "y": 4.4861698697564005, "z": null, "yaw": 4.322299161128889, "pitch": null, "roll": null}, "v": 1.6101841826611536, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30643614015397935, "steering_wheel_angle": 2.982881523765279, "front_wheel_angle": 0.14280312172477497, "heading_rate": 0.0904356304943579, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.8690476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.944461894923022, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5974037201307516, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02563242291431804, "steering_wheel_angle": 2.8097923504915783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.8690476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 43.26554903788969, "y": 4.4861698697564005, "z": null, "yaw": 4.322299161128889, "pitch": null, "roll": null}, "v": 1.6101841826611536, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30643614015397935, "steering_wheel_angle": 2.982881523765279, "front_wheel_angle": 0.14280312172477497, "heading_rate": 0.0904356304943579, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.8890476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.944461894923022, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5912984783380633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.7207066659707153, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.8890476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 43.26554903788969, "y": 4.4861698697564005, "z": null, "yaw": 4.322299161128889, "pitch": null, "roll": null}, "v": 1.6101841826611536, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30643614015397935, "steering_wheel_angle": 2.982881523765279, "front_wheel_angle": 0.14280312172477497, "heading_rate": 0.0904356304943579, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.9090476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.944461894923022, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5852032275300707, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.6313778401090566, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.9090476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 43.26554903788969, "y": 4.4861698697564005, "z": null, "yaw": 4.322299161128889, "pitch": null, "roll": null}, "v": 1.6101841826611536, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30643614015397935, "steering_wheel_angle": 2.982881523765279, "front_wheel_angle": 0.14280312172477497, "heading_rate": 0.0904356304943579, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.9290476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.944461894923022, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.579117936502159, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.5418058729066004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.9290476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.9490476, "x": 47.199256158678075, "y": 9.323704737092037, "z": null, "yaw": 4.32800145057792, "pitch": null, "roll": null}, "v": 1.5760790161881697, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3036442014620952, "steering_wheel_angle": 2.4969287113025747, "front_wheel_angle": 0.11868745548355597, "heading_rate": 0.07341568084728892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.9490476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.376398106328572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5730425741735488, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.451990764363349, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.9490476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 43.199256158678075, "y": 4.3237047370920365, "z": null, "yaw": 4.32800145057792, "pitch": null, "roll": null}, "v": 1.5760790161881697, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3036442014620952, "steering_wheel_angle": 2.4969287113025747, "front_wheel_angle": 0.11868745548355597, "heading_rate": 0.07341568084728892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.9690475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.376398106328572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5700086065924457, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.4062344123136383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.9690475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 43.199256158678075, "y": 4.3237047370920365, "z": null, "yaw": 4.32800145057792, "pitch": null, "roll": null}, "v": 1.5760790161881697, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3036442014620952, "steering_wheel_angle": 2.4969287113025747, "front_wheel_angle": 0.11868745548355597, "heading_rate": 0.07341568084728892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.9890475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.376398106328572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.554875750420189, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.176509932690653, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.9890475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 43.199256158678075, "y": 4.3237047370920365, "z": null, "yaw": 4.32800145057792, "pitch": null, "roll": null}, "v": 1.5760790161881697, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3036442014620952, "steering_wheel_angle": 2.4969287113025747, "front_wheel_angle": 0.11868745548355597, "heading_rate": 0.07341568084728892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.0190475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.376398106328572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.554875750420189, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.176509932690653, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.0190475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 43.199256158678075, "y": 4.3237047370920365, "z": null, "yaw": 4.32800145057792, "pitch": null, "roll": null}, "v": 1.5760790161881697, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3036442014620952, "steering_wheel_angle": 2.4969287113025747, "front_wheel_angle": 0.11868745548355597, "heading_rate": 0.07341568084728892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.0390475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.376398106328572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5367971778104033, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.8987665745193258, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.0390475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.0590475, "x": 47.135217579243886, "y": 9.164391114185152, "z": null, "yaw": 4.332637600100819, "pitch": null, "roll": null}, "v": 1.5428136137829265, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3009434191578857, "steering_wheel_angle": 1.991599085742949, "front_wheel_angle": 0.09398196123949185, "heading_rate": 0.056806665034460614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.0790474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.817832113785789, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5307904563871806, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.804852911624881, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.0790474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 43.135217579243886, "y": 4.164391114185152, "z": null, "yaw": 4.332637600100819, "pitch": null, "roll": null}, "v": 1.5428136137829265, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3009434191578857, "steering_wheel_angle": 1.991599085742949, "front_wheel_angle": 0.09398196123949185, "heading_rate": 0.056806665034460614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.1090474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.817832113785789, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5277907292168504, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7573846705150162, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.1090474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 43.135217579243886, "y": 4.164391114185152, "z": null, "yaw": 4.332637600100819, "pitch": null, "roll": null}, "v": 1.5428136137829265, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3009434191578857, "steering_wheel_angle": 1.991599085742949, "front_wheel_angle": 0.09398196123949185, "heading_rate": 0.056806665034460614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.1290474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.817832113785789, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5217985231941287, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.66225287100126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.1290474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 43.135217579243886, "y": 4.164391114185152, "z": null, "yaw": 4.332637600100819, "pitch": null, "roll": null}, "v": 1.5428136137829265, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3009434191578857, "steering_wheel_angle": 1.991599085742949, "front_wheel_angle": 0.09398196123949185, "heading_rate": 0.056806665034460614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.1490474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.817832113785789, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5158159566618234, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.566860648428803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.1490474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.1690474, "x": 47.07318573034666, "y": 9.008200158137457, "z": null, "yaw": 4.336196541187949, "pitch": null, "roll": null}, "v": 1.509842999802466, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29828840883064844, "steering_wheel_angle": 1.4712080027976449, "front_wheel_angle": 0.0689188714026977, "heading_rate": 0.040711616796282976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.1690474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.344018990872387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.509842999802466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.4712080027976449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.1690474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 43.07318573034666, "y": 4.008200158137457, "z": null, "yaw": 4.336196541187949, "pitch": null, "roll": null}, "v": 1.509842999802466, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29828840883064844, "steering_wheel_angle": 1.4712080027976449, "front_wheel_angle": 0.0689188714026977, "heading_rate": 0.040711616796282976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.1890473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.344018990872387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5038796229154696, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.3731699809869224, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.1890473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 43.07318573034666, "y": 4.008200158137457, "z": null, "yaw": 4.336196541187949, "pitch": null, "roll": null}, "v": 1.509842999802466, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29828840883064844, "steering_wheel_angle": 1.4712080027976449, "front_wheel_angle": 0.0689188714026977, "heading_rate": 0.040711616796282976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.2090473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.344018990872387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4979257964165467, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.2748598852939763, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.2090473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 43.07318573034666, "y": 4.008200158137457, "z": null, "yaw": 4.336196541187949, "pitch": null, "roll": null}, "v": 1.509842999802466, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29828840883064844, "steering_wheel_angle": 1.4712080027976449, "front_wheel_angle": 0.0689188714026977, "heading_rate": 0.040711616796282976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.2290473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.344018990872387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4919814908371312, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.176277715718806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.2290473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 43.07318573034666, "y": 4.008200158137457, "z": null, "yaw": 4.336196541187949, "pitch": null, "roll": null}, "v": 1.509842999802466, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29828840883064844, "steering_wheel_angle": 1.4712080027976449, "front_wheel_angle": 0.0689188714026977, "heading_rate": 0.040711616796282976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.2490473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.344018990872387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4860466768238023, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.0774234722614122, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.2490473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 43.07318573034666, "y": 4.008200158137457, "z": null, "yaw": 4.336196541187949, "pitch": null, "roll": null}, "v": 1.509842999802466, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29828840883064844, "steering_wheel_angle": 1.4712080027976449, "front_wheel_angle": 0.0689188714026977, "heading_rate": 0.040711616796282976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.2690473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.344018990872387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4801213251377123, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.9782971549217939, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.2690473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.2790473, "x": 47.01295574145203, "y": 8.855181052824962, "z": null, "yaw": 4.338657978803536, "pitch": null, "roll": null}, "v": 1.4771621885614308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29567819074122753, "steering_wheel_angle": 0.9286319685461512, "front_wheel_angle": 0.04317847912529549, "heading_rate": 0.024930189082734575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.2890472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22118489461391863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.772730599302511, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4742054066540184, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.8788987636999522, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.2890472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 43.01295574145203, "y": 3.855181052824962, "z": null, "yaw": 4.338657978803536, "pitch": null, "roll": null}, "v": 1.4771621885614308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29567819074122753, "steering_wheel_angle": 0.9286319685461512, "front_wheel_angle": 0.04317847912529549, "heading_rate": 0.024930189082734575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.3090472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21633144047396882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.772730599302511, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.470945952381077, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.7773579691465273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.3090472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 43.01295574145203, "y": 3.855181052824962, "z": null, "yaw": 4.338657978803536, "pitch": null, "roll": null}, "v": 1.4771621885614308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29567819074122753, "steering_wheel_angle": 0.9286319685461512, "front_wheel_angle": 0.04317847912529549, "heading_rate": 0.024930189082734575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.3290472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21633144047396882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.772730599302511, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4670852333955626, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.6755348083447223, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.3290472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 43.01295574145203, "y": 3.855181052824962, "z": null, "yaw": 4.338657978803536, "pitch": null, "roll": null}, "v": 1.4771621885614308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29567819074122753, "steering_wheel_angle": 0.9286319685461512, "front_wheel_angle": 0.04317847912529549, "heading_rate": 0.024930189082734575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.3490472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21633144047396882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.772730599302511, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.463230639790119, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5734292812945374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.3490472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 43.01295574145203, "y": 3.855181052824962, "z": null, "yaw": 4.338657978803536, "pitch": null, "roll": null}, "v": 1.4771621885614308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29567819074122753, "steering_wheel_angle": 0.9286319685461512, "front_wheel_angle": 0.04317847912529549, "heading_rate": 0.024930189082734575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.3690472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21633144047396882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.772730599302511, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.459382155905473, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4710413879959723, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.3690472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.3890471, "x": 46.95414466181501, "y": 8.704903901610184, "z": null, "yaw": 4.340003369734488, "pitch": null, "roll": null}, "v": 1.4555397661354288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29396294841478726, "steering_wheel_angle": 0.3683711284490268, "front_wheel_angle": 0.016999585774542164, "heading_rate": 0.009666389411307139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.3890471} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.06931267055211773, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.908166235322199, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4555397661354288, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3683711284490268, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.3890471} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.95414466181501, "y": 3.7049039016101837, "z": null, "yaw": 4.340003369734488, "pitch": null, "roll": null}, "v": 1.4555397661354288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29396294841478726, "steering_wheel_angle": 0.3683711284490268, "front_wheel_angle": 0.016999585774542164, "heading_rate": 0.009666389411307139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.4090471} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04373227780168002, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.908166235322199, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4385771849485365, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.06931267055211773, "steering_wheel_angle": 0.25407278807897565, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.4090471} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.95414466181501, "y": 3.7049039016101837, "z": null, "yaw": 4.340003369734488, "pitch": null, "roll": null}, "v": 1.4555397661354288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29396294841478726, "steering_wheel_angle": 0.3683711284490268, "front_wheel_angle": 0.016999585774542164, "heading_rate": 0.009666389411307139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.429047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04373227780168002, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.908166235322199, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4257325992549528, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "steering_wheel_angle": 0.13942652184051157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.429047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.95414466181501, "y": 3.7049039016101837, "z": null, "yaw": 4.340003369734488, "pitch": null, "roll": null}, "v": 1.4555397661354288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29396294841478726, "steering_wheel_angle": 0.3683711284490268, "front_wheel_angle": 0.016999585774542164, "heading_rate": 0.009666389411307139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.449047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04373227780168002, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.908166235322199, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4129081918986306, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "steering_wheel_angle": 0.02443232973363463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.449047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.95414466181501, "y": 3.7049039016101837, "z": null, "yaw": 4.340003369734488, "pitch": null, "roll": null}, "v": 1.4555397661354288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29396294841478726, "steering_wheel_angle": 0.3683711284490268, "front_wheel_angle": 0.016999585774542164, "heading_rate": 0.009666389411307139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.469047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04373227780168002, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.908166235322199, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.40010386541975, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "steering_wheel_angle": -0.09069378792663994, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.469047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.95414466181501, "y": 3.7049039016101837, "z": null, "yaw": 4.340003369734488, "pitch": null, "roll": null}, "v": 1.4555397661354288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29396294841478726, "steering_wheel_angle": 0.3683711284490268, "front_wheel_angle": 0.016999585774542164, "heading_rate": 0.009666389411307139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.489047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04373227780168002, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.908166235322199, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3873195228202613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "steering_wheel_angle": -0.2054876282453391, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.489047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.499047, "x": 46.89734261908269, "y": 8.559409600818748, "z": null, "yaw": 4.3401653135963665, "pitch": null, "roll": null}, "v": 1.380934815288877, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "acceleration": -0.6379747728186533, "steering_wheel_angle": -0.26275407620403385, "front_wheel_angle": -0.012108597070307666, "heading_rate": -0.006532031451610934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.509047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01685167223975377, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.2386055108951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3745550675606903, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "steering_wheel_angle": -0.3199335426956253, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.509047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.89734261908269, "y": 3.559409600818748, "z": null, "yaw": 4.3401653135963665, "pitch": null, "roll": null}, "v": 1.380934815288877, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "acceleration": -0.6379747728186533, "steering_wheel_angle": -0.26275407620403385, "front_wheel_angle": -0.012108597070307666, "heading_rate": -0.006532031451610934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.529047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.025480242057435945, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.2386055108951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3661096363199872, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01685167223975377, "steering_wheel_angle": -0.4361348332671461, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.529047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.89734261908269, "y": 3.559409600818748, "z": null, "yaw": 4.3401653135963665, "pitch": null, "roll": null}, "v": 1.380934815288877, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "acceleration": -0.6379747728186533, "steering_wheel_angle": -0.26275407620403385, "front_wheel_angle": -0.012108597070307666, "heading_rate": -0.006532031451610934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.549047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.025480242057435945, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.2386055108951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3562972294881814, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "steering_wheel_angle": -0.5519752319697921, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.549047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.89734261908269, "y": 3.559409600818748, "z": null, "yaw": 4.3401653135963665, "pitch": null, "roll": null}, "v": 1.380934815288877, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "acceleration": -0.6379747728186533, "steering_wheel_angle": -0.26275407620403385, "front_wheel_angle": -0.012108597070307666, "heading_rate": -0.006532031451610934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.569047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.025480242057435945, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.2386055108951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3464999622670824, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "steering_wheel_angle": -0.6674547388035639, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.569047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.89734261908269, "y": 3.559409600818748, "z": null, "yaw": 4.3401653135963665, "pitch": null, "roll": null}, "v": 1.380934815288877, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "acceleration": -0.6379747728186533, "steering_wheel_angle": -0.26275407620403385, "front_wheel_angle": -0.012108597070307666, "heading_rate": -0.006532031451610934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.589047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.025480242057435945, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.2386055108951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3367177729178894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "steering_wheel_angle": -0.7825733537684609, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.589047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.609047, "x": 46.84303533288678, "y": 8.420471320357247, "z": null, "yaw": 4.339067596757311, "pitch": null, "roll": null}, "v": 1.3269505999741287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "acceleration": -0.487797445405911, "steering_wheel_angle": -0.8973310768644835, "front_wheel_angle": -0.04170534335315007, "heading_rate": -0.021630093049970118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.609047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04482115805355611, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3269505999741287, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "steering_wheel_angle": -0.8973310768644835, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.609047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.84303533288678, "y": 3.4204713203572474, "z": null, "yaw": 4.339067596757311, "pitch": null, "roll": null}, "v": 1.3269505999741287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "acceleration": -0.487797445405911, "steering_wheel_angle": -0.8973310768644835, "front_wheel_angle": -0.04170534335315007, "heading_rate": -0.021630093049970118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.629047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038939658630541, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3141050181993843, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04482115805355611, "steering_wheel_angle": -1.016846869534795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.629047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.84303533288678, "y": 3.4204713203572474, "z": null, "yaw": 4.339067596757311, "pitch": null, "roll": null}, "v": 1.3269505999741287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "acceleration": -0.487797445405911, "steering_wheel_angle": -0.8973310768644835, "front_wheel_angle": -0.04170534335315007, "heading_rate": -0.021630093049970118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.649047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038939658630541, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3022197247703717, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "steering_wheel_angle": -1.1359686940567368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.649047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.84303533288678, "y": 3.4204713203572474, "z": null, "yaw": 4.339067596757311, "pitch": null, "roll": null}, "v": 1.3269505999741287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "acceleration": -0.487797445405911, "steering_wheel_angle": -0.8973310768644835, "front_wheel_angle": -0.04170534335315007, "heading_rate": -0.021630093049970118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.6690469} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038939658630541, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2903525147878825, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "steering_wheel_angle": -1.2546965504303087, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.6690469} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.84303533288678, "y": 3.4204713203572474, "z": null, "yaw": 4.339067596757311, "pitch": null, "roll": null}, "v": 1.3269505999741287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "acceleration": -0.487797445405911, "steering_wheel_angle": -0.8973310768644835, "front_wheel_angle": -0.04170534335315007, "heading_rate": -0.021630093049970118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.6890469} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038939658630541, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2785033044270606, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "steering_wheel_angle": -1.3730304386555103, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.6890469} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.84303533288678, "y": 3.4204713203572474, "z": null, "yaw": 4.339067596757311, "pitch": null, "roll": null}, "v": 1.3269505999741287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "acceleration": -0.487797445405911, "steering_wheel_angle": -0.8973310768644835, "front_wheel_angle": -0.04170534335315007, "heading_rate": -0.021630093049970118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.7090468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038939658630541, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2666720102466233, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "steering_wheel_angle": -1.490970358732342, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.7090468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.7190468, "x": 46.790895977750374, "y": 8.287736723280416, "z": null, "yaw": 4.336667922003423, "pitch": null, "roll": null}, "v": 1.2607630557529026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "acceleration": -0.5904506566594871, "steering_wheel_angle": -1.5497925807151194, "front_wheel_angle": -0.07267969967071386, "heading_rate": -0.03585686149638931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.7290468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02924620222434405, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2548585491863078, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "steering_wheel_angle": -1.608516310660804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.7290468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.790895977750374, "y": 3.2877367232804158, "z": null, "yaw": 4.336667922003423, "pitch": null, "roll": null}, "v": 1.2607630557529026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "acceleration": -0.5904506566594871, "steering_wheel_angle": -1.5497925807151194, "front_wheel_angle": -0.07267969967071386, "heading_rate": -0.03585686149638931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.7490468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03247158608050956, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2446132100833431, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02924620222434405, "steering_wheel_angle": -1.7256682944408959, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.7490468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.790895977750374, "y": 3.2877367232804158, "z": null, "yaw": 4.336667922003423, "pitch": null, "roll": null}, "v": 1.2607630557529026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "acceleration": -0.5904506566594871, "steering_wheel_angle": -1.5497925807151194, "front_wheel_angle": -0.07267969967071386, "heading_rate": -0.03585686149638931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.7690468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03247158608050956, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2338673532168754, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "steering_wheel_angle": -1.8424263100726175, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.7690468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.790895977750374, "y": 3.2877367232804158, "z": null, "yaw": 4.336667922003423, "pitch": null, "roll": null}, "v": 1.2607630557529026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "acceleration": -0.5904506566594871, "steering_wheel_angle": -1.5497925807151194, "front_wheel_angle": -0.07267969967071386, "heading_rate": -0.03585686149638931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.7890468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03247158608050956, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.223137551342444, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "steering_wheel_angle": -1.9587903575559695, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.7890468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.790895977750374, "y": 3.2877367232804158, "z": null, "yaw": 4.336667922003423, "pitch": null, "roll": null}, "v": 1.2607630557529026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "acceleration": -0.5904506566594871, "steering_wheel_angle": -1.5497925807151194, "front_wheel_angle": -0.07267969967071386, "heading_rate": -0.03585686149638931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.8090467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03247158608050956, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2124237344385458, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "steering_wheel_angle": -2.0747604368909514, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.8090467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.8290467, "x": 46.7408958853888, "y": 8.161562816098746, "z": null, "yaw": 4.332930317907047, "pitch": null, "roll": null}, "v": 1.2017258327938845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "acceleration": -0.5343004300558123, "steering_wheel_angle": -2.1903365480775627, "front_wheel_angle": -0.10365405598827762, "heading_rate": -0.04883273182851631, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.8290467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.018059128362835103, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2017258327938845, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "steering_wheel_angle": -2.1903365480775627, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.8290467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.7408958853888, "y": 3.161562816098746, "z": null, "yaw": 4.332930317907047, "pitch": null, "roll": null}, "v": 1.2017258327938845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "acceleration": -0.5343004300558123, "steering_wheel_angle": -2.1903365480775627, "front_wheel_angle": -0.10365405598827762, "heading_rate": -0.04883273182851631, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.8490467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022735120020248634, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1933489177239156, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018059128362835103, "steering_wheel_angle": -2.305518691115805, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.8490467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.7408958853888, "y": 3.161562816098746, "z": null, "yaw": 4.332930317907047, "pitch": null, "roll": null}, "v": 1.2017258327938845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "acceleration": -0.5343004300558123, "steering_wheel_angle": -2.1903365480775627, "front_wheel_angle": -0.10365405598827762, "heading_rate": -0.04883273182851631, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.8690467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022735120020248634, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.18423649797489, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "steering_wheel_angle": -2.4203068660056766, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.8690467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.7408958853888, "y": 3.161562816098746, "z": null, "yaw": 4.332930317907047, "pitch": null, "roll": null}, "v": 1.2017258327938845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "acceleration": -0.5343004300558123, "steering_wheel_angle": -2.1903365480775627, "front_wheel_angle": -0.10365405598827762, "heading_rate": -0.04883273182851631, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.8890467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022735120020248634, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1751375105026598, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "steering_wheel_angle": -2.534701072747179, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.8890467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.7408958853888, "y": 3.161562816098746, "z": null, "yaw": 4.332930317907047, "pitch": null, "roll": null}, "v": 1.2017258327938845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "acceleration": -0.5343004300558123, "steering_wheel_angle": -2.1903365480775627, "front_wheel_angle": -0.10365405598827762, "heading_rate": -0.04883273182851631, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.9090466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022735120020248634, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.166051902402741, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "steering_wheel_angle": -2.6487013113403113, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.9090466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.7408958853888, "y": 3.161562816098746, "z": null, "yaw": 4.332930317907047, "pitch": null, "roll": null}, "v": 1.2017258327938845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "acceleration": -0.5343004300558123, "steering_wheel_angle": -2.1903365480775627, "front_wheel_angle": -0.10365405598827762, "heading_rate": -0.04883273182851631, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.9290466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022735120020248634, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1569796209945655, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "steering_wheel_angle": -2.762307581785073, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.9290466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.9390466, "x": 46.692569220431736, "y": 8.041142232904061, "z": null, "yaw": 4.327847551997605, "pitch": null, "roll": null}, "v": 1.1524484613981087, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "acceleration": -0.4527847577936832, "steering_wheel_angle": -2.818962978951815, "front_wheel_angle": -0.1346284123058414, "heading_rate": -0.0609752036563806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.9490466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.017187229903971417, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1479206138201719, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "steering_wheel_angle": -2.875519884081465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.9490466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 42.692569220431736, "y": 3.041142232904061, "z": null, "yaw": 4.327847551997605, "pitch": null, "roll": null}, "v": 1.1524484613981087, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "acceleration": -0.4527847577936832, "steering_wheel_angle": -2.818962978951815, "front_wheel_angle": -0.1346284123058414, "heading_rate": -0.0609752036563806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.9690466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.019062507098743464, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1397621676312317, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.017187229903971417, "steering_wheel_angle": -2.988338218229487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.9690466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 42.692569220431736, "y": 3.041142232904061, "z": null, "yaw": 4.327847551997605, "pitch": null, "roll": null}, "v": 1.1524484613981087, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "acceleration": -0.4527847577936832, "steering_wheel_angle": -2.818962978951815, "front_wheel_angle": -0.1346284123058414, "heading_rate": -0.0609752036563806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.9890466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.019062507098743464, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.131315666427458, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "steering_wheel_angle": -3.100762584229139, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.9890466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 42.692569220431736, "y": 3.041142232904061, "z": null, "yaw": 4.327847551997605, "pitch": null, "roll": null}, "v": 1.1524484613981087, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "acceleration": -0.4527847577936832, "steering_wheel_angle": -2.818962978951815, "front_wheel_angle": -0.1346284123058414, "heading_rate": -0.0609752036563806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.0090466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.019062507098743464, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1228814366651136, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "steering_wheel_angle": -3.2127929820804213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.0090466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 42.692569220431736, "y": 3.041142232904061, "z": null, "yaw": 4.327847551997605, "pitch": null, "roll": null}, "v": 1.1524484613981087, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "acceleration": -0.4527847577936832, "steering_wheel_angle": -2.818962978951815, "front_wheel_angle": -0.1346284123058414, "heading_rate": -0.0609752036563806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.0290465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.019062507098743464, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1144594320715278, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "steering_wheel_angle": -3.324429411783333, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.0290465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.0490465, "x": 46.64556500541736, "y": 7.9259193043541565, "z": null, "yaw": 4.3214097260357205, "pitch": null, "roll": null}, "v": 1.1060496065648597, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "acceleration": -0.42003599444001355, "steering_wheel_angle": -3.435671873337875, "front_wheel_angle": -0.16560276862340548, "heading_rate": -0.07221009332774524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.0490465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1060496065648597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "steering_wheel_angle": -3.435671873337875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.0490465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.64556500541736, "y": 2.9259193043541565, "z": null, "yaw": 4.3214097260357205, "pitch": null, "roll": null}, "v": 1.1060496065648597, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "acceleration": -0.42003599444001355, "steering_wheel_angle": -3.435671873337875, "front_wheel_angle": -0.16560276862340548, "heading_rate": -0.07221009332774524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.0690465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1007008165918288, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5465203667440472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.0690465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.64556500541736, "y": 2.9259193043541565, "z": null, "yaw": 4.3214097260357205, "pitch": null, "roll": null}, "v": 1.1060496065648597, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "acceleration": -0.42003599444001355, "steering_wheel_angle": -3.435671873337875, "front_wheel_angle": -0.16560276862340548, "heading_rate": -0.07221009332774524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.0890465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0953597304618, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.6569748920018497, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.0890465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.64556500541736, "y": 2.9259193043541565, "z": null, "yaw": 4.3214097260357205, "pitch": null, "roll": null}, "v": 1.1060496065648597, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "acceleration": -0.42003599444001355, "steering_wheel_angle": -3.435671873337875, "front_wheel_angle": -0.16560276862340548, "heading_rate": -0.07221009332774524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.1090465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.090026325672174, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.7670354491112814, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.1090465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.64556500541736, "y": 2.9259193043541565, "z": null, "yaw": 4.3214097260357205, "pitch": null, "roll": null}, "v": 1.1060496065648597, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "acceleration": -0.42003599444001355, "steering_wheel_angle": -3.435671873337875, "front_wheel_angle": -0.16560276862340548, "heading_rate": -0.07221009332774524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.1290464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.084700579801949, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.876702038072344, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.1290464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.64556500541736, "y": 2.9259193043541565, "z": null, "yaw": 4.3214097260357205, "pitch": null, "roll": null}, "v": 1.1060496065648597, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "acceleration": -0.42003599444001355, "steering_wheel_angle": -3.435671873337875, "front_wheel_angle": -0.16560276862340548, "heading_rate": -0.07221009332774524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.1490464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0793824705113366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.985974658885036, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.1490464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.1590464, "x": 46.59937923100498, "y": 7.814950095671179, "z": null, "yaw": 4.313604198251807, "pitch": null, "roll": null}, "v": 1.0767262726243163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654297082928104, "steering_wheel_angle": -4.040463231235743, "front_wheel_angle": -0.19657712494096927, "heading_rate": -0.08376129872184102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.1690464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0740719755413881, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.094853311549359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.1690464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 42.59937923100498, "y": 2.814950095671179, "z": null, "yaw": 4.313604198251807, "pitch": null, "roll": null}, "v": 1.0767262726243163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654297082928104, "steering_wheel_angle": -4.040463231235743, "front_wheel_angle": -0.19657712494096927, "heading_rate": -0.08376129872184102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.1890464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0687690727136174, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.2033379960653106, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.1890464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 42.59937923100498, "y": 2.814950095671179, "z": null, "yaw": 4.313604198251807, "pitch": null, "roll": null}, "v": 1.0767262726243163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654297082928104, "steering_wheel_angle": -4.040463231235743, "front_wheel_angle": -0.19657712494096927, "heading_rate": -0.08376129872184102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.2090464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0634737399296286, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.311428712432893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.2090464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 42.59937923100498, "y": 2.814950095671179, "z": null, "yaw": 4.313604198251807, "pitch": null, "roll": null}, "v": 1.0767262726243163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654297082928104, "steering_wheel_angle": -4.040463231235743, "front_wheel_angle": -0.19657712494096927, "heading_rate": -0.08376129872184102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.2290463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0581859551707442, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.419125460652106, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.2290463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 42.59937923100498, "y": 2.814950095671179, "z": null, "yaw": 4.313604198251807, "pitch": null, "roll": null}, "v": 1.0767262726243163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654297082928104, "steering_wheel_angle": -4.040463231235743, "front_wheel_angle": -0.19657712494096927, "heading_rate": -0.08376129872184102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.2490463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0529056964976367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.526428240722948, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.2490463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.2690463, "x": 46.55351971062796, "y": 7.7073310108479145, "z": null, "yaw": 4.304415482793127, "pitch": null, "roll": null}, "v": 1.047632942049961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2633569949151806, "steering_wheel_angle": -4.6333370526454205, "front_wheel_angle": -0.22755148125853306, "heading_rate": -0.09476252584499364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.2690463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.047632942049961, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.6333370526454205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.2690463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 42.55351971062796, "y": 2.7073310108479145, "z": null, "yaw": 4.304415482793127, "pitch": null, "roll": null}, "v": 1.047632942049961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2633569949151806, "steering_wheel_angle": -4.6333370526454205, "front_wheel_angle": -0.22755148125853306, "heading_rate": -0.09476252584499364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.2890463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0423676700459898, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.739851896419523, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.2890463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 42.55351971062796, "y": 2.7073310108479145, "z": null, "yaw": 4.304415482793127, "pitch": null, "roll": null}, "v": 1.047632942049961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2633569949151806, "steering_wheel_angle": -4.6333370526454205, "front_wheel_angle": -0.22755148125853306, "heading_rate": -0.09476252584499364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.3090463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.03710985878225, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.845972772045256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.3090463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 42.55351971062796, "y": 2.7073310108479145, "z": null, "yaw": 4.304415482793127, "pitch": null, "roll": null}, "v": 1.047632942049961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2633569949151806, "steering_wheel_angle": -4.6333370526454205, "front_wheel_angle": -0.22755148125853306, "heading_rate": -0.09476252584499364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.3290462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0318594866331625, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.951699679522617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.3290462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 42.55351971062796, "y": 2.7073310108479145, "z": null, "yaw": 4.304415482793127, "pitch": null, "roll": null}, "v": 1.047632942049961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2633569949151806, "steering_wheel_angle": -4.6333370526454205, "front_wheel_angle": -0.22755148125853306, "heading_rate": -0.09476252584499364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.3490462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0266165320506824, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.057032618851611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.3490462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 42.55351971062796, "y": 2.7073310108479145, "z": null, "yaw": 4.304415482793127, "pitch": null, "roll": null}, "v": 1.047632942049961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2633569949151806, "steering_wheel_angle": -4.6333370526454205, "front_wheel_angle": -0.22755148125853306, "heading_rate": -0.09476252584499364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.3690462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0213809735639423, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.161971590032232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.3690462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.3790462, "x": 46.50788445645159, "y": 7.603088828733065, "z": null, "yaw": 4.2938251246562, "pitch": null, "roll": null}, "v": 1.0187659611678446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2613171388947346, "steering_wheel_angle": -5.2142933375669065, "front_wheel_angle": -0.25852583757609715, "heading_rate": -0.10523680231410065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.3890462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0161527897788971, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.266516593064485, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.3890462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 42.50788445645159, "y": 2.603088828733065, "z": null, "yaw": 4.2938251246562, "pitch": null, "roll": null}, "v": 1.0187659611678446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2613171388947346, "steering_wheel_angle": -5.2142933375669065, "front_wheel_angle": -0.25852583757609715, "heading_rate": -0.10523680231410065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.4090462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0109319593779706, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.370667627948367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.4090462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 42.50788445645159, "y": 2.603088828733065, "z": null, "yaw": 4.2938251246562, "pitch": null, "roll": null}, "v": 1.0187659611678446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2613171388947346, "steering_wheel_angle": -5.2142933375669065, "front_wheel_angle": -0.25852583757609715, "heading_rate": -0.10523680231410065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.4290462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0057184611197048, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.47442469468388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.4290462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 42.50788445645159, "y": 2.603088828733065, "z": null, "yaw": 4.2938251246562, "pitch": null, "roll": null}, "v": 1.0187659611678446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2613171388947346, "steering_wheel_angle": -5.2142933375669065, "front_wheel_angle": -0.25852583757609715, "heading_rate": -0.10523680231410065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.4490461} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0005122738384093, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.577787793271023, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.4490461} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 42.50788445645159, "y": 2.603088828733065, "z": null, "yaw": 4.2938251246562, "pitch": null, "roll": null}, "v": 1.0187659611678446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2613171388947346, "steering_wheel_angle": -5.2142933375669065, "front_wheel_angle": -0.25852583757609715, "heading_rate": -0.10523680231410065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.469046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9953133764438159, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.6807569237097955, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.469046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.489046, "x": 46.46238279099186, "y": 7.50225005188212, "z": null, "yaw": 4.281811547917533, "pitch": null, "roll": null}, "v": 0.9901217479207308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25930949815309257, "steering_wheel_angle": -5.783332086000198, "front_wheel_angle": -0.28950019389366066, "heading_rate": -0.1152055207419707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.489046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9901217479207308, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.783332086000198, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.489046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 42.46238279099186, "y": 2.50225005188212, "z": null, "yaw": 4.281811547917533, "pitch": null, "roll": null}, "v": 0.9901217479207308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25930949815309257, "steering_wheel_angle": -5.783332086000198, "front_wheel_angle": -0.28950019389366066, "heading_rate": -0.1152055207419707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.509046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9849373673286927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.885513280142231, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.509046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 42.46238279099186, "y": 2.50225005188212, "z": null, "yaw": 4.281811547917533, "pitch": null, "roll": null}, "v": 0.9901217479207308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25930949815309257, "steering_wheel_angle": -5.783332086000198, "front_wheel_angle": -0.28950019389366066, "heading_rate": -0.1152055207419707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.529046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.97976021380163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.987300506135893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.529046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 42.46238279099186, "y": 2.50225005188212, "z": null, "yaw": 4.281811547917533, "pitch": null, "roll": null}, "v": 0.9901217479207308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25930949815309257, "steering_wheel_angle": -5.783332086000198, "front_wheel_angle": -0.28950019389366066, "heading_rate": -0.1152055207419707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.549046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.974590266547521, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.088693763981186, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.549046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 42.46238279099186, "y": 2.50225005188212, "z": null, "yaw": 4.281811547917533, "pitch": null, "roll": null}, "v": 0.9901217479207308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25930949815309257, "steering_wheel_angle": -5.783332086000198, "front_wheel_angle": -0.28950019389366066, "heading_rate": -0.1152055207419707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.569046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9694275048480564, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.189693053678109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.569046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 42.46238279099186, "y": 2.50225005188212, "z": null, "yaw": 4.281811547917533, "pitch": null, "roll": null}, "v": 0.9901217479207308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25930949815309257, "steering_wheel_angle": -5.783332086000198, "front_wheel_angle": -0.28950019389366066, "heading_rate": -0.1152055207419707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.589046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642719080583022, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.290298375226661, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.589046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.599046, "x": 46.41693526074779, "y": 7.4048411884956975, "z": null, "yaw": 4.2683498745449375, "pitch": null, "roll": null}, "v": 0.961696790073006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573334466640176, "steering_wheel_angle": -6.3404532979453, "front_wheel_angle": -0.3204745502112247, "heading_rate": -0.12468855423001877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.609046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9591234556063658, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.390509728626844, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.609046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 42.41693526074779, "y": 2.4048411884956975, "z": null, "yaw": 4.2683498745449375, "pitch": null, "roll": null}, "v": 0.961696790073006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573334466640176, "steering_wheel_angle": -6.3404532979453, "front_wheel_angle": -0.3204745502112247, "heading_rate": -0.12468855423001877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.629046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9539821269930633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.490327113878657, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.629046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 42.41693526074779, "y": 2.4048411884956975, "z": null, "yaw": 4.2683498745449375, "pitch": null, "roll": null}, "v": 0.961696790073006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573334466640176, "steering_wheel_angle": -6.3404532979453, "front_wheel_angle": -0.3204745502112247, "heading_rate": -0.12468855423001877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.649046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9488479017915884, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.5897505309821, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.649046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 42.41693526074779, "y": 2.4048411884956975, "z": null, "yaw": 4.2683498745449375, "pitch": null, "roll": null}, "v": 0.961696790073006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573334466640176, "steering_wheel_angle": -6.3404532979453, "front_wheel_angle": -0.3204745502112247, "heading_rate": -0.12468855423001877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.669046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9437207596471837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.688779979937172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.669046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 42.41693526074779, "y": 2.4048411884956975, "z": null, "yaw": 4.2683498745449375, "pitch": null, "roll": null}, "v": 0.961696790073006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573334466640176, "steering_wheel_angle": -6.3404532979453, "front_wheel_angle": -0.3204745502112247, "heading_rate": -0.12468855423001877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.689046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9386006802768131, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.787415460743876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.689046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.709046, "x": 46.371473581054296, "y": 7.310888970568799, "z": null, "yaw": 4.253411710455373, "pitch": null, "roll": null}, "v": 0.9334876434688367, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25538837397853187, "steering_wheel_angle": -6.885656973402209, "front_wheel_angle": -0.35144890652878846, "heading_rate": -0.1337043584899913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.709046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9334876434688367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.885656973402209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.709046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 42.371473581054296, "y": 2.310888970568799, "z": null, "yaw": 4.253411710455373, "pitch": null, "roll": null}, "v": 0.9334876434688367, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25538837397853187, "steering_wheel_angle": -6.885656973402209, "front_wheel_angle": -0.35144890652878846, "heading_rate": -0.1337043584899913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.7290459} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9283816290826866, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.983504517912171, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.7290459} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 42.371473581054296, "y": 2.310888970568799, "z": null, "yaw": 4.253411710455373, "pitch": null, "roll": null}, "v": 0.9334876434688367, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25538837397853187, "steering_wheel_angle": -6.885656973402209, "front_wheel_angle": -0.35144890652878846, "heading_rate": -0.1337043584899913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.7490458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9232826170485451, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.080958094273765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.7490458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 42.371473581054296, "y": 2.310888970568799, "z": null, "yaw": 4.253411710455373, "pitch": null, "roll": null}, "v": 0.9334876434688367, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25538837397853187, "steering_wheel_angle": -6.885656973402209, "front_wheel_angle": -0.35144890652878846, "heading_rate": -0.1337043584899913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.7690458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9181905873670244, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.178017702486988, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.7690458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 42.371473581054296, "y": 2.310888970568799, "z": null, "yaw": 4.253411710455373, "pitch": null, "roll": null}, "v": 0.9334876434688367, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25538837397853187, "steering_wheel_angle": -6.885656973402209, "front_wheel_angle": -0.35144890652878846, "heading_rate": -0.1337043584899913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.7890458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9131055201088482, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.27468334255184, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.7890458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 42.371473581054296, "y": 2.310888970568799, "z": null, "yaw": 4.253411710455373, "pitch": null, "roll": null}, "v": 0.9334876434688367, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25538837397853187, "steering_wheel_angle": -6.885656973402209, "front_wheel_angle": -0.35144890652878846, "heading_rate": -0.1337043584899913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.8090458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9080273954145345, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.370955014468323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.8090458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.8190458, "x": 46.325940612849635, "y": 7.220420509127849, "z": null, "yaw": 4.236964894760447, "pitch": null, "roll": null}, "v": 0.9054909303417449, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25347368476639887, "steering_wheel_angle": -7.418943112370925, "front_wheel_angle": -0.38242326284635225, "heading_rate": -0.1422700616694297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.8290458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9029561934940808, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.466832718236436, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.8290458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 42.325940612849635, "y": 2.220420509127849, "z": null, "yaw": 4.236964894760447, "pitch": null, "roll": null}, "v": 0.9054909303417449, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25347368476639887, "steering_wheel_angle": -7.418943112370925, "front_wheel_angle": -0.38242326284635225, "heading_rate": -0.1422700616694297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.8490458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8978918946266506, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.56231645385618, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.8490458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 42.325940612849635, "y": 2.220420509127849, "z": null, "yaw": 4.236964894760447, "pitch": null, "roll": null}, "v": 0.9054909303417449, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25347368476639887, "steering_wheel_angle": -7.418943112370925, "front_wheel_angle": -0.38242326284635225, "heading_rate": -0.1422700616694297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.8690457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8928344791602614, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.657406221327552, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.8690457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 42.325940612849635, "y": 2.220420509127849, "z": null, "yaw": 4.236964894760447, "pitch": null, "roll": null}, "v": 0.9054909303417449, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25347368476639887, "steering_wheel_angle": -7.418943112370925, "front_wheel_angle": -0.38242326284635225, "heading_rate": -0.1422700616694297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.8890457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8877839275114745, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.752102020650556, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.8890457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 42.325940612849635, "y": 2.220420509127849, "z": null, "yaw": 4.236964894760447, "pitch": null, "roll": null}, "v": 0.9054909303417449, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25347368476639887, "steering_wheel_angle": -7.418943112370925, "front_wheel_angle": -0.38242326284635225, "heading_rate": -0.1422700616694297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.9090457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8827402201650871, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.846403851825188, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.9090457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.9290457, "x": 46.280290371822886, "y": 7.133463386665087, "z": null, "yaw": 4.218973207279142, "pitch": null, "roll": null}, "v": 0.8777033376738249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.251588798373329, "steering_wheel_angle": -7.940311714851451, "front_wheel_angle": -0.4133976191639163, "heading_rate": -0.15040154273641737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.9290457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2266695176080931, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8777033376738249, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.940311714851451, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.9290457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 42.280290371822886, "y": 2.1334633866650874, "z": null, "yaw": 4.218973207279142, "pitch": null, "roll": null}, "v": 0.8777033376738249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.251588798373329, "steering_wheel_angle": -7.940311714851451, "front_wheel_angle": -0.4133976191639163, "heading_rate": -0.15040154273641737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.9490457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22058919472955266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8760058248984476, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.033825609729345, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.9490457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 42.280290371822886, "y": 2.1334633866650874, "z": null, "yaw": 4.218973207279142, "pitch": null, "roll": null}, "v": 0.8777033376738249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.251588798373329, "steering_wheel_angle": -7.940311714851451, "front_wheel_angle": -0.4133976191639163, "heading_rate": -0.15040154273641737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.9690456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22058919472955266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.87355082011381, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.126945536458868, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.9690456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 42.280290371822886, "y": 2.1334633866650874, "z": null, "yaw": 4.218973207279142, "pitch": null, "roll": null}, "v": 0.8777033376738249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.251588798373329, "steering_wheel_angle": -7.940311714851451, "front_wheel_angle": -0.4133976191639163, "heading_rate": -0.15040154273641737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.9890456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22058919472955266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8710991276474346, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.21967149504002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.9890456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 42.280290371822886, "y": 2.1334633866650874, "z": null, "yaw": 4.218973207279142, "pitch": null, "roll": null}, "v": 0.8777033376738249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.251588798373329, "steering_wheel_angle": -7.940311714851451, "front_wheel_angle": -0.4133976191639163, "heading_rate": -0.15040154273641737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.0090456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22058919472955266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.868650740626798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.312003485472804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.0090456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 42.280290371822886, "y": 2.1334633866650874, "z": null, "yaw": 4.218973207279142, "pitch": null, "roll": null}, "v": 0.8777033376738249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.251588798373329, "steering_wheel_angle": -7.940311714851451, "front_wheel_angle": -0.4133976191639163, "heading_rate": -0.15040154273641737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.0290456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22058919472955266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8662056521983664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.403941507757217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.0290456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.0390456, "x": 46.23411116520935, "y": 7.049364719840734, "z": null, "yaw": 4.199396028363092, "pitch": null, "roll": null}, "v": 0.8649843428196743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2507311962742156, "steering_wheel_angle": -8.449762780843786, "front_wheel_angle": -0.4443719754814801, "heading_rate": -0.16087780686135567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.0490456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8637638555275292, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.49548556189326, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.0490456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 42.23411116520935, "y": 2.0493647198407343, "z": null, "yaw": 4.199396028363092, "pitch": null, "roll": null}, "v": 0.8649843428196743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2507311962742156, "steering_wheel_angle": -8.449762780843786, "front_wheel_angle": -0.4443719754814801, "heading_rate": -0.16087780686135567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.0690455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8587525596927117, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.586635647880934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.0690455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 42.23411116520935, "y": 2.0493647198407343, "z": null, "yaw": 4.199396028363092, "pitch": null, "roll": null}, "v": 0.8649843428196743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2507311962742156, "steering_wheel_angle": -8.449762780843786, "front_wheel_angle": -0.4443719754814801, "heading_rate": -0.16087780686135567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.0890455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8537479967881028, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.677391765720236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.0890455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 42.23411116520935, "y": 2.0493647198407343, "z": null, "yaw": 4.199396028363092, "pitch": null, "roll": null}, "v": 0.8649843428196743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2507311962742156, "steering_wheel_angle": -8.449762780843786, "front_wheel_angle": -0.4443719754814801, "heading_rate": -0.16087780686135567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.1090455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8487501477527668, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.76775391541117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.1090455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 42.23411116520935, "y": 2.0493647198407343, "z": null, "yaw": 4.199396028363092, "pitch": null, "roll": null}, "v": 0.8649843428196743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2507311962742156, "steering_wheel_angle": -8.449762780843786, "front_wheel_angle": -0.4443719754814801, "heading_rate": -0.16087780686135567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.1290455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8437589935916608, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.857722096953735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.1290455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.1490455, "x": 46.1872560304227, "y": 6.9679918604176265, "z": null, "yaw": 4.178187943827709, "pitch": null, "roll": null}, "v": 0.8387745153753405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24897415264519843, "steering_wheel_angle": -8.947296310347928, "front_wheel_angle": -0.4753463317990439, "heading_rate": -0.16864286365063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.1490455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2228953735421645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8387745153753405, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.947296310347928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.1490455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 42.1872560304227, "y": 1.9679918604176265, "z": null, "yaw": 4.178187943827709, "pitch": null, "roll": null}, "v": 0.8387745153753405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24897415264519843, "steering_wheel_angle": -8.947296310347928, "front_wheel_angle": -0.4753463317990439, "heading_rate": -0.16864286365063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.1690454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22062387077792323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8366576609090959, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.036476555593751, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.1690454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 42.1872560304227, "y": 1.9679918604176265, "z": null, "yaw": 4.178187943827709, "pitch": null, "roll": null}, "v": 0.8387745153753405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24897415264519843, "steering_wheel_angle": -8.947296310347928, "front_wheel_angle": -0.4753463317990439, "heading_rate": -0.16864286365063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.1890454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22062387077792323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8342597880983463, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.125262832691204, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.1890454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 42.1872560304227, "y": 1.9679918604176265, "z": null, "yaw": 4.178187943827709, "pitch": null, "roll": null}, "v": 0.8387745153753405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24897415264519843, "steering_wheel_angle": -8.947296310347928, "front_wheel_angle": -0.4753463317990439, "heading_rate": -0.16864286365063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.2090454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22062387077792323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8318651128484266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.213655141640286, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.2090454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 42.1872560304227, "y": 1.9679918604176265, "z": null, "yaw": 4.178187943827709, "pitch": null, "roll": null}, "v": 0.8387745153753405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24897415264519843, "steering_wheel_angle": -8.947296310347928, "front_wheel_angle": -0.4753463317990439, "heading_rate": -0.16864286365063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.2290454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22062387077792323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8294736286023684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.301653482441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.2290454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 42.1872560304227, "y": 1.9679918604176265, "z": null, "yaw": 4.178187943827709, "pitch": null, "roll": null}, "v": 0.8387745153753405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24897415264519843, "steering_wheel_angle": -8.947296310347928, "front_wheel_angle": -0.4753463317990439, "heading_rate": -0.16864286365063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.2490454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22062387077792323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8270853288211096, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.389257855093344, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.2490454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.2590454, "x": 46.139797136358645, "y": 6.889608830573974, "z": null, "yaw": 4.155298286254579, "pitch": null, "roll": null}, "v": 0.8258923710662042, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2481156006391638, "steering_wheel_angle": -9.432912303363878, "front_wheel_angle": -0.5063206881166078, "heading_rate": -0.17890187349623277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.2690454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22897113907058217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8247002069834327, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.476468259597318, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.2690454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 42.139797136358645, "y": 1.889608830573974, "z": null, "yaw": 4.155298286254579, "pitch": null, "roll": null}, "v": 0.8258923710662042, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2481156006391638, "steering_wheel_angle": -9.432912303363878, "front_wheel_angle": -0.5063206881166078, "heading_rate": -0.17890187349623277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.2890453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22631968839039798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8233613183175196, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.56328469595292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.2890453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 42.139797136358645, "y": 1.889608830573974, "z": null, "yaw": 4.155298286254579, "pitch": null, "roll": null}, "v": 0.8258923710662042, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2481156006391638, "steering_wheel_angle": -9.432912303363878, "front_wheel_angle": -0.5063206881166078, "heading_rate": -0.17890187349623277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.3090453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22631968839039798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8216928878702966, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.649707164160155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.3090453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 42.139797136358645, "y": 1.889608830573974, "z": null, "yaw": 4.155298286254579, "pitch": null, "roll": null}, "v": 0.8258923710662042, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2481156006391638, "steering_wheel_angle": -9.432912303363878, "front_wheel_angle": -0.5063206881166078, "heading_rate": -0.17890187349623277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.3290453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22631968839039798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8200266737704125, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.735735664219016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.3290453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 42.139797136358645, "y": 1.889608830573974, "z": null, "yaw": 4.155298286254579, "pitch": null, "roll": null}, "v": 0.8258923710662042, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2481156006391638, "steering_wheel_angle": -9.432912303363878, "front_wheel_angle": -0.5063206881166078, "heading_rate": -0.17890187349623277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.3490453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22631968839039798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8183626719635265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.82137019612951, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.3490453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.3690453, "x": 46.091168825634995, "y": 6.813426493996616, "z": null, "yaw": 4.130670602052144, "pitch": null, "roll": null}, "v": 0.8167008784051033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24750504716813185, "steering_wheel_angle": -9.906610759891635, "front_wheel_angle": -0.5372950444341715, "heading_rate": -0.1900611855914682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.3690453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23246593857643497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8167008784051033, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.906610759891635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.3690453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 42.091168825634995, "y": 1.8134264939966158, "z": null, "yaw": 4.130670602052144, "pitch": null, "roll": null}, "v": 0.8167008784051033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24750504716813185, "steering_wheel_angle": -9.906610759891635, "front_wheel_angle": -0.5372950444341715, "heading_rate": -0.1900611855914682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.3890452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23051470644041933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.815809315566737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.99145735550539, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.3890452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 42.091168825634995, "y": 1.8134264939966158, "z": null, "yaw": 4.130670602052144, "pitch": null, "roll": null}, "v": 0.8167008784051033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24750504716813185, "steering_wheel_angle": -9.906610759891635, "front_wheel_angle": -0.5372950444341715, "heading_rate": -0.1900611855914682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.4090452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23051470644041933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8146751117612538, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.075909982970774, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.4090452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 42.091168825634995, "y": 1.8134264939966158, "z": null, "yaw": 4.130670602052144, "pitch": null, "roll": null}, "v": 0.8167008784051033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24750504716813185, "steering_wheel_angle": -9.906610759891635, "front_wheel_angle": -0.5372950444341715, "heading_rate": -0.1900611855914682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.4290452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23051470644041933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8135424113927572, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.159968642287787, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.4290452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 42.091168825634995, "y": 1.8134264939966158, "z": null, "yaw": 4.130670602052144, "pitch": null, "roll": null}, "v": 0.8167008784051033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24750504716813185, "steering_wheel_angle": -9.906610759891635, "front_wheel_angle": -0.5372950444341715, "heading_rate": -0.1900611855914682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.4490452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23051470644041933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8124112119553409, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.243633333456428, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.4490452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 42.091168825634995, "y": 1.8134264939966158, "z": null, "yaw": 4.130670602052144, "pitch": null, "roll": null}, "v": 0.8167008784051033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24750504716813185, "steering_wheel_angle": -9.906610759891635, "front_wheel_angle": -0.5372950444341715, "heading_rate": -0.1900611855914682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.4690452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23051470644041933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8112815109484594, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.326904056476703, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.4690452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.4790452, "x": 46.04108412913952, "y": 6.739197153871549, "z": null, "yaw": 4.104242031335271, "pitch": null, "roll": null}, "v": 0.8107172215765106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24710848521243292, "steering_wheel_angle": -10.3683916799312, "front_wheel_angle": -0.5682694007517354, "heading_rate": -0.20221366705032978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.4890451} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24375855571687555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8101533058769125, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.4890451} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 42.04108412913952, "y": 1.7391971538715492, "z": null, "yaw": 4.104242031335271, "pitch": null, "roll": null}, "v": 0.8107172215765106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24710848521243292, "steering_wheel_angle": -10.3683916799312, "front_wheel_angle": -0.5682694007517354, "heading_rate": -0.20221366705032978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.5090451} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23960002199365085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8106815274455238, "gear": 1, "accelerator_pedal_position": 0.24375855571687555, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.5090451} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 42.04108412913952, "y": 1.7391971538715492, "z": null, "yaw": 4.104242031335271, "pitch": null, "roll": null}, "v": 0.8107172215765106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24710848521243292, "steering_wheel_angle": -10.3683916799312, "front_wheel_angle": -0.5682694007517354, "heading_rate": -0.20221366705032978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.529045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23960002199365085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8106894051505737, "gear": 1, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.529045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 42.04108412913952, "y": 1.7391971538715492, "z": null, "yaw": 4.104242031335271, "pitch": null, "roll": null}, "v": 0.8107172215765106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24710848521243292, "steering_wheel_angle": -10.3683916799312, "front_wheel_angle": -0.5682694007517354, "heading_rate": -0.20221366705032978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.549045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23960002199365085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.81069727242683, "gear": 1, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.549045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 42.04108412913952, "y": 1.7391971538715492, "z": null, "yaw": 4.104242031335271, "pitch": null, "roll": null}, "v": 0.8107172215765106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24710848521243292, "steering_wheel_angle": -10.3683916799312, "front_wheel_angle": -0.5682694007517354, "heading_rate": -0.20221366705032978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.569045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23960002199365085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8107051292880736, "gear": 1, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.569045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.589045, "x": 45.989226203077486, "y": 6.666662492234313, "z": null, "yaw": 4.076650089916402, "pitch": null, "roll": null}, "v": 0.8107129757480677, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "acceleration": 0.0003919333824514981, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2034701885403637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.589045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23432393975286758, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8107129757480677, "gear": 1, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.589045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.989226203077486, "y": 1.6666624922343134, "z": null, "yaw": 4.076650089916402, "pitch": null, "roll": null}, "v": 0.8107129757480677, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "acceleration": 0.0003919333824514981, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2034701885403637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.609045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2359727024773971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8100615198747682, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.609045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.989226203077486, "y": 1.6666624922343134, "z": null, "yaw": 4.076650089916402, "pitch": null, "roll": null}, "v": 0.8107129757480677, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "acceleration": 0.0003919333824514981, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2034701885403637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.629045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2359727024773971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8096169534293792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.629045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.989226203077486, "y": 1.6666624922343134, "z": null, "yaw": 4.076650089916402, "pitch": null, "roll": null}, "v": 0.8107129757480677, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "acceleration": 0.0003919333824514981, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2034701885403637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.649045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2359727024773971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8091729753468221, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.649045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.989226203077486, "y": 1.6666624922343134, "z": null, "yaw": 4.076650089916402, "pitch": null, "roll": null}, "v": 0.8107129757480677, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "acceleration": 0.0003919333824514981, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2034701885403637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.659045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2359727024773971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8089512066735828, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.659045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.989226203077486, "y": 1.6666624922343134, "z": null, "yaw": 4.076650089916402, "pitch": null, "roll": null}, "v": 0.8107129757480677, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "acceleration": 0.0003919333824514981, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2034701885403637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.679045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2359727024773971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8080655986040941, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.679045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.699045, "x": 45.93546611141185, "y": 6.595691571139081, "z": null, "yaw": 4.049042636466195, "pitch": null, "roll": null}, "v": 0.8080655986040941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24693298004667866, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20280575816520569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.699045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23424883703249288, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8078445627084646, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.699045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 41.93546611141185, "y": 1.5956915711390813, "z": null, "yaw": 4.049042636466195, "pitch": null, "roll": null}, "v": 0.8080655986040941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24693298004667866, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20280575816520569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.729045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23477878412992648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8071875176087375, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.729045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 41.93546611141185, "y": 1.5956915711390813, "z": null, "yaw": 4.049042636466195, "pitch": null, "roll": null}, "v": 0.8080655986040941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24693298004667866, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20280575816520569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.749045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23477878412992648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8065975629345642, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.749045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 41.93546611141185, "y": 1.5956915711390813, "z": null, "yaw": 4.049042636466195, "pitch": null, "roll": null}, "v": 0.8080655986040941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24693298004667866, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20280575816520569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.7690449} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23477878412992648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8060083883342463, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.7690449} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 41.93546611141185, "y": 1.5956915711390813, "z": null, "yaw": 4.049042636466195, "pitch": null, "roll": null}, "v": 0.8080655986040941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24693298004667866, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20280575816520569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.7890449} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23477878412992648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8054199926375181, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.7890449} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.8090448, "x": 45.87996140548262, "y": 6.526473307551362, "z": null, "yaw": 4.0214351830159885, "pitch": null, "roll": null}, "v": 0.8048323746762113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24671917024708007, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20199429380990475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.8090448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.248118041228851, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8048323746762113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.8090448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.87996140548262, "y": 1.5264733075513623, "z": null, "yaw": 4.0214351830159885, "pitch": null, "roll": null}, "v": 0.8048323746762113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24671917024708007, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20199429380990475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.8290448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393883015535284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8061906605630459, "gear": 1, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.8290448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.87996140548262, "y": 1.5264733075513623, "z": null, "yaw": 4.0214351830159885, "pitch": null, "roll": null}, "v": 0.8048323746762113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24671917024708007, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20199429380990475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.8490448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393883015535284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8064687477793561, "gear": 1, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.8490448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.87996140548262, "y": 1.5264733075513623, "z": null, "yaw": 4.0214351830159885, "pitch": null, "roll": null}, "v": 0.8048323746762113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24671917024708007, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20199429380990475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.8690448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393883015535284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8070243706493109, "gear": 1, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.8690448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.87996140548262, "y": 1.5264733075513623, "z": null, "yaw": 4.0214351830159885, "pitch": null, "roll": null}, "v": 0.8048323746762113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24671917024708007, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20199429380990475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.8890448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393883015535284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8078564276392179, "gear": 1, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.8890448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.87996140548262, "y": 1.5264733075513623, "z": null, "yaw": 4.0214351830159885, "pitch": null, "roll": null}, "v": 0.8048323746762113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24671917024708007, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20199429380990475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.9090447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393883015535284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8081334131093401, "gear": 1, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.9090447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.9190447, "x": 45.822561060291235, "y": 6.458808985154009, "z": null, "yaw": 3.993827729565783, "pitch": null, "roll": null}, "v": 0.8084102153261565, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "acceleration": 0.02766190694221049, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20289224898441025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.9290447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2393835745989912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8086785669512053, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.9290447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 41.822561060291235, "y": 1.4588089851540094, "z": null, "yaw": 3.993827729565783, "pitch": null, "roll": null}, "v": 0.8084102153261565, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "acceleration": 0.02766190694221049, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20289224898441025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.9490447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408189234655255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8086703049777021, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.9490447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 41.822561060291235, "y": 1.4588089851540094, "z": null, "yaw": 3.993827729565783, "pitch": null, "roll": null}, "v": 0.8084102153261565, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "acceleration": 0.02766190694221049, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20289224898441025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.9690447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408189234655255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8088331566727303, "gear": 1, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.9690447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 41.822561060291235, "y": 1.4588089851540094, "z": null, "yaw": 3.993827729565783, "pitch": null, "roll": null}, "v": 0.8084102153261565, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "acceleration": 0.02766190694221049, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20289224898441025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.9890447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408189234655255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8089957929020929, "gear": 1, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.9890447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 41.822561060291235, "y": 1.4588089851540094, "z": null, "yaw": 3.993827729565783, "pitch": null, "roll": null}, "v": 0.8084102153261565, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "acceleration": 0.02766190694221049, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20289224898441025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.0090446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408189234655255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8091582139402913, "gear": 1, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.0090446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.0290446, "x": 45.763155053355334, "y": 6.392575848835998, "z": null, "yaw": 3.966220276115581, "pitch": null, "roll": null}, "v": 0.8093204200615057, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "acceleration": 0.00810225523317365, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20312068930133123, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.0290446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25343192396151953, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8093204200615057, "gear": 1, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.0290446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 41.763155053355334, "y": 1.3925758488359978, "z": null, "yaw": 3.966220276115581, "pitch": null, "roll": null}, "v": 0.8093204200615057, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "acceleration": 0.00810225523317365, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20312068930133123, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.0490446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494933704690853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8110585147709254, "gear": 1, "accelerator_pedal_position": 0.25343192396151953, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.0490446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 41.763155053355334, "y": 1.3925758488359978, "z": null, "yaw": 3.966220276115581, "pitch": null, "roll": null}, "v": 0.8093204200615057, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "acceleration": 0.00810225523317365, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20312068930133123, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.0690446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494933704690853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8123021524311164, "gear": 1, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.0690446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 41.763155053355334, "y": 1.3925758488359978, "z": null, "yaw": 3.966220276115581, "pitch": null, "roll": null}, "v": 0.8093204200615057, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "acceleration": 0.00810225523317365, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20312068930133123, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.0890446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494933704690853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8135441430702153, "gear": 1, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.0890446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 41.763155053355334, "y": 1.3925758488359978, "z": null, "yaw": 3.966220276115581, "pitch": null, "roll": null}, "v": 0.8093204200615057, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "acceleration": 0.00810225523317365, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20312068930133123, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.1090446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494933704690853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.814784488252655, "gear": 1, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.1090446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 41.763155053355334, "y": 1.3925758488359978, "z": null, "yaw": 3.966220276115581, "pitch": null, "roll": null}, "v": 0.8093204200615057, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "acceleration": 0.00810225523317365, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20312068930133123, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.1290445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494933704690853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8166419242182065, "gear": 1, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.1290445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.1390445, "x": 45.70163966210803, "y": 6.327689734849988, "z": null, "yaw": 3.938612822665379, "pitch": null, "roll": null}, "v": 0.8166419242182065, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "acceleration": 0.0618324288969645, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20495821734852743, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.1390445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24805827541920122, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8166419242182065, "gear": 1, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.1390445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 41.70163966210803, "y": 1.3276897348499883, "z": null, "yaw": 3.938612822665379, "pitch": null, "roll": null}, "v": 0.8166419242182065, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "acceleration": 0.0618324288969645, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20495821734852743, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.1690445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24853099893765457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.818226764888689, "gear": 1, "accelerator_pedal_position": 0.24805827541920122, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.1690445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 41.70163966210803, "y": 1.3276897348499883, "z": null, "yaw": 3.938612822665379, "pitch": null, "roll": null}, "v": 0.8166419242182065, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "acceleration": 0.0618324288969645, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20495821734852743, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.1890445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24853099893765457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8198970294214624, "gear": 1, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.1890445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 41.70163966210803, "y": 1.3276897348499883, "z": null, "yaw": 3.938612822665379, "pitch": null, "roll": null}, "v": 0.8166419242182065, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "acceleration": 0.0618324288969645, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20495821734852743, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.2090445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24853099893765457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8204530452264697, "gear": 1, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.2090445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 41.70163966210803, "y": 1.3276897348499883, "z": null, "yaw": 3.938612822665379, "pitch": null, "roll": null}, "v": 0.8166419242182065, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "acceleration": 0.0618324288969645, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20495821734852743, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.2290444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24853099893765457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8221188780913448, "gear": 1, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.2290444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.2490444, "x": 45.63785070163154, "y": 6.2640210525144, "z": null, "yaw": 3.911005369215177, "pitch": null, "roll": null}, "v": 0.8226734181409311, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "acceleration": 0.05541715692413757, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2064719826913165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.2490444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2602766526996217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8226734181409311, "gear": 1, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.2490444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 41.63785070163154, "y": 1.2640210525143996, "z": null, "yaw": 3.911005369215177, "pitch": null, "roll": null}, "v": 0.8226734181409311, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "acceleration": 0.05541715692413757, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2064719826913165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.2690444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566261560006241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8252491117303219, "gear": 1, "accelerator_pedal_position": 0.2602766526996217, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.2690444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 41.63785070163154, "y": 1.2640210525143996, "z": null, "yaw": 3.911005369215177, "pitch": null, "roll": null}, "v": 0.8226734181409311, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "acceleration": 0.05541715692413757, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2064719826913165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.2890444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566261560006241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8273652208942538, "gear": 1, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.2890444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 41.63785070163154, "y": 1.2640210525143996, "z": null, "yaw": 3.911005369215177, "pitch": null, "roll": null}, "v": 0.8226734181409311, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "acceleration": 0.05541715692413757, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2064719826913165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.3090444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566261560006241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8294785150157422, "gear": 1, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.3090444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 41.63785070163154, "y": 1.2640210525143996, "z": null, "yaw": 3.911005369215177, "pitch": null, "roll": null}, "v": 0.8226734181409311, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "acceleration": 0.05541715692413757, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2064719826913165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.3290443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566261560006241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8315889960538044, "gear": 1, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.3290443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 41.63785070163154, "y": 1.2640210525143996, "z": null, "yaw": 3.911005369215177, "pitch": null, "roll": null}, "v": 0.8226734181409311, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "acceleration": 0.05541715692413757, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2064719826913165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.3490443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566261560006241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8336966659719801, "gear": 1, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.3490443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.3590443, "x": 45.57160770546459, "y": 6.20145866495381, "z": null, "yaw": 3.883397915764975, "pitch": null, "roll": null}, "v": 0.8347494473759478, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "acceleration": 0.10520793623615865, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20950278646376203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.3690443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26634333805121624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8358015267383094, "gear": 1, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.3690443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 41.57160770546459, "y": 1.20145866495381, "z": null, "yaw": 3.883397915764975, "pitch": null, "roll": null}, "v": 0.8347494473759478, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "acceleration": 0.10520793623615865, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20950278646376203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.3890443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2633469143123746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8391178227346616, "gear": 1, "accelerator_pedal_position": 0.26634333805121624, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.3890443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 41.57160770546459, "y": 1.20145866495381, "z": null, "yaw": 3.883397915764975, "pitch": null, "roll": null}, "v": 0.8347494473759478, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "acceleration": 0.10520793623615865, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20950278646376203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.4090443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2633469143123746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8420552640670611, "gear": 1, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.4090443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 41.57160770546459, "y": 1.20145866495381, "z": null, "yaw": 3.883397915764975, "pitch": null, "roll": null}, "v": 0.8347494473759478, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "acceleration": 0.10520793623615865, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20950278646376203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.4190443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2633469143123746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8449887807378914, "gear": 1, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.4190443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 41.57160770546459, "y": 1.20145866495381, "z": null, "yaw": 3.883397915764975, "pitch": null, "roll": null}, "v": 0.8347494473759478, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "acceleration": 0.10520793623615865, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20950278646376203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.4490442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2633469143123746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8479183745497636, "gear": 1, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.4490442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.4690442, "x": 45.50254291420188, "y": 6.1397492913788705, "z": null, "yaw": 3.855790462314773, "pitch": null, "roll": null}, "v": 0.8508440473166797, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "acceleration": 0.146136656157965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21354215845161106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.4690442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719109214614162, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8508440473166797, "gear": 1, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.4690442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 41.50254291420188, "y": 1.1397492913788705, "z": null, "yaw": 3.855790462314773, "pitch": null, "roll": null}, "v": 0.8508440473166797, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "acceleration": 0.146136656157965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21354215845161106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.4890442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26928846848425825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8548359428643778, "gear": 1, "accelerator_pedal_position": 0.2719109214614162, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.4890442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 41.50254291420188, "y": 1.1397492913788705, "z": null, "yaw": 3.855790462314773, "pitch": null, "roll": null}, "v": 0.8508440473166797, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "acceleration": 0.146136656157965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21354215845161106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.4990442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26928846848425825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8566659797242905, "gear": 1, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.4990442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 41.50254291420188, "y": 1.1397492913788705, "z": null, "yaw": 3.855790462314773, "pitch": null, "roll": null}, "v": 0.8508440473166797, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "acceleration": 0.146136656157965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21354215845161106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.5290442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26928846848425825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8621487215485044, "gear": 1, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.5290442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 41.50254291420188, "y": 1.1397492913788705, "z": null, "yaw": 3.855790462314773, "pitch": null, "roll": null}, "v": 0.8508440473166797, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "acceleration": 0.146136656157965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21354215845161106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.5490441} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26928846848425825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8657977437025117, "gear": 1, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.5490441} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 41.50254291420188, "y": 1.1397492913788705, "z": null, "yaw": 3.855790462314773, "pitch": null, "roll": null}, "v": 0.8508440473166797, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "acceleration": 0.146136656157965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21354215845161106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.569044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26928846848425825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8694418560929251, "gear": 1, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.569044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.579044, "x": 45.43026560860449, "y": 6.078673615162425, "z": null, "yaw": 3.828183008864571, "pitch": null, "roll": null}, "v": 0.8712620715310322, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "acceleration": 0.1818988484771769, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21866660984290964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.589044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2765304033951706, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.873081060015804, "gear": 1, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.589044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 41.43026560860449, "y": 1.0786736151624252, "z": null, "yaw": 3.828183008864571, "pitch": null, "roll": null}, "v": 0.8712620715310322, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "acceleration": 0.1818988484771769, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21866660984290964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.609044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2743359233594503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8776202931203205, "gear": 1, "accelerator_pedal_position": 0.2765304033951706, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.609044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 41.43026560860449, "y": 1.0786736151624252, "z": null, "yaw": 3.828183008864571, "pitch": null, "roll": null}, "v": 0.8712620715310322, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "acceleration": 0.1818988484771769, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21866660984290964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.629044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2743359233594503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8818791803410174, "gear": 1, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.629044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 41.43026560860449, "y": 1.0786736151624252, "z": null, "yaw": 3.828183008864571, "pitch": null, "roll": null}, "v": 0.8712620715310322, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "acceleration": 0.1818988484771769, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21866660984290964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.649044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2743359233594503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8861323101064769, "gear": 1, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.649044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 41.43026560860449, "y": 1.0786736151624252, "z": null, "yaw": 3.828183008864571, "pitch": null, "roll": null}, "v": 0.8712620715310322, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "acceleration": 0.1818988484771769, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21866660984290964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.669044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2743359233594503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8903796829668241, "gear": 1, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.669044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.689044, "x": 45.35447594427345, "y": 6.018136331816677, "z": null, "yaw": 3.800575555414369, "pitch": null, "roll": null}, "v": 0.8946212995008026, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "acceleration": 0.21186498332631903, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2245292352866197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.689044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22673518493925648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8946212995008026, "gear": 1, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.689044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 41.35447594427345, "y": 1.0181363318166774, "z": null, "yaw": 3.800575555414369, "pitch": null, "roll": null}, "v": 0.8946212995008026, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "acceleration": 0.21186498332631903, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2245292352866197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.709044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168944840638662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8929090882196996, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.709044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 41.35447594427345, "y": 1.0181363318166774, "z": null, "yaw": 3.800575555414369, "pitch": null, "roll": null}, "v": 0.8946212995008026, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "acceleration": 0.21186498332631903, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2245292352866197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.729044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168944840638662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8930678489693209, "gear": 1, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.729044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 41.35447594427345, "y": 1.0181363318166774, "z": null, "yaw": 3.800575555414369, "pitch": null, "roll": null}, "v": 0.8946212995008026, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "acceleration": 0.21186498332631903, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2245292352866197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.749044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168944840638662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8932263943201756, "gear": 1, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.749044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 41.35447594427345, "y": 1.0181363318166774, "z": null, "yaw": 3.800575555414369, "pitch": null, "roll": null}, "v": 0.8946212995008026, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "acceleration": 0.21186498332631903, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2245292352866197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.769044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168944840638662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.893384724554455, "gear": 1, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.769044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 41.35447594427345, "y": 1.0181363318166774, "z": null, "yaw": 3.800575555414369, "pitch": null, "roll": null}, "v": 0.8946212995008026, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "acceleration": 0.21186498332631903, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2245292352866197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.789044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168944840638662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8935428399540083, "gear": 1, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.789044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.799044, "x": 45.27603238275469, "y": 5.958943243443391, "z": null, "yaw": 3.772968101964167, "pitch": null, "roll": null}, "v": 0.8936218171787471, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "acceleration": 0.007892362159600486, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.224278388362252, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.809044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25129052142379393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8937007408003431, "gear": 1, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.809044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 41.27603238275469, "y": 0.9589432434433913, "z": null, "yaw": 3.772968101964167, "pitch": null, "roll": null}, "v": 0.8936218171787471, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "acceleration": 0.007892362159600486, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.224278388362252, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.8290439} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24828679177195906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8950581541667205, "gear": 1, "accelerator_pedal_position": 0.25129052142379393, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.8290439} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 41.27603238275469, "y": 0.9589432434433913, "z": null, "yaw": 3.772968101964167, "pitch": null, "roll": null}, "v": 0.8936218171787471, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "acceleration": 0.007892362159600486, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.224278388362252, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.8490438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24828679177195906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8960383862326239, "gear": 1, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.8490438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 41.27603238275469, "y": 0.9589432434433913, "z": null, "yaw": 3.772968101964167, "pitch": null, "roll": null}, "v": 0.8936218171787471, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "acceleration": 0.007892362159600486, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.224278388362252, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.8690438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24828679177195906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8970172872844945, "gear": 1, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.8690438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 41.27603238275469, "y": 0.9589432434433913, "z": null, "yaw": 3.772968101964167, "pitch": null, "roll": null}, "v": 0.8936218171787471, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "acceleration": 0.007892362159600486, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.224278388362252, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.8890438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24828679177195906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8979948587464889, "gear": 1, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.8890438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 41.27603238275469, "y": 0.9589432434433913, "z": null, "yaw": 3.772968101964167, "pitch": null, "roll": null}, "v": 0.8936218171787471, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "acceleration": 0.007892362159600486, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.224278388362252, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.8990438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24828679177195906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8989711020423907, "gear": 1, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.8990438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.9090438, "x": 45.1957521013195, "y": 5.901774237694393, "z": null, "yaw": 3.745360648513965, "pitch": null, "roll": null}, "v": 0.8989711020423907, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "acceleration": 0.04876240304955143, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22562093502466032, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.9190438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24828643723161659, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8994587260728862, "gear": 1, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.9190438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 41.1957521013195, "y": 0.9017742376943927, "z": null, "yaw": 3.745360648513965, "pitch": null, "roll": null}, "v": 0.8989711020423907, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "acceleration": 0.04876240304955143, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22562093502466032, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.9490438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2483047157947018, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9014069627611467, "gear": 1, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.9490438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 41.1957521013195, "y": 0.9017742376943927, "z": null, "yaw": 3.745360648513965, "pitch": null, "roll": null}, "v": 0.8989711020423907, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "acceleration": 0.04876240304955143, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22562093502466032, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.9590437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2483047157947018, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9014069627611467, "gear": 1, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.9590437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 41.1957521013195, "y": 0.9017742376943927, "z": null, "yaw": 3.745360648513965, "pitch": null, "roll": null}, "v": 0.8989711020423907, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "acceleration": 0.04876240304955143, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22562093502466032, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.9890437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2483047157947018, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9028672322113167, "gear": 1, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.9890437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 41.1957521013195, "y": 0.9017742376943927, "z": null, "yaw": 3.745360648513965, "pitch": null, "roll": null}, "v": 0.8989711020423907, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "acceleration": 0.04876240304955143, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22562093502466032, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.0090437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2483047157947018, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9038390897592111, "gear": 1, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.0090437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.0190437, "x": 45.1134295898405, "y": 5.846510878115508, "z": null, "yaw": 3.717753195063763, "pitch": null, "roll": null}, "v": 0.9043245224414828, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "acceleration": 0.048510219175921965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22696451961072664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.0290437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547083847326999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9056946258210362, "gear": 1, "accelerator_pedal_position": 0.2547083847326999, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.0290437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 41.1134295898405, "y": 0.8465108781155077, "z": null, "yaw": 3.717753195063763, "pitch": null, "roll": null}, "v": 0.9043245224414828, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "acceleration": 0.048510219175921965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22696451961072664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.0490437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25272544734024904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9065790242783953, "gear": 1, "accelerator_pedal_position": 0.2547083847326999, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.0490437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 41.1134295898405, "y": 0.8465108781155077, "z": null, "yaw": 3.717753195063763, "pitch": null, "roll": null}, "v": 0.9043245224414828, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "acceleration": 0.048510219175921965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22696451961072664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.0690436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25272544734024904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9080982313021982, "gear": 1, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.0690436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 41.1134295898405, "y": 0.8465108781155077, "z": null, "yaw": 3.717753195063763, "pitch": null, "roll": null}, "v": 0.9043245224414828, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "acceleration": 0.048510219175921965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22696451961072664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.0890436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25272544734024904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9096153682198448, "gear": 1, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.0890436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 41.1134295898405, "y": 0.8465108781155077, "z": null, "yaw": 3.717753195063763, "pitch": null, "roll": null}, "v": 0.9043245224414828, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "acceleration": 0.048510219175921965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22696451961072664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.1090436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25272544734024904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9111304369317408, "gear": 1, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.1090436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.1290436, "x": 45.02899345633571, "y": 5.793150406444788, "z": null, "yaw": 3.690145741613561, "pitch": null, "roll": null}, "v": 0.9126434393394649, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "acceleration": 0.07557269343588946, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.229052375165428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.1290436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606582217404537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9126434393394649, "gear": 1, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.1290436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 41.02899345633571, "y": 0.7931504064447878, "z": null, "yaw": 3.690145741613561, "pitch": null, "roll": null}, "v": 0.9126434393394649, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "acceleration": 0.07557269343588946, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.229052375165428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.1490436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582075830286109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9151456356496324, "gear": 1, "accelerator_pedal_position": 0.2606582217404537, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.1490436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 41.02899345633571, "y": 0.7931504064447878, "z": null, "yaw": 3.690145741613561, "pitch": null, "roll": null}, "v": 0.9126434393394649, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "acceleration": 0.07557269343588946, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.229052375165428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.1690435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582075830286109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9173381904201684, "gear": 1, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.1690435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 41.02899345633571, "y": 0.7931504064447878, "z": null, "yaw": 3.690145741613561, "pitch": null, "roll": null}, "v": 0.9126434393394649, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "acceleration": 0.07557269343588946, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.229052375165428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.1890435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582075830286109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9195277496150125, "gear": 1, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.1890435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 41.02899345633571, "y": 0.7931504064447878, "z": null, "yaw": 3.690145741613561, "pitch": null, "roll": null}, "v": 0.9126434393394649, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "acceleration": 0.07557269343588946, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.229052375165428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.2090435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582075830286109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9217143154098545, "gear": 1, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.2090435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 41.02899345633571, "y": 0.7931504064447878, "z": null, "yaw": 3.690145741613561, "pitch": null, "roll": null}, "v": 0.9126434393394649, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "acceleration": 0.07557269343588946, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.229052375165428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.2290435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582075830286109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9238978899852707, "gear": 1, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.2290435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.2390435, "x": 44.94213976589536, "y": 5.741561929978398, "z": null, "yaw": 3.662538288163359, "pitch": null, "roll": null}, "v": 0.9249885562484543, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "acceleration": 0.10899192782448935, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.23215071371453921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.2490435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.265506808087436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.739273416278579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9260784755266992, "gear": 1, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.2490435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 40.94213976589536, "y": 0.7415619299783982, "z": null, "yaw": 3.662538288163359, "pitch": null, "roll": null}, "v": 0.9249885562484543, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "acceleration": 0.10899192782448935, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.23215071371453921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.2690434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632680044718622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.739273416278579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9291681646401061, "gear": 1, "accelerator_pedal_position": 0.265506808087436, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.2690434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 40.94213976589536, "y": 0.7415619299783982, "z": null, "yaw": 3.662538288163359, "pitch": null, "roll": null}, "v": 0.9249885562484543, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "acceleration": 0.10899192782448935, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.23215071371453921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.2890434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632680044718622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.739273416278579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9333752695097702, "gear": 1, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.2890434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 40.94213976589536, "y": 0.7415619299783982, "z": null, "yaw": 3.662538288163359, "pitch": null, "roll": null}, "v": 0.9249885562484543, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "acceleration": 0.10899192782448935, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.23215071371453921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.3090434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632680044718622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.739273416278579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9347757132151335, "gear": 1, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.3090434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 40.94213976589536, "y": 0.7415619299783982, "z": null, "yaw": 3.662538288163359, "pitch": null, "roll": null}, "v": 0.9249885562484543, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "acceleration": 0.10899192782448935, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.23215071371453921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.3290434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632680044718622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.739273416278579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9389712743316225, "gear": 1, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.3290434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.3490434, "x": 44.852593124490916, "y": 5.691666016377232, "z": null, "yaw": 3.634930834713157, "pitch": null, "roll": null}, "v": 0.9403678722685461, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "acceleration": 0.13956371698376274, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2360105659974541, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.3490434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2661325095401085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.287477308667842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9403678722685461, "gear": 1, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.3490434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 40.852593124490916, "y": 0.6916660163772317, "z": null, "yaw": 3.634930834713157, "pitch": null, "roll": null}, "v": 0.9403678722685461, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "acceleration": 0.13956371698376274, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2360105659974541, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.3690434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2652901433970356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.287477308667842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9435161260058479, "gear": 1, "accelerator_pedal_position": 0.2661325095401085, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.3690434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 40.852593124490916, "y": 0.6916660163772317, "z": null, "yaw": 3.634930834713157, "pitch": null, "roll": null}, "v": 0.9403678722685461, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "acceleration": 0.13956371698376274, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2360105659974541, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.3890433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2652901433970356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.287477308667842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9480725462821832, "gear": 1, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.3890433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 40.852593124490916, "y": 0.6916660163772317, "z": null, "yaw": 3.634930834713157, "pitch": null, "roll": null}, "v": 0.9403678722685461, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "acceleration": 0.13956371698376274, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2360105659974541, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.4090433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2652901433970356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.287477308667842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9495892598160555, "gear": 1, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.4090433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 40.852593124490916, "y": 0.6916660163772317, "z": null, "yaw": 3.634930834713157, "pitch": null, "roll": null}, "v": 0.9403678722685461, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "acceleration": 0.13956371698376274, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2360105659974541, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.4290433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2652901433970356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.287477308667842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9541331244002744, "gear": 1, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.4290433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 40.852593124490916, "y": 0.6916660163772317, "z": null, "yaw": 3.634930834713157, "pitch": null, "roll": null}, "v": 0.9403678722685461, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "acceleration": 0.13956371698376274, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2360105659974541, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.4490433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2652901433970356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.287477308667842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9556456547984812, "gear": 1, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.4490433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.4590433, "x": 44.760131135677895, "y": 5.643441244225822, "z": null, "yaw": 3.607323381262955, "pitch": null, "roll": null}, "v": 0.9571571400716431, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "acceleration": 0.15104404131998905, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.24022428353688124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.4690433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26367004289287854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.77675029398072, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958667580484843, "gear": 1, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.4690433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 40.760131135677895, "y": 0.6434412442258219, "z": null, "yaw": 3.607323381262955, "pitch": null, "roll": null}, "v": 0.9571571400716431, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "acceleration": 0.15104404131998905, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.24022428353688124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.4890432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26423422686764086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.77675029398072, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9629243381070963, "gear": 1, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.371163342156517, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.4890432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 40.760131135677895, "y": 0.6434412442258219, "z": null, "yaw": 3.607323381262955, "pitch": null, "roll": null}, "v": 0.9571571400716431, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "acceleration": 0.15104404131998905, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.24022428353688124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.5090432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26423422686764086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.77675029398072, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643647927891784, "gear": 1, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.371163342156517, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.5090432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 40.760131135677895, "y": 0.6434412442258219, "z": null, "yaw": 3.607323381262955, "pitch": null, "roll": null}, "v": 0.9571571400716431, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "acceleration": 0.15104404131998905, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.24022428353688124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.5290432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26423422686764086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.77675029398072, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9701166358416422, "gear": 1, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.371163342156517, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.5290432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 40.760131135677895, "y": 0.6434412442258219, "z": null, "yaw": 3.607323381262955, "pitch": null, "roll": null}, "v": 0.9571571400716431, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "acceleration": 0.15104404131998905, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.24022428353688124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.5490432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26423422686764086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.77675029398072, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9715521040742353, "gear": 1, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.371163342156517, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.5490432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.5690432, "x": 44.664761838447504, "y": 5.596996580001491, "z": null, "yaw": 3.5798462131568063, "pitch": null, "roll": null}, "v": 0.9729865758523326, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "acceleration": 0.14334756036225021, "steering_wheel_angle": -10.371163342156517, "front_wheel_angle": -0.5684577577200296, "heading_rate": -0.24278859556149876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.5690432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2686552064778588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.301026046312987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9729865758523326, "gear": 1, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.371163342156517, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.5690432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 40.664761838447504, "y": 0.5969965800014911, "z": null, "yaw": 3.5798462131568063, "pitch": null, "roll": null}, "v": 0.9729865758523326, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "acceleration": 0.14334756036225021, "steering_wheel_angle": -10.371163342156517, "front_wheel_angle": -0.5684577577200296, "heading_rate": -0.24278859556149876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.5890431} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26732849961225996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.301026046312987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9812750488766923, "gear": 1, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.181589577548653, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.5890431} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 40.664761838447504, "y": 0.5969965800014911, "z": null, "yaw": 3.5798462131568063, "pitch": null, "roll": null}, "v": 0.9729865758523326, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "acceleration": 0.14334756036225021, "steering_wheel_angle": -10.371163342156517, "front_wheel_angle": -0.5684577577200296, "heading_rate": -0.24278859556149876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.619043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26732849961225996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.301026046312987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9828961525058654, "gear": 1, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.143430039129338, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.619043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 40.664761838447504, "y": 0.5969965800014911, "z": null, "yaw": 3.5798462131568063, "pitch": null, "roll": null}, "v": 0.9729865758523326, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "acceleration": 0.14334756036225021, "steering_wheel_angle": -10.371163342156517, "front_wheel_angle": -0.5684577577200296, "heading_rate": -0.24278859556149876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.639043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26732849961225996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.301026046312987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.987752690653109, "gear": 1, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.028461852875921, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.639043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 40.664761838447504, "y": 0.5969965800014911, "z": null, "yaw": 3.5798462131568063, "pitch": null, "roll": null}, "v": 0.9729865758523326, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "acceleration": 0.14334756036225021, "steering_wheel_angle": -10.371163342156517, "front_wheel_angle": -0.5684577577200296, "heading_rate": -0.24278859556149876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.659043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26732849961225996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.301026046312987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.987752690653109, "gear": 1, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.028461852875921, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.659043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.679043, "x": 44.5664719893891, "y": 5.552400128904712, "z": null, "yaw": 3.553164642202006, "pitch": null, "roll": null}, "v": 0.9909847414243078, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "acceleration": 0.16143337792805124, "steering_wheel_angle": -9.951408419544075, "front_wheel_angle": -0.5402652346207498, "heading_rate": -0.23218084149383345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.689043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27132067500720286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.82670596325937, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9925990752035884, "gear": 1, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.91275931012928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.689043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 40.5664719893891, "y": 0.5524001289047122, "z": null, "yaw": 3.553164642202006, "pitch": null, "roll": null}, "v": 0.9909847414243078, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "acceleration": 0.16143337792805124, "steering_wheel_angle": -9.951408419544075, "front_wheel_angle": -0.5402652346207498, "heading_rate": -0.23218084149383345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.709043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013578877381467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.82670596325937, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9963232084275102, "gear": 1, "accelerator_pedal_position": 0.27132067500720286, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.837030284061488, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.709043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 40.5664719893891, "y": 0.5524001289047122, "z": null, "yaw": 3.553164642202006, "pitch": null, "roll": null}, "v": 0.9909847414243078, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "acceleration": 0.16143337792805124, "steering_wheel_angle": -9.951408419544075, "front_wheel_angle": -0.5402652346207498, "heading_rate": -0.23218084149383345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.729043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013578877381467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.82670596325937, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9998940775816316, "gear": 1, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.760989938301302, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.729043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 40.5664719893891, "y": 0.5524001289047122, "z": null, "yaw": 3.553164642202006, "pitch": null, "roll": null}, "v": 0.9909847414243078, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "acceleration": 0.16143337792805124, "steering_wheel_angle": -9.951408419544075, "front_wheel_angle": -0.5402652346207498, "heading_rate": -0.23218084149383345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.749043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013578877381467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.82670596325937, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0034599506945152, "gear": 1, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.684638272848728, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.749043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 40.5664719893891, "y": 0.5524001289047122, "z": null, "yaw": 3.553164642202006, "pitch": null, "roll": null}, "v": 0.9909847414243078, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "acceleration": 0.16143337792805124, "steering_wheel_angle": -9.951408419544075, "front_wheel_angle": -0.5402652346207498, "heading_rate": -0.23218084149383345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.769043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013578877381467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.82670596325937, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0070208296717758, "gear": 1, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.607975287703761, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.769043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.789043, "x": 44.465171754817135, "y": 5.509569202683146, "z": null, "yaw": 3.528119265893799, "pitch": null, "roll": null}, "v": 1.0105767164377166, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "acceleration": 0.17760719101639544, "steering_wheel_angle": -9.531000982866397, "front_wheel_angle": -0.5126710390551783, "heading_rate": -0.22219689642905405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.789043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2782128005169336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.410993061939616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0105767164377166, "gear": 1, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.531000982866397, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.789043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 40.465171754817135, "y": 0.5095692026831458, "z": null, "yaw": 3.528119265893799, "pitch": null, "roll": null}, "v": 1.0105767164377166, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "acceleration": 0.17760719101639544, "steering_wheel_angle": -9.531000982866397, "front_wheel_angle": -0.5126710390551783, "heading_rate": -0.22219689642905405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.809043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757573199458391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.410993061939616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0151368847612348, "gear": 1, "accelerator_pedal_position": 0.2782128005169336, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.455235348116336, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.809043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 40.465171754817135, "y": 0.5095692026831458, "z": null, "yaw": 3.528119265893799, "pitch": null, "roll": null}, "v": 1.0105767164377166, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "acceleration": 0.17760719101639544, "steering_wheel_angle": -9.531000982866397, "front_wheel_angle": -0.5126710390551783, "heading_rate": -0.22219689642905405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.829043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757573199458391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.410993061939616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0193838184590833, "gear": 1, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.379170495155188, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.829043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 40.465171754817135, "y": 0.5095692026831458, "z": null, "yaw": 3.528119265893799, "pitch": null, "roll": null}, "v": 1.0105767164377166, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "acceleration": 0.17760719101639544, "steering_wheel_angle": -9.531000982866397, "front_wheel_angle": -0.5126710390551783, "heading_rate": -0.22219689642905405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.849043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757573199458391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.410993061939616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0236247774281586, "gear": 1, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.302806423982954, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.849043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 40.465171754817135, "y": 0.5095692026831458, "z": null, "yaw": 3.528119265893799, "pitch": null, "roll": null}, "v": 1.0105767164377166, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "acceleration": 0.17760719101639544, "steering_wheel_angle": -9.531000982866397, "front_wheel_angle": -0.5126710390551783, "heading_rate": -0.22219689642905405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.8690429} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757573199458391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.410993061939616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0278597628821493, "gear": 1, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.226143134599633, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.8690429} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 40.465171754817135, "y": 0.5095692026831458, "z": null, "yaw": 3.528119265893799, "pitch": null, "roll": null}, "v": 1.0105767164377166, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "acceleration": 0.17760719101639544, "steering_wheel_angle": -9.531000982866397, "front_wheel_angle": -0.5126710390551783, "heading_rate": -0.22219689642905405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.8890429} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757573199458391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.410993061939616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0320887760634152, "gear": 1, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.149180627005226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.8890429} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.8990428, "x": 44.36065005336615, "y": 5.468345031478225, "z": null, "yaw": 3.5046211102439786, "pitch": null, "roll": null}, "v": 1.0342010434478308, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "acceleration": 0.21107747950641675, "steering_wheel_angle": -9.110587166378867, "front_wheel_angle": -0.48567713217275116, "heading_rate": -0.21324262001767078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.9090428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2771148709558317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9817977494742465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.036311818242895, "gear": 1, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.071918901199734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.9090428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 40.36065005336615, "y": 0.4683450314782247, "z": null, "yaw": 3.5046211102439786, "pitch": null, "roll": null}, "v": 1.0342010434478308, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "acceleration": 0.21107747950641675, "steering_wheel_angle": -9.110587166378867, "front_wheel_angle": -0.48567713217275116, "heading_rate": -0.21324262001767078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.9290428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27677385010837485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9817977494742465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0406985245507048, "gear": 1, "accelerator_pedal_position": 0.2771148709558317, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.995871830953616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.9290428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 40.36065005336615, "y": 0.4683450314782247, "z": null, "yaw": 3.5046211102439786, "pitch": null, "roll": null}, "v": 1.0342010434478308, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "acceleration": 0.21107747950641675, "steering_wheel_angle": -9.110587166378867, "front_wheel_angle": -0.48567713217275116, "heading_rate": -0.21324262001767078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.9490428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27677385010837485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9817977494742465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.045036409676609, "gear": 1, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.919537087467353, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.9490428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 40.36065005336615, "y": 0.4683450314782247, "z": null, "yaw": 3.5046211102439786, "pitch": null, "roll": null}, "v": 1.0342010434478308, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "acceleration": 0.21107747950641675, "steering_wheel_angle": -9.110587166378867, "front_wheel_angle": -0.48567713217275116, "heading_rate": -0.21324262001767078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.9690428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27677385010837485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9817977494742465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0493681476799024, "gear": 1, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.842914670740935, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.9690428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 40.36065005336615, "y": 0.4683450314782247, "z": null, "yaw": 3.5046211102439786, "pitch": null, "roll": null}, "v": 1.0342010434478308, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "acceleration": 0.21107747950641675, "steering_wheel_angle": -9.110587166378867, "front_wheel_angle": -0.48567713217275116, "heading_rate": -0.21324262001767078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.9890428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27677385010837485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9817977494742465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0558542314807853, "gear": 1, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.72744165832603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.9890428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.0090427, "x": 44.25278184086044, "y": 5.428620407035806, "z": null, "yaw": 3.482597729519573, "pitch": null, "roll": null}, "v": 1.0580131871810048, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "acceleration": 0.21574198477580342, "steering_wheel_angle": -8.68880681756765, "front_wheel_angle": -0.4591613035706175, "heading_rate": -0.20433071109134654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.0090427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28294591794006574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.614240195427049, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0580131871810048, "gear": 1, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.68880681756765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.0090427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 40.25278184086044, "y": 0.4286204070358064, "z": null, "yaw": 3.482597729519573, "pitch": null, "roll": null}, "v": 1.0580131871810048, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "acceleration": 0.21574198477580342, "steering_wheel_angle": -8.68880681756765, "front_wheel_angle": -0.4591613035706175, "heading_rate": -0.20433071109134654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.0290427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811015859457472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.614240195427049, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.063097724979321, "gear": 1, "accelerator_pedal_position": 0.28294591794006574, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.612572949810364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.0290427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 40.25278184086044, "y": 0.4286204070358064, "z": null, "yaw": 3.482597729519573, "pitch": null, "roll": null}, "v": 1.0580131871810048, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "acceleration": 0.21574198477580342, "steering_wheel_angle": -8.68880681756765, "front_wheel_angle": -0.4591613035706175, "heading_rate": -0.20433071109134654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.0490427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811015859457472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.614240195427049, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.067944561964124, "gear": 1, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.536060610265293, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.0490427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 40.25278184086044, "y": 0.4286204070358064, "z": null, "yaw": 3.482597729519573, "pitch": null, "roll": null}, "v": 1.0580131871810048, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "acceleration": 0.21574198477580342, "steering_wheel_angle": -8.68880681756765, "front_wheel_angle": -0.4591613035706175, "heading_rate": -0.20433071109134654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.0690427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811015859457472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.614240195427049, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.072784486467059, "gear": 1, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.459269798932434, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.0690427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 40.25278184086044, "y": 0.4286204070358064, "z": null, "yaw": 3.482597729519573, "pitch": null, "roll": null}, "v": 1.0580131871810048, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "acceleration": 0.21574198477580342, "steering_wheel_angle": -8.68880681756765, "front_wheel_angle": -0.4591613035706175, "heading_rate": -0.20433071109134654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.0890427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811015859457472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.614240195427049, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.080031413404704, "gear": 1, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.343561447331052, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.0890427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 40.25278184086044, "y": 0.4286204070358064, "z": null, "yaw": 3.482597729519573, "pitch": null, "roll": null}, "v": 1.0580131871810048, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "acceleration": 0.21574198477580342, "steering_wheel_angle": -8.68880681756765, "front_wheel_angle": -0.4591613035706175, "heading_rate": -0.20433071109134654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.1090426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811015859457472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.614240195427049, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0824436000342168, "gear": 1, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.304852760903366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.1090426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.1190426, "x": 44.14145726768009, "y": 5.390305087190741, "z": null, "yaw": 3.4619816491805318, "pitch": null, "roll": null}, "v": 1.0848540589410833, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "acceleration": 0.24087312592185628, "steering_wheel_angle": -8.266074456528733, "front_wheel_angle": -0.4331200230505782, "heading_rate": -0.19595291477671403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.1290426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29049551321383205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3043535596325615, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0872627902003018, "gear": 1, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.266074456528733, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.1290426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 40.14145726768009, "y": 0.3903050871907414, "z": null, "yaw": 3.4619816491805318, "pitch": null, "roll": null}, "v": 1.0848540589410833, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "acceleration": 0.24087312592185628, "steering_wheel_angle": -8.266074456528733, "front_wheel_angle": -0.4331200230505782, "heading_rate": -0.19595291477671403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.1490426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28765576947255067, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3043535596325615, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.093248889448336, "gear": 1, "accelerator_pedal_position": 0.29049551321383205, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.189338622966012, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.1490426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 40.14145726768009, "y": 0.3903050871907414, "z": null, "yaw": 3.4619816491805318, "pitch": null, "roll": null}, "v": 1.0848540589410833, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "acceleration": 0.24087312592185628, "steering_wheel_angle": -8.266074456528733, "front_wheel_angle": -0.4331200230505782, "heading_rate": -0.19595291477671403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.1690426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28765576947255067, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3043535596325615, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0988715512363398, "gear": 1, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.112331630000702, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.1690426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 40.14145726768009, "y": 0.3903050871907414, "z": null, "yaw": 3.4619816491805318, "pitch": null, "roll": null}, "v": 1.0848540589410833, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "acceleration": 0.24087312592185628, "steering_wheel_angle": -8.266074456528733, "front_wheel_angle": -0.4331200230505782, "heading_rate": -0.19595291477671403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.1890426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28765576947255067, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3043535596325615, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1044861250025768, "gear": 1, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.035053477632797, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.1890426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 40.14145726768009, "y": 0.3903050871907414, "z": null, "yaw": 3.4619816491805318, "pitch": null, "roll": null}, "v": 1.0848540589410833, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "acceleration": 0.24087312592185628, "steering_wheel_angle": -8.266074456528733, "front_wheel_angle": -0.4331200230505782, "heading_rate": -0.19595291477671403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.2090425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28765576947255067, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3043535596325615, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1100926097765782, "gear": 1, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.957504165862302, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.2090425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.2290425, "x": 44.026403470505485, "y": 5.3532683792340015, "z": null, "yaw": 3.44259700300547, "pitch": null, "roll": null}, "v": 1.1156910046437314, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "acceleration": 0.2796163447928257, "steering_wheel_angle": -7.957504165862302, "front_wheel_angle": -0.41443122503044966, "heading_rate": -0.1917200405207992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.2290425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2704480578130077, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.822778657872993, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1174116861129382, "gear": 1, "accelerator_pedal_position": 0.2704480578130077, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.9193982242212515, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.2290425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 40.026403470505485, "y": 0.35326837923400145, "z": null, "yaw": 3.44259700300547, "pitch": null, "roll": null}, "v": 1.1156910046437314, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "acceleration": 0.2796163447928257, "steering_wheel_angle": -7.957504165862302, "front_wheel_angle": -0.41443122503044966, "heading_rate": -0.1917200405207992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.2490425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2759364927136908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.822778657872993, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1191311229955685, "gear": 1, "accelerator_pedal_position": 0.2704480578130077, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.881227150595931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.2490425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 40.026403470505485, "y": 0.35326837923400145, "z": null, "yaw": 3.44259700300547, "pitch": null, "roll": null}, "v": 1.1156910046437314, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "acceleration": 0.2796163447928257, "steering_wheel_angle": -7.957504165862302, "front_wheel_angle": -0.41443122503044966, "heading_rate": -0.1917200405207992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.2690425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2759364927136908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.822778657872993, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1232520701778943, "gear": 1, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.8046896073924925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.2690425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 40.026403470505485, "y": 0.35326837923400145, "z": null, "yaw": 3.44259700300547, "pitch": null, "roll": null}, "v": 1.1156910046437314, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "acceleration": 0.2796163447928257, "steering_wheel_angle": -7.957504165862302, "front_wheel_angle": -0.41443122503044966, "heading_rate": -0.1917200405207992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.2890425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2759364927136908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.822778657872993, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.12942230035363, "gear": 1, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.689394802705322, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.2890425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 40.026403470505485, "y": 0.35326837923400145, "z": null, "yaw": 3.44259700300547, "pitch": null, "roll": null}, "v": 1.1156910046437314, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "acceleration": 0.2796163447928257, "steering_wheel_angle": -7.957504165862302, "front_wheel_angle": -0.41443122503044966, "heading_rate": -0.1917200405207992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.3090425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2759364927136908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.822778657872993, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.131476060524805, "gear": 1, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.650832937174396, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.3090425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 40.026403470505485, "y": 0.35326837923400145, "z": null, "yaw": 3.44259700300547, "pitch": null, "roll": null}, "v": 1.1156910046437314, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "acceleration": 0.2796163447928257, "steering_wheel_angle": -7.957504165862302, "front_wheel_angle": -0.41443122503044966, "heading_rate": -0.1917200405207992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.3290424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2759364927136908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.822778657872993, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1376283947140282, "gear": 1, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.534756548676011, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.3290424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.3390424, "x": 43.907871013459676, "y": 5.317568411388685, "z": null, "yaw": 3.4242777437042498, "pitch": null, "roll": null}, "v": 1.1376283947140282, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "acceleration": 0.20477967608026987, "steering_wheel_angle": -7.534756548676011, "front_wheel_angle": -0.3892429234391417, "heading_rate": -0.18227392918904345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.3490424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2859731940747825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.5652521653864255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.139676191474831, "gear": 1, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.4959341552080145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.3490424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 39.907871013459676, "y": 0.3175684113886854, "z": null, "yaw": 3.4242777437042498, "pitch": null, "roll": null}, "v": 1.1376283947140282, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "acceleration": 0.20477967608026987, "steering_wheel_angle": -7.534756548676011, "front_wheel_angle": -0.3892429234391417, "heading_rate": -0.18227392918904345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.3690424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2829162823436579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.5652521653864255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1450214452556982, "gear": 1, "accelerator_pedal_position": 0.2859731940747825, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.418898710458267, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.3690424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 39.907871013459676, "y": 0.3175684113886854, "z": null, "yaw": 3.4242777437042498, "pitch": null, "roll": null}, "v": 1.1376283947140282, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "acceleration": 0.20477967608026987, "steering_wheel_angle": -7.534756548676011, "front_wheel_angle": -0.3892429234391417, "heading_rate": -0.18227392918904345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.3890424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2829162823436579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.5652521653864255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1499769367208843, "gear": 1, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.341608087962784, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.3890424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 39.907871013459676, "y": 0.3175684113886854, "z": null, "yaw": 3.4242777437042498, "pitch": null, "roll": null}, "v": 1.1376283947140282, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "acceleration": 0.20477967608026987, "steering_wheel_angle": -7.534756548676011, "front_wheel_angle": -0.3892429234391417, "heading_rate": -0.18227392918904345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.4090424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2829162823436579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.5652521653864255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1549251983097872, "gear": 1, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.26406228772156, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.4090424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 39.907871013459676, "y": 0.3175684113886854, "z": null, "yaw": 3.4242777437042498, "pitch": null, "roll": null}, "v": 1.1376283947140282, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "acceleration": 0.20477967608026987, "steering_wheel_angle": -7.534756548676011, "front_wheel_angle": -0.3892429234391417, "heading_rate": -0.18227392918904345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.4290423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2829162823436579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.5652521653864255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1598662307799854, "gear": 1, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.225193695946298, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.4290423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.4490423, "x": 43.78612703487878, "y": 5.283245571395417, "z": null, "yaw": 3.4071889501576296, "pitch": null, "roll": null}, "v": 1.164800034930846, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "acceleration": 0.24641917168757044, "steering_wheel_angle": -7.225193695946298, "front_wheel_angle": -0.3710895970333793, "heading_rate": -0.17704833393863953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.4490423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2767092152793372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.215599166949639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.164800034930846, "gear": 1, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.225193695946298, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.4490423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 39.78612703487878, "y": 0.2832455713954172, "z": null, "yaw": 3.4071889501576296, "pitch": null, "roll": null}, "v": 1.164800034930846, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "acceleration": 0.24641917168757044, "steering_wheel_angle": -7.225193695946298, "front_wheel_angle": -0.3710895970333793, "heading_rate": -0.17704833393863953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.4690423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27874813455275677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.215599166949639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.168951012742243, "gear": 1, "accelerator_pedal_position": 0.2767092152793372, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.148331062243454, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.4690423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 39.78612703487878, "y": 0.2832455713954172, "z": null, "yaw": 3.4071889501576296, "pitch": null, "roll": null}, "v": 1.164800034930846, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "acceleration": 0.24641917168757044, "steering_wheel_angle": -7.225193695946298, "front_wheel_angle": -0.3710895970333793, "heading_rate": -0.17704833393863953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.4890423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27874813455275677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.215599166949639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.175548081855641, "gear": 1, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.032571632109456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.4890423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27874813455275677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.215599166949639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.175548081855641, "gear": 1, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.032571632109456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.4990423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 39.78612703487878, "y": 0.2832455713954172, "z": null, "yaw": 3.4071889501576296, "pitch": null, "roll": null}, "v": 1.164800034930846, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "acceleration": 0.24641917168757044, "steering_wheel_angle": -7.225193695946298, "front_wheel_angle": -0.3710895970333793, "heading_rate": -0.17704833393863953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.5290422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27874813455275677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.215599166949639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1886986251410934, "gear": 1, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.916253626479781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.5290422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.5590422, "x": 43.66109905293996, "y": 5.250237230844888, "z": null, "yaw": 3.3909890077633515, "pitch": null, "roll": null}, "v": 1.1886986251410934, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "acceleration": 0.2186108654835518, "steering_wheel_angle": -6.916253626479781, "front_wheel_angle": -0.353207488892234, "heading_rate": -0.17118543691744184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.5590422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28276357815562997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.957818775607447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1886986251410934, "gear": 1, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.916253626479781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.5590422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 39.66109905293996, "y": 0.25023723084488836, "z": null, "yaw": 3.3909890077633515, "pitch": null, "roll": null}, "v": 1.1886986251410934, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "acceleration": 0.2186108654835518, "steering_wheel_angle": -6.916253626479781, "front_wheel_angle": -0.353207488892234, "heading_rate": -0.17118543691744184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.5890422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2815966203901593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.957818775607447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1960044513614243, "gear": 1, "accelerator_pedal_position": 0.28276357815562997, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.80053121160279, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.5890422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 39.66109905293996, "y": 0.25023723084488836, "z": null, "yaw": 3.3909890077633515, "pitch": null, "roll": null}, "v": 1.1886986251410934, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "acceleration": 0.2186108654835518, "steering_wheel_angle": -6.916253626479781, "front_wheel_angle": -0.353207488892234, "heading_rate": -0.17118543691744184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.6090422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2815966203901593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.957818775607447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2007201949873512, "gear": 1, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.7230786995800775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.6090422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 39.66109905293996, "y": 0.25023723084488836, "z": null, "yaw": 3.3909890077633515, "pitch": null, "roll": null}, "v": 1.1886986251410934, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "acceleration": 0.2186108654835518, "steering_wheel_angle": -6.916253626479781, "front_wheel_angle": -0.353207488892234, "heading_rate": -0.17118543691744184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.6290421} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2815966203901593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.957818775607447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.205428962760556, "gear": 1, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.6453827992069225, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.6290421} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 39.66109905293996, "y": 0.25023723084488836, "z": null, "yaw": 3.3909890077633515, "pitch": null, "roll": null}, "v": 1.1886986251410934, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "acceleration": 0.2186108654835518, "steering_wheel_angle": -6.916253626479781, "front_wheel_angle": -0.353207488892234, "heading_rate": -0.17118543691744184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.6490421} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2815966203901593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.957818775607447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.210130756134487, "gear": 1, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.6453827992069225, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.6490421} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.669042, "x": 43.53288483600638, "y": 5.21854679410644, "z": null, "yaw": 3.3756267670446873, "pitch": null, "roll": null}, "v": 1.2148255765998208, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "acceleration": 0.23447958679289377, "steering_wheel_angle": -6.6453827992069225, "front_wheel_angle": -0.3377147934741458, "heading_rate": -0.16664360185416469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.669042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27576684138675606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.623664404224915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2148255765998208, "gear": 1, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.6453827992069225, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.669042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 39.53288483600638, "y": 0.21854679410644007, "z": null, "yaw": 3.3756267670446873, "pitch": null, "roll": null}, "v": 1.2148255765998208, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "acceleration": 0.23447958679289377, "steering_wheel_angle": -6.6453827992069225, "front_wheel_angle": -0.3377147934741458, "heading_rate": -0.16664360185416469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.689042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2776853643419224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.623664404224915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2187849741741605, "gear": 1, "accelerator_pedal_position": 0.27576684138675606, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.568416950840269, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.689042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 39.53288483600638, "y": 0.21854679410644007, "z": null, "yaw": 3.3756267670446873, "pitch": null, "roll": null}, "v": 1.2148255765998208, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "acceleration": 0.23447958679289377, "steering_wheel_angle": -6.6453827992069225, "front_wheel_angle": -0.3377147934741458, "heading_rate": -0.16664360185416469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.709042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2776853643419224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.623664404224915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.22297821198491, "gear": 1, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.491213746620616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.709042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 39.53288483600638, "y": 0.21854679410644007, "z": null, "yaw": 3.3756267670446873, "pitch": null, "roll": null}, "v": 1.2148255765998208, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "acceleration": 0.23447958679289377, "steering_wheel_angle": -6.6453827992069225, "front_wheel_angle": -0.3377147934741458, "heading_rate": -0.16664360185416469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.729042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2776853643419224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.623664404224915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2271652093449514, "gear": 1, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.413773186547961, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.729042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 39.53288483600638, "y": 0.21854679410644007, "z": null, "yaw": 3.3756267670446873, "pitch": null, "roll": null}, "v": 1.2148255765998208, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "acceleration": 0.23447958679289377, "steering_wheel_angle": -6.6453827992069225, "front_wheel_angle": -0.3377147934741458, "heading_rate": -0.16664360185416469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.749042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2776853643419224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.623664404224915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2313459685316672, "gear": 1, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.336095270622307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.749042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 39.53288483600638, "y": 0.21854679410644007, "z": null, "yaw": 3.3756267670446873, "pitch": null, "roll": null}, "v": 1.2148255765998208, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "acceleration": 0.23447958679289377, "steering_wheel_angle": -6.6453827992069225, "front_wheel_angle": -0.3377147934741458, "heading_rate": -0.16664360185416469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.769042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2776853643419224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.623664404224915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2355204918503688, "gear": 1, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.336095270622307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.769042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.779042, "x": 43.401591398822156, "y": 5.188179652273459, "z": null, "yaw": 3.3610338369876334, "pitch": null, "roll": null}, "v": 1.2376054157872356, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "acceleration": 0.20833658469579436, "steering_wheel_angle": -6.336095270622307, "front_wheel_angle": -0.3202296577020209, "heading_rate": -0.16032999438487666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.789042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28615756539832476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.432434710000177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2396887816341935, "gear": 1, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.336095270622307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.789042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 39.401591398822156, "y": 0.18817965227345912, "z": null, "yaw": 3.3610338369876334, "pitch": null, "roll": null}, "v": 1.2376054157872356, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "acceleration": 0.20833658469579436, "steering_wheel_angle": -6.336095270622307, "front_wheel_angle": -0.3202296577020209, "heading_rate": -0.16032999438487666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.809042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2835948834777548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.432434710000177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2449094690851035, "gear": 1, "accelerator_pedal_position": 0.28615756539832476, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.258727599755026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.809042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 39.401591398822156, "y": 0.18817965227345912, "z": null, "yaw": 3.3610338369876334, "pitch": null, "roll": null}, "v": 1.2376054157872356, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "acceleration": 0.20833658469579436, "steering_wheel_angle": -6.336095270622307, "front_wheel_angle": -0.3202296577020209, "heading_rate": -0.16032999438487666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.829042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2835948834777548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.432434710000177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2498021265920056, "gear": 1, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.181125892656704, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.829042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 39.401591398822156, "y": 0.18817965227345912, "z": null, "yaw": 3.3610338369876334, "pitch": null, "roll": null}, "v": 1.2376054157872356, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "acceleration": 0.20833658469579436, "steering_wheel_angle": -6.336095270622307, "front_wheel_angle": -0.3202296577020209, "heading_rate": -0.16032999438487666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.849042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2835948834777548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.432434710000177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2546874506446384, "gear": 1, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.142237275520903, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.849042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 39.401591398822156, "y": 0.18817965227345912, "z": null, "yaw": 3.3610338369876334, "pitch": null, "roll": null}, "v": 1.2376054157872356, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "acceleration": 0.20833658469579436, "steering_wheel_angle": -6.336095270622307, "front_wheel_angle": -0.3202296577020209, "heading_rate": -0.16032999438487666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.869042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2835948834777548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.432434710000177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2595654426919167, "gear": 1, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.142237275520903, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.869042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.889042, "x": 43.267227254878364, "y": 5.159114675584272, "z": null, "yaw": 3.3471118171883303, "pitch": null, "roll": null}, "v": 1.2644361042235341, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "acceleration": 0.24325822990815082, "steering_wheel_angle": -6.142237275520903, "front_wheel_angle": -0.3093781370491952, "heading_rate": -0.15787767443738918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.889042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27772121487647605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.108579133697644, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2644361042235341, "gear": 1, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.142237275520903, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.889042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 39.267227254878364, "y": 0.15911467558427184, "z": null, "yaw": 3.3471118171883303, "pitch": null, "roll": null}, "v": 1.2644361042235341, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "acceleration": 0.24325822990815082, "steering_wheel_angle": -6.142237275520903, "front_wheel_angle": -0.3093781370491952, "heading_rate": -0.15787767443738918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.909042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27965738005315427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.108579133697644, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2685655047479174, "gear": 1, "accelerator_pedal_position": 0.27772121487647605, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.0651929571480325, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.909042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 39.267227254878364, "y": 0.15911467558427184, "z": null, "yaw": 3.3471118171883303, "pitch": null, "roll": null}, "v": 1.2644361042235341, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "acceleration": 0.24325822990815082, "steering_wheel_angle": -6.142237275520903, "front_wheel_angle": -0.3093781370491952, "heading_rate": -0.15787767443738918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.9290419} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27965738005315427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.108579133697644, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2772891398302026, "gear": 1, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.91041845681227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.9290419} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 39.267227254878364, "y": 0.15911467558427184, "z": null, "yaw": 3.3471118171883303, "pitch": null, "roll": null}, "v": 1.2644361042235341, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "acceleration": 0.24325822990815082, "steering_wheel_angle": -6.142237275520903, "front_wheel_angle": -0.3093781370491952, "heading_rate": -0.15787767443738918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.9490418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27965738005315427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.108579133697644, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2816410847370585, "gear": 1, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.832688274849376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.9490418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 39.267227254878364, "y": 0.15911467558427184, "z": null, "yaw": 3.3471118171883303, "pitch": null, "roll": null}, "v": 1.2644361042235341, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "acceleration": 0.24325822990815082, "steering_wheel_angle": -6.142237275520903, "front_wheel_angle": -0.3093781370491952, "heading_rate": -0.15787767443738918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.9790418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27965738005315427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.108579133697644, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.292492170810939, "gear": 1, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.832688274849376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.9790418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.9990418, "x": 43.129742418660214, "y": 5.131332006312061, "z": null, "yaw": 3.333855372020498, "pitch": null, "roll": null}, "v": 1.2881566679417145, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "acceleration": 0.21685731592350144, "steering_wheel_angle": -5.832688274849376, "front_wheel_angle": -0.2922177419406417, "heading_rate": -0.15137331400774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.0190418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2790655043159033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.8463225634214915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2946574573776948, "gear": 1, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.832688274849376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.0190418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 39.129742418660214, "y": 0.13133200631206066, "z": null, "yaw": 3.333855372020498, "pitch": null, "roll": null}, "v": 1.2881566679417145, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "acceleration": 0.21685731592350144, "steering_wheel_angle": -5.832688274849376, "front_wheel_angle": -0.2922177419406417, "heading_rate": -0.15137331400774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.0390418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27934004154283965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.8463225634214915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3010497274648767, "gear": 1, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.716747843211106, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.0390418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 39.129742418660214, "y": 0.13133200631206066, "z": null, "yaw": 3.333855372020498, "pitch": null, "roll": null}, "v": 1.2881566679417145, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "acceleration": 0.21685731592350144, "steering_wheel_angle": -5.832688274849376, "front_wheel_angle": -0.2922177419406417, "heading_rate": -0.15137331400774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.0590417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27934004154283965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.8463225634214915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3031886821582381, "gear": 1, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.677988824477852, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.0590417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 39.129742418660214, "y": 0.13133200631206066, "z": null, "yaw": 3.333855372020498, "pitch": null, "roll": null}, "v": 1.2881566679417145, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "acceleration": 0.21685731592350144, "steering_wheel_angle": -5.832688274849376, "front_wheel_angle": -0.2922177419406417, "heading_rate": -0.15137331400774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.0890417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27934004154283965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.8463225634214915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3074617123313867, "gear": 1, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.600302474730601, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.0890417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.1090417, "x": 42.989339256407206, "y": 5.104851438394748, "z": null, "yaw": 3.3211817857354102, "pitch": null, "roll": null}, "v": 1.3117282390480105, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "acceleration": 0.2130825379591872, "steering_wheel_angle": -5.561375143716603, "front_wheel_angle": -0.2773411188493756, "heading_rate": -0.14586714229572298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.1090417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2797089685068541, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6016004552139735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3117282390480105, "gear": 1, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.561375143716603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.1090417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 38.989339256407206, "y": 0.10485143839474809, "z": null, "yaw": 3.3211817857354102, "pitch": null, "roll": null}, "v": 1.3117282390480105, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "acceleration": 0.2130825379591872, "steering_wheel_angle": -5.561375143716603, "front_wheel_angle": -0.2773411188493756, "heading_rate": -0.14586714229572298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.1290417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27968324942747924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6016004552139735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.318183354473301, "gear": 1, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.445250911053585, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.1290417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 38.989339256407206, "y": 0.10485143839474809, "z": null, "yaw": 3.3211817857354102, "pitch": null, "roll": null}, "v": 1.3117282390480105, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "acceleration": 0.2130825379591872, "steering_wheel_angle": -5.561375143716603, "front_wheel_angle": -0.2773411188493756, "heading_rate": -0.14586714229572298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.1490417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27968324942747924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6016004552139735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3203307051496809, "gear": 1, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.406432518580662, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.1490417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 38.989339256407206, "y": 0.10485143839474809, "z": null, "yaw": 3.3211817857354102, "pitch": null, "roll": null}, "v": 1.3117282390480105, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "acceleration": 0.2130825379591872, "steering_wheel_angle": -5.561375143716603, "front_wheel_angle": -0.2773411188493756, "heading_rate": -0.14586714229572298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.1690416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27968324942747924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6016004552139735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3246204860636865, "gear": 1, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.328630261256942, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.1690416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 38.989339256407206, "y": 0.10485143839474809, "z": null, "yaw": 3.3211817857354102, "pitch": null, "roll": null}, "v": 1.3117282390480105, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "acceleration": 0.2130825379591872, "steering_wheel_angle": -5.561375143716603, "front_wheel_angle": -0.2773411188493756, "heading_rate": -0.14586714229572298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.1890416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27968324942747924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6016004552139735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3289037086136124, "gear": 1, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.328630261256942, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.1890416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 38.989339256407206, "y": 0.10485143839474809, "z": null, "yaw": 3.3211817857354102, "pitch": null, "roll": null}, "v": 1.3117282390480105, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "acceleration": 0.2130825379591872, "steering_wheel_angle": -5.561375143716603, "front_wheel_angle": -0.2773411188493756, "heading_rate": -0.14586714229572298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.2090416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27968324942747924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6016004552139735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.33318037549052, "gear": 1, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.328630261256942, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.2090416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.2190416, "x": 42.84606866862808, "y": 5.079647506890617, "z": null, "yaw": 3.3093487336402325, "pitch": null, "roll": null}, "v": 1.335316251400633, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "acceleration": 0.21342380143916717, "steering_wheel_angle": -5.328630261256942, "front_wheel_angle": -0.26469776124127176, "heading_rate": -0.14138604027252688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.2290416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2813032865076223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.386671383380559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3374504894150245, "gear": 1, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.328630261256942, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.2290416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 38.84606866862808, "y": 0.07964750689061706, "z": null, "yaw": 3.3093487336402325, "pitch": null, "roll": null}, "v": 1.335316251400633, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "acceleration": 0.21342380143916717, "steering_wheel_angle": -5.328630261256942, "front_wheel_angle": -0.26469776124127176, "heading_rate": -0.14138604027252688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.2490416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28088721393723004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.386671383380559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3419164800178358, "gear": 1, "accelerator_pedal_position": 0.2813032865076223, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.251179928143811, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.2490416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 38.84606866862808, "y": 0.07964750689061706, "z": null, "yaw": 3.3093487336402325, "pitch": null, "roll": null}, "v": 1.335316251400633, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "acceleration": 0.21342380143916717, "steering_wheel_angle": -5.328630261256942, "front_wheel_angle": -0.26469776124127176, "heading_rate": -0.14138604027252688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.2690415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28088721393723004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.386671383380559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3485246533174926, "gear": 1, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.134596788221459, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.2690415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 38.84606866862808, "y": 0.07964750689061706, "z": null, "yaw": 3.3093487336402325, "pitch": null, "roll": null}, "v": 1.335316251400633, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "acceleration": 0.21342380143916717, "steering_wheel_angle": -5.328630261256942, "front_wheel_angle": -0.26469776124127176, "heading_rate": -0.14138604027252688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.2890415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28088721393723004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.386671383380559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.355117583694036, "gear": 1, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.134596788221459, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.2890415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 38.84606866862808, "y": 0.07964750689061706, "z": null, "yaw": 3.3093487336402325, "pitch": null, "roll": null}, "v": 1.335316251400633, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "acceleration": 0.21342380143916717, "steering_wheel_angle": -5.328630261256942, "front_wheel_angle": -0.26469776124127176, "heading_rate": -0.14138604027252688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.3190415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28088721393723004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.386671383380559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.357311841406702, "gear": 1, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.134596788221459, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.3190415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.3290415, "x": 42.69992711597581, "y": 5.055683345176492, "z": null, "yaw": 3.2980079453194655, "pitch": null, "roll": null}, "v": 1.3595044068135933, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "acceleration": 0.21908734444555217, "steering_wheel_angle": -5.134596788221459, "front_wheel_angle": -0.2542388386536812, "heading_rate": -0.1380014068035027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.3390415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28113852140814344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.167587142123151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3616952802580489, "gear": 1, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.134596788221459, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.3390415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 38.69992711597581, "y": 0.05568334517649198, "z": null, "yaw": 3.2980079453194655, "pitch": null, "roll": null}, "v": 1.3595044068135933, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "acceleration": 0.21908734444555217, "steering_wheel_angle": -5.134596788221459, "front_wheel_angle": -0.2542388386536812, "heading_rate": -0.1380014068035027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.3590415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811530495919863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.167587142123151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.366103353938863, "gear": 1, "accelerator_pedal_position": 0.28113852140814344, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.057177782077558, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.3590415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 38.69992711597581, "y": 0.05568334517649198, "z": null, "yaw": 3.2980079453194655, "pitch": null, "roll": null}, "v": 1.3595044068135933, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "acceleration": 0.21908734444555217, "steering_wheel_angle": -5.134596788221459, "front_wheel_angle": -0.2542388386536812, "heading_rate": -0.1380014068035027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.3790414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811530495919863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.167587142123151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3705064306906025, "gear": 1, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.979544556371263, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.3790414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 38.69992711597581, "y": 0.05568334517649198, "z": null, "yaw": 3.2980079453194655, "pitch": null, "roll": null}, "v": 1.3595044068135933, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "acceleration": 0.21908734444555217, "steering_wheel_angle": -5.134596788221459, "front_wheel_angle": -0.2542388386536812, "heading_rate": -0.1380014068035027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.3990414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811530495919863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.167587142123151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3749026951640142, "gear": 1, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.901697111102577, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.3990414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 38.69992711597581, "y": 0.05568334517649198, "z": null, "yaw": 3.2980079453194655, "pitch": null, "roll": null}, "v": 1.3595044068135933, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "acceleration": 0.21908734444555217, "steering_wheel_angle": -5.134596788221459, "front_wheel_angle": -0.2542388386536812, "heading_rate": -0.1380014068035027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.4190414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811530495919863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.167587142123151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3792921501709412, "gear": 1, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.901697111102577, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.4190414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.4390414, "x": 42.55089770430696, "y": 5.03294399037451, "z": null, "yaw": 3.2871787700477575, "pitch": null, "roll": null}, "v": 1.3836747985547704, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "acceleration": 0.21887726054061973, "steering_wheel_angle": -4.901697111102577, "front_wheel_angle": -0.2417805077050956, "heading_rate": -0.13328931929232635, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.4390414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28060216568088464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.941761081616841, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3836747985547704, "gear": 1, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.901697111102577, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.4390414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 38.55089770430696, "y": 0.0329439903745099, "z": null, "yaw": 3.2871787700477575, "pitch": null, "roll": null}, "v": 1.3836747985547704, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "acceleration": 0.21887726054061973, "steering_wheel_angle": -4.901697111102577, "front_wheel_angle": -0.2417805077050956, "heading_rate": -0.13328931929232635, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.4590414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2808678949146875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.941761081616841, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3879818094595489, "gear": 1, "accelerator_pedal_position": 0.28060216568088464, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.824219687136048, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.4590414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 38.55089770430696, "y": 0.0329439903745099, "z": null, "yaw": 3.2871787700477575, "pitch": null, "roll": null}, "v": 1.3836747985547704, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "acceleration": 0.21887726054061973, "steering_wheel_angle": -4.901697111102577, "front_wheel_angle": -0.2417805077050956, "heading_rate": -0.13328931929232635, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.4790413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2808678949146875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.941761081616841, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3923153298235522, "gear": 1, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.746531233867736, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.4790413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 38.55089770430696, "y": 0.0329439903745099, "z": null, "yaw": 3.2871787700477575, "pitch": null, "roll": null}, "v": 1.3836747985547704, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "acceleration": 0.21887726054061973, "steering_wheel_angle": -4.901697111102577, "front_wheel_angle": -0.2417805077050956, "heading_rate": -0.13328931929232635, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.4990413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2808678949146875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.941761081616841, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3966421077197995, "gear": 1, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.707607871245411, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.4990413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 38.55089770430696, "y": 0.0329439903745099, "z": null, "yaw": 3.2871787700477575, "pitch": null, "roll": null}, "v": 1.3836747985547704, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "acceleration": 0.21887726054061973, "steering_wheel_angle": -4.901697111102577, "front_wheel_angle": -0.2417805077050956, "heading_rate": -0.13328931929232635, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.5190413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2808678949146875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.941761081616841, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.400962146153321, "gear": 1, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.707607871245411, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.5190413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 38.55089770430696, "y": 0.0329439903745099, "z": null, "yaw": 3.2871787700477575, "pitch": null, "roll": null}, "v": 1.3836747985547704, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "acceleration": 0.21887726054061973, "steering_wheel_angle": -4.901697111102577, "front_wheel_angle": -0.2417805077050956, "heading_rate": -0.13328931929232635, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.5390413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2808678949146875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.941761081616841, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4052754481594354, "gear": 1, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.707607871245411, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.5390413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.5490413, "x": 42.39902545714323, "y": 5.011407479089678, "z": null, "yaw": 3.2769233003450022, "pitch": null, "roll": null}, "v": 1.4074295739590037, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "acceleration": 0.21524428446230243, "steering_wheel_angle": -4.707607871245411, "front_wheel_angle": -0.2314761616691115, "heading_rate": -0.12958302569043084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.5590413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28736278125120546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8210091419365306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4095820168036268, "gear": 1, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.707607871245411, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.5590413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 38.39902545714323, "y": 0.011407479089678318, "z": null, "yaw": 3.2769233003450022, "pitch": null, "roll": null}, "v": 1.4074295739590037, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "acceleration": 0.21524428446230243, "steering_wheel_angle": -4.707607871245411, "front_wheel_angle": -0.2314761616691115, "heading_rate": -0.12958302569043084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.5790412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854256659682318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8210091419365306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.414693398378762, "gear": 1, "accelerator_pedal_position": 0.28736278125120546, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.629912031601394, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.5790412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 38.39902545714323, "y": 0.011407479089678318, "z": null, "yaw": 3.2769233003450022, "pitch": null, "roll": null}, "v": 1.4074295739590037, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "acceleration": 0.21524428446230243, "steering_wheel_angle": -4.707607871245411, "front_wheel_angle": -0.2314761616691115, "heading_rate": -0.12958302569043084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.5990412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854256659682318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8210091419365306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4195547373421806, "gear": 1, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.552006829845901, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.5990412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 38.39902545714323, "y": 0.011407479089678318, "z": null, "yaw": 3.2769233003450022, "pitch": null, "roll": null}, "v": 1.4074295739590037, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "acceleration": 0.21524428446230243, "steering_wheel_angle": -4.707607871245411, "front_wheel_angle": -0.2314761616691115, "heading_rate": -0.12958302569043084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.6190412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854256659682318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8210091419365306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4244084599416402, "gear": 1, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.552006829845901, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.6190412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 38.39902545714323, "y": 0.011407479089678318, "z": null, "yaw": 3.2769233003450022, "pitch": null, "roll": null}, "v": 1.4074295739590037, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "acceleration": 0.21524428446230243, "steering_wheel_angle": -4.707607871245411, "front_wheel_angle": -0.2314761616691115, "heading_rate": -0.12958302569043084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.6390412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854256659682318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8210091419365306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4316747686665645, "gear": 1, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.552006829845901, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.6390412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 38.39902545714323, "y": 0.011407479089678318, "z": null, "yaw": 3.2769233003450022, "pitch": null, "roll": null}, "v": 1.4074295739590037, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "acceleration": 0.21524428446230243, "steering_wheel_angle": -4.707607871245411, "front_wheel_angle": -0.2314761616691115, "heading_rate": -0.12958302569043084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.6490412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854256659682318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8210091419365306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4316747686665645, "gear": 1, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.552006829845901, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.6490412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.6590412, "x": 42.24421290988843, "y": 4.991043530120282, "z": null, "yaw": 3.2670489948217805, "pitch": null, "roll": null}, "v": 1.4340930661409221, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "acceleration": 0.24163952977086806, "steering_wheel_angle": -4.552006829845901, "front_wheel_angle": -0.22326531229195823, "heading_rate": -0.1271920306622703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.6790411} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2806833706265429, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5608853478359803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4389239548876458, "gear": 1, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.552006829845901, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.6790411} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 38.24421290988843, "y": -0.008956469879717766, "z": null, "yaw": 3.2670489948217805, "pitch": null, "roll": null}, "v": 1.4340930661409221, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "acceleration": 0.24163952977086806, "steering_wheel_angle": -4.552006829845901, "front_wheel_angle": -0.22326531229195823, "heading_rate": -0.1271920306622703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.6990411} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2822698801498217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5608853478359803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4431546842746856, "gear": 1, "accelerator_pedal_position": 0.2806833706265429, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.474549479546092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.6990411} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 38.24421290988843, "y": -0.008956469879717766, "z": null, "yaw": 3.2670489948217805, "pitch": null, "roll": null}, "v": 1.4340930661409221, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "acceleration": 0.24163952977086806, "steering_wheel_angle": -4.552006829845901, "front_wheel_angle": -0.22326531229195823, "heading_rate": -0.1271920306622703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.719041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2822698801498217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5608853478359803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.44757698056339, "gear": 1, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.396886270597458, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.719041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 38.24421290988843, "y": -0.008956469879717766, "z": null, "yaw": 3.2670489948217805, "pitch": null, "roll": null}, "v": 1.4340930661409221, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "acceleration": 0.24163952977086806, "steering_wheel_angle": -4.552006829845901, "front_wheel_angle": -0.22326531229195823, "heading_rate": -0.1271920306622703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.739041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2822698801498217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5608853478359803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4541973418180774, "gear": 1, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.319017202999995, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.739041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 38.24421290988843, "y": -0.008956469879717766, "z": null, "yaw": 3.2670489948217805, "pitch": null, "roll": null}, "v": 1.4340930661409221, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "acceleration": 0.24163952977086806, "steering_wheel_angle": -4.552006829845901, "front_wheel_angle": -0.22326531229195823, "heading_rate": -0.1271920306622703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.759041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2822698801498217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5608853478359803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4564006416656372, "gear": 1, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.319017202999995, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.759041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.769041, "x": 42.08638693465914, "y": 4.97184138835973, "z": null, "yaw": 3.2575682094300253, "pitch": null, "roll": null}, "v": 1.4586021985712638, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "acceleration": 0.21998143727105302, "steering_wheel_angle": -4.319017202999995, "front_wheel_angle": -0.2110525231606861, "heading_rate": -0.12206849826454555, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.779041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28827243170678873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.4492027937610064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4608020129439743, "gear": 1, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.319017202999995, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.779041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 38.08638693465914, "y": -0.028158611640270337, "z": null, "yaw": 3.2575682094300253, "pitch": null, "roll": null}, "v": 1.4586021985712638, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "acceleration": 0.21998143727105302, "steering_wheel_angle": -4.319017202999995, "front_wheel_angle": -0.2110525231606861, "heading_rate": -0.12206849826454555, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.799041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28649335473552034, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.4492027937610064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4659464373157447, "gear": 1, "accelerator_pedal_position": 0.28827243170678873, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.241221610789449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.799041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 38.08638693465914, "y": -0.028158611640270337, "z": null, "yaw": 3.2575682094300253, "pitch": null, "roll": null}, "v": 1.4586021985712638, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "acceleration": 0.21998143727105302, "steering_wheel_angle": -4.319017202999995, "front_wheel_angle": -0.2110525231606861, "heading_rate": -0.12206849826454555, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.819041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28649335473552034, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.4492027937610064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.47086041019602, "gear": 1, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.202247168366611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.819041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 38.08638693465914, "y": -0.028158611640270337, "z": null, "yaw": 3.2575682094300253, "pitch": null, "roll": null}, "v": 1.4586021985712638, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "acceleration": 0.21998143727105302, "steering_wheel_angle": -4.319017202999995, "front_wheel_angle": -0.2110525231606861, "heading_rate": -0.12206849826454555, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.839041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28649335473552034, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.4492027937610064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4757665835091898, "gear": 1, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.202247168366611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.839041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 38.08638693465914, "y": -0.028158611640270337, "z": null, "yaw": 3.2575682094300253, "pitch": null, "roll": null}, "v": 1.4586021985712638, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "acceleration": 0.21998143727105302, "steering_wheel_angle": -4.319017202999995, "front_wheel_angle": -0.2110525231606861, "heading_rate": -0.12206849826454555, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.859041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28649335473552034, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.4492027937610064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4806649600105102, "gear": 1, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.202247168366611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.859041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.879041, "x": 41.92560764998388, "y": 4.953784260496893, "z": null, "yaw": 3.2485610824954145, "pitch": null, "roll": null}, "v": 1.4855555424967304, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "acceleration": 0.24423693727373802, "steering_wheel_angle": -4.202247168366611, "front_wheel_angle": -0.204967947201479, "heading_rate": -0.12063603432875339, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.879041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2818322802093307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.2173987948684633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4877065947115808, "gear": 1, "accelerator_pedal_position": 0.2818322802093307, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.163507546787555, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.879041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 37.92560764998388, "y": -0.04621573950310687, "z": null, "yaw": 3.2485610824954145, "pitch": null, "roll": null}, "v": 1.4855555424967304, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "acceleration": 0.24423693727373802, "steering_wheel_angle": -4.202247168366611, "front_wheel_angle": -0.204967947201479, "heading_rate": -0.12063603432875339, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.899041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28339592783186884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.2173987948684633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4898559318361133, "gear": 1, "accelerator_pedal_position": 0.2818322802093307, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.124717573164493, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.899041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 37.92560764998388, "y": -0.04621573950310687, "z": null, "yaw": 3.2485610824954145, "pitch": null, "roll": null}, "v": 1.4855555424967304, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "acceleration": 0.24423693727373802, "steering_wheel_angle": -4.202247168366611, "front_wheel_angle": -0.204967947201479, "heading_rate": -0.12063603432875339, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.919041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28339592783186884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.2173987948684633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.49434484051461, "gear": 1, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.046986569786353, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.919041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 37.92560764998388, "y": -0.04621573950310687, "z": null, "yaw": 3.2485610824954145, "pitch": null, "roll": null}, "v": 1.4855555424967304, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "acceleration": 0.24423693727373802, "steering_wheel_angle": -4.202247168366611, "front_wheel_angle": -0.204967947201479, "heading_rate": -0.12063603432875339, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.939041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28339592783186884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.2173987948684633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4988265819724271, "gear": 1, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.969054158232192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.939041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 37.92560764998388, "y": -0.04621573950310687, "z": null, "yaw": 3.2485610824954145, "pitch": null, "roll": null}, "v": 1.4855555424967304, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "acceleration": 0.24423693727373802, "steering_wheel_angle": -4.202247168366611, "front_wheel_angle": -0.204967947201479, "heading_rate": -0.12063603432875339, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.9590409} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28339592783186884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.2173987948684633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5033011596219221, "gear": 1, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.969054158232192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.9590409} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 37.92560764998388, "y": -0.04621573950310687, "z": null, "yaw": 3.2485610824954145, "pitch": null, "roll": null}, "v": 1.4855555424967304, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "acceleration": 0.24423693727373802, "steering_wheel_angle": -4.202247168366611, "front_wheel_angle": -0.204967947201479, "heading_rate": -0.12063603432875339, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.9690409} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28339592783186884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.2173987948684633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5077685769085003, "gear": 1, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.969054158232192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.9690409} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.9890409, "x": 41.76185436125822, "y": 4.936855796343539, "z": null, "yaw": 3.2399968336696063, "pitch": null, "roll": null}, "v": 1.5099996015013866, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "acceleration": 0.2229235809087674, "steering_wheel_angle": -3.969054158232192, "front_wheel_angle": -0.19288789397631215, "heading_rate": -0.11520602026533577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.9990408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28935316716479614, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.1261118044616976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5122288373104742, "gear": 1, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.969054158232192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.9990408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 37.76185436125822, "y": -0.0631442036564609, "z": null, "yaw": 3.2399968336696063, "pitch": null, "roll": null}, "v": 1.5099996015013866, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "acceleration": 0.2229235809087674, "steering_wheel_angle": -3.969054158232192, "front_wheel_angle": -0.19288789397631215, "heading_rate": -0.11520602026533577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.0190408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2875892506276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.1261118044616976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5174263003032178, "gear": 1, "accelerator_pedal_position": 0.28935316716479614, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8911441263357998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.0190408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 37.76185436125822, "y": -0.0631442036564609, "z": null, "yaw": 3.2399968336696063, "pitch": null, "roll": null}, "v": 1.5099996015013866, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "acceleration": 0.2229235809087674, "steering_wheel_angle": -3.969054158232192, "front_wheel_angle": -0.19288789397631215, "heading_rate": -0.11520602026533577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.0390408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2875892506276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.1261118044616976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5223950162507747, "gear": 1, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8911441263357998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.0390408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 37.76185436125822, "y": -0.0631442036564609, "z": null, "yaw": 3.2399968336696063, "pitch": null, "roll": null}, "v": 1.5099996015013866, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "acceleration": 0.2229235809087674, "steering_wheel_angle": -3.969054158232192, "front_wheel_angle": -0.19288789397631215, "heading_rate": -0.11520602026533577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.0590408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2875892506276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.1261118044616976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5273557434265306, "gear": 1, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8911441263357998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.0590408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 37.76185436125822, "y": -0.0631442036564609, "z": null, "yaw": 3.2399968336696063, "pitch": null, "roll": null}, "v": 1.5099996015013866, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "acceleration": 0.2229235809087674, "steering_wheel_angle": -3.969054158232192, "front_wheel_angle": -0.19288789397631215, "heading_rate": -0.11520602026533577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.0790408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2875892506276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.1261118044616976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.534781861827919, "gear": 1, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8911441263357998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.0790408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 37.76185436125822, "y": -0.0631442036564609, "z": null, "yaw": 3.2399968336696063, "pitch": null, "roll": null}, "v": 1.5099996015013866, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "acceleration": 0.2229235809087674, "steering_wheel_angle": -3.969054158232192, "front_wheel_angle": -0.19288789397631215, "heading_rate": -0.11520602026533577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.0890408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2875892506276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.1261118044616976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5397226303138802, "gear": 1, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8911441263357998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.0890408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.0990407, "x": 41.595144512883685, "y": 4.921033713831507, "z": null, "yaw": 3.231742637218304, "pitch": null, "roll": null}, "v": 1.5372532435248905, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "acceleration": 0.24693867889897736, "steering_wheel_angle": -3.8911441263357998, "front_wheel_angle": -0.18887272783703393, "heading_rate": -0.11478425206592342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.1190407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2924050818070962, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.0364962636665775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5421900225851182, "gear": 1, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8911441263357998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.1190407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 37.595144512883685, "y": -0.07896628616849277, "z": null, "yaw": 3.231742637218304, "pitch": null, "roll": null}, "v": 1.5372532435248905, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "acceleration": 0.24693867889897736, "steering_wheel_angle": -3.8911441263357998, "front_wheel_angle": -0.18887272783703393, "heading_rate": -0.11478425206592342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.1390407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2910097921228359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.0364962636665775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5503952683911524, "gear": 1, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.813252227246872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.1390407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 37.595144512883685, "y": -0.07896628616849277, "z": null, "yaw": 3.231742637218304, "pitch": null, "roll": null}, "v": 1.5372532435248905, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "acceleration": 0.24693867889897736, "steering_wheel_angle": -3.8911441263357998, "front_wheel_angle": -0.18887272783703393, "heading_rate": -0.11478425206592342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.1590407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2910097921228359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.0364962636665775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.553067810215809, "gear": 1, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.813252227246872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.1590407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 37.595144512883685, "y": -0.07896628616849277, "z": null, "yaw": 3.231742637218304, "pitch": null, "roll": null}, "v": 1.5372532435248905, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "acceleration": 0.24693867889897736, "steering_wheel_angle": -3.8911441263357998, "front_wheel_angle": -0.18887272783703393, "heading_rate": -0.11478425206592342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.1790407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2910097921228359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.0364962636665775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.558406397140116, "gear": 1, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.813252227246872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.1790407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 37.595144512883685, "y": -0.07896628616849277, "z": null, "yaw": 3.231742637218304, "pitch": null, "roll": null}, "v": 1.5372532435248905, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "acceleration": 0.24693867889897736, "steering_wheel_angle": -3.8911441263357998, "front_wheel_angle": -0.18887272783703393, "heading_rate": -0.11478425206592342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.1990407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2910097921228359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.0364962636665775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5637363239683881, "gear": 1, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.813252227246872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.1990407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.2090406, "x": 41.42523911895955, "y": 4.906310403615023, "z": null, "yaw": 3.223650612556335, "pitch": null, "roll": null}, "v": 1.5663980406849913, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "acceleration": 0.2659552705148569, "steering_wheel_angle": -3.813252227246872, "front_wheel_angle": -0.1848687734623662, "heading_rate": -0.11442294279971707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.2190406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2881580014021757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.820789775451371, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5690575933901398, "gear": 1, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.813252227246872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.2190406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 37.42523911895955, "y": -0.09368959638497731, "z": null, "yaw": 3.223650612556335, "pitch": null, "roll": null}, "v": 1.5663980406849913, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "acceleration": 0.2659552705148569, "steering_wheel_angle": -3.813252227246872, "front_wheel_angle": -0.1848687734623662, "heading_rate": -0.11442294279971707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.2390406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2891672763005814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.820789775451371, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5765520753083693, "gear": 1, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.6968213422950016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.2390406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 37.42523911895955, "y": -0.09368959638497731, "z": null, "yaw": 3.223650612556335, "pitch": null, "roll": null}, "v": 1.5663980406849913, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "acceleration": 0.2659552705148569, "steering_wheel_angle": -3.813252227246872, "front_wheel_angle": -0.1848687734623662, "heading_rate": -0.11442294279971707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.2590406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2891672763005814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.820789775451371, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5790882023948856, "gear": 1, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.657912795835624, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.2590406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 37.42523911895955, "y": -0.09368959638497731, "z": null, "yaw": 3.223650612556335, "pitch": null, "roll": null}, "v": 1.5663980406849913, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "acceleration": 0.2659552705148569, "steering_wheel_angle": -3.813252227246872, "front_wheel_angle": -0.1848687734623662, "heading_rate": -0.11442294279971707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.2790406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2891672763005814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.820789775451371, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.58415425184793, "gear": 1, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5799483257037368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.2790406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 37.42523911895955, "y": -0.09368959638497731, "z": null, "yaw": 3.223650612556335, "pitch": null, "roll": null}, "v": 1.5663980406849913, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "acceleration": 0.2659552705148569, "steering_wheel_angle": -3.813252227246872, "front_wheel_angle": -0.1848687734623662, "heading_rate": -0.11442294279971707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.2990406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2891672763005814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.820789775451371, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5892120310355768, "gear": 1, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5799483257037368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.2990406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.3190405, "x": 41.252073608038394, "y": 4.892692591133996, "z": null, "yaw": 3.2159282579726245, "pitch": null, "roll": null}, "v": 1.5942615432306648, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "acceleration": 0.2521657010348583, "steering_wheel_angle": -3.5799483257037368, "front_wheel_angle": -0.17293672969205234, "heading_rate": -0.10878444839305275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.3190405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2961787935007446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.78009309403782, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5942615432306648, "gear": 1, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5799483257037368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.3190405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 37.252073608038394, "y": -0.10730740886600376, "z": null, "yaw": 3.2159282579726245, "pitch": null, "roll": null}, "v": 1.5942615432306648, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "acceleration": 0.2521657010348583, "steering_wheel_angle": -3.5799483257037368, "front_wheel_angle": -0.17293672969205234, "heading_rate": -0.10878444839305275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.3390405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941013852931841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.78009309403782, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6001788723233152, "gear": 1, "accelerator_pedal_position": 0.2961787935007446, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5409411430739257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.3390405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 37.252073608038394, "y": -0.10730740886600376, "z": null, "yaw": 3.2159282579726245, "pitch": null, "roll": null}, "v": 1.5942615432306648, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "acceleration": 0.2521657010348583, "steering_wheel_angle": -3.5799483257037368, "front_wheel_angle": -0.17293672969205234, "heading_rate": -0.10878444839305275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.3590405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941013852931841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.78009309403782, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6058269345729945, "gear": 1, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5409411430739257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.3590405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 37.252073608038394, "y": -0.10730740886600376, "z": null, "yaw": 3.2159282579726245, "pitch": null, "roll": null}, "v": 1.5942615432306648, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "acceleration": 0.2521657010348583, "steering_wheel_angle": -3.5799483257037368, "front_wheel_angle": -0.17293672969205234, "heading_rate": -0.10878444839305275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.3790405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941013852931841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.78009309403782, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6114657278335371, "gear": 1, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5409411430739257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.3790405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 37.252073608038394, "y": -0.10730740886600376, "z": null, "yaw": 3.2159282579726245, "pitch": null, "roll": null}, "v": 1.5942615432306648, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "acceleration": 0.2521657010348583, "steering_wheel_angle": -3.5799483257037368, "front_wheel_angle": -0.17293672969205234, "heading_rate": -0.10878444839305275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.3990405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941013852931841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.78009309403782, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6170952546030348, "gear": 1, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5409411430739257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.3990405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 37.252073608038394, "y": -0.10730740886600376, "z": null, "yaw": 3.2159282579726245, "pitch": null, "roll": null}, "v": 1.5942615432306648, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "acceleration": 0.2521657010348583, "steering_wheel_angle": -3.5799483257037368, "front_wheel_angle": -0.17293672969205234, "heading_rate": -0.10878444839305275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.4190404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941013852931841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.78009309403782, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6227155174381291, "gear": 1, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5409411430739257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.4190404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.4290404, "x": 41.07557307036615, "y": 4.8801497709591795, "z": null, "yaw": 3.208502332635277, "pitch": null, "roll": null}, "v": 1.6255221756951805, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "acceleration": 0.2804343258608735, "steering_wheel_angle": -3.5409411430739257, "front_wheel_angle": -0.17095053599931267, "heading_rate": -0.10961831132070582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.4390404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2961891053072854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6834896163494406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6283265189537892, "gear": 1, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5409411430739257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.4390404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 37.07557307036615, "y": -0.11985022904082054, "z": null, "yaw": 3.208502332635277, "pitch": null, "roll": null}, "v": 1.6255221756951805, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "acceleration": 0.2804343258608735, "steering_wheel_angle": -3.5409411430739257, "front_wheel_angle": -0.17095053599931267, "heading_rate": -0.10961831132070582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.4590404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29566517027824774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6834896163494406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6341891190151525, "gear": 1, "accelerator_pedal_position": 0.2961891053072854, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.463010289075194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.4590404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 37.07557307036615, "y": -0.11985022904082054, "z": null, "yaw": 3.208502332635277, "pitch": null, "roll": null}, "v": 1.6255221756951805, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "acceleration": 0.2804343258608735, "steering_wheel_angle": -3.5409411430739257, "front_wheel_angle": -0.17095053599931267, "heading_rate": -0.10961831132070582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.4790404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29566517027824774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6834896163494406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6457544381355957, "gear": 1, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.463010289075194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.4790404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 37.07557307036615, "y": -0.11985022904082054, "z": null, "yaw": 3.208502332635277, "pitch": null, "roll": null}, "v": 1.6255221756951805, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "acceleration": 0.2804343258608735, "steering_wheel_angle": -3.5409411430739257, "front_wheel_angle": -0.17095053599931267, "heading_rate": -0.10961831132070582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.4990404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29566517027824774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6834896163494406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6457544381355957, "gear": 1, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.463010289075194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.4990404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 37.07557307036615, "y": -0.11985022904082054, "z": null, "yaw": 3.208502332635277, "pitch": null, "roll": null}, "v": 1.6255221756951805, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "acceleration": 0.2804343258608735, "steering_wheel_angle": -3.5409411430739257, "front_wheel_angle": -0.17095053599931267, "heading_rate": -0.10961831132070582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.5190403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29566517027824774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6834896163494406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6515227352290935, "gear": 1, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.463010289075194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.5190403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.5390403, "x": 40.895542428509614, "y": 4.868689321855683, "z": null, "yaw": 3.2012197371807116, "pitch": null, "roll": null}, "v": 1.6572814607386184, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "acceleration": 0.2875774228010381, "steering_wheel_angle": -3.463010289075194, "front_wheel_angle": -0.16698984973405964, "heading_rate": -0.10912134499903652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.5390403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2958716082637551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.5407698837845385, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6572814607386184, "gear": 1, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.463010289075194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.5390403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 36.895542428509614, "y": -0.13131067814431674, "z": null, "yaw": 3.2012197371807116, "pitch": null, "roll": null}, "v": 1.6572814607386184, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "acceleration": 0.2875774228010381, "steering_wheel_angle": -3.463010289075194, "front_wheel_angle": -0.16698984973405964, "heading_rate": -0.10912134499903652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.5590403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2959386243980474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.5407698837845385, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6630564113000454, "gear": 1, "accelerator_pedal_position": 0.2958716082637551, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.3852222822898863, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.5590403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 36.895542428509614, "y": -0.13131067814431674, "z": null, "yaw": 3.2012197371807116, "pitch": null, "roll": null}, "v": 1.6572814607386184, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "acceleration": 0.2875774228010381, "steering_wheel_angle": -3.463010289075194, "front_wheel_angle": -0.16698984973405964, "heading_rate": -0.10912134499903652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.5790403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2959386243980474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.5407698837845385, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.671713375710319, "gear": 1, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.307241094349303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.5790403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 36.895542428509614, "y": -0.13131067814431674, "z": null, "yaw": 3.2012197371807116, "pitch": null, "roll": null}, "v": 1.6572814607386184, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "acceleration": 0.2875774228010381, "steering_wheel_angle": -3.463010289075194, "front_wheel_angle": -0.16698984973405964, "heading_rate": -0.10912134499903652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.5990403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2959386243980474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.5407698837845385, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6774726608205952, "gear": 1, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.307241094349303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.5990403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 36.895542428509614, "y": -0.13131067814431674, "z": null, "yaw": 3.2012197371807116, "pitch": null, "roll": null}, "v": 1.6572814607386184, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "acceleration": 0.2875774228010381, "steering_wheel_angle": -3.463010289075194, "front_wheel_angle": -0.16698984973405964, "heading_rate": -0.10912134499903652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.6190403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2959386243980474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.5407698837845385, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6803486970622827, "gear": 1, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.307241094349303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.6190403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 36.895542428509614, "y": -0.13131067814431674, "z": null, "yaw": 3.2012197371807116, "pitch": null, "roll": null}, "v": 1.6572814607386184, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "acceleration": 0.2875774228010381, "steering_wheel_angle": -3.463010289075194, "front_wheel_angle": -0.16698984973405964, "heading_rate": -0.10912134499903652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.6390402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2959386243980474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.5407698837845385, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.686093558683279, "gear": 1, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.307241094349303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.6390402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.6490402, "x": 40.71194809470455, "y": 4.858320384033212, "z": null, "yaw": 3.194245936410567, "pitch": null, "roll": null}, "v": 1.688962384779952, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "acceleration": 0.2866423438767828, "steering_wheel_angle": -3.307241094349303, "front_wheel_angle": -0.1591026757697778, "heading_rate": -0.10586290891791993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.6590402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2942161790275796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.3441925470100546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6946928293678565, "gear": 1, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.307241094349303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.6590402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 36.71194809470455, "y": -0.1416796159667877, "z": null, "yaw": 3.194245936410567, "pitch": null, "roll": null}, "v": 1.688962384779952, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "acceleration": 0.2866423438767828, "steering_wheel_angle": -3.307241094349303, "front_wheel_angle": -0.1591026757697778, "heading_rate": -0.10586290891791993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.6790402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2948866520040973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.3441925470100546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7002403555537347, "gear": 1, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.229527057465774, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.6790402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 36.71194809470455, "y": -0.1416796159667877, "z": null, "yaw": 3.194245936410567, "pitch": null, "roll": null}, "v": 1.688962384779952, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "acceleration": 0.2866423438767828, "steering_wheel_angle": -3.307241094349303, "front_wheel_angle": -0.1591026757697778, "heading_rate": -0.10586290891791993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.6990402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2948866520040973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.3441925470100546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7030315693995486, "gear": 1, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.1905984457032757, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.6990402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 36.71194809470455, "y": -0.1416796159667877, "z": null, "yaw": 3.194245936410567, "pitch": null, "roll": null}, "v": 1.688962384779952, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "acceleration": 0.2866423438767828, "steering_wheel_angle": -3.307241094349303, "front_wheel_angle": -0.1591026757697778, "heading_rate": -0.10586290891791993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.7190402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2948866520040973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.3441925470100546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7086069609072958, "gear": 1, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.112598035536815, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.7190402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 36.71194809470455, "y": -0.1416796159667877, "z": null, "yaw": 3.194245936410567, "pitch": null, "roll": null}, "v": 1.688962384779952, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "acceleration": 0.2866423438767828, "steering_wheel_angle": -3.307241094349303, "front_wheel_angle": -0.1591026757697778, "heading_rate": -0.10586290891791993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.7390401} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2948866520040973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.3441925470100546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.716952463984862, "gear": 1, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.112598035536815, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.7390401} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.75904, "x": 40.52484704605236, "y": 4.849038853373895, "z": null, "yaw": 3.1875865283045615, "pitch": null, "roll": null}, "v": 1.7197296109267672, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "acceleration": 0.2774803951322864, "steering_wheel_angle": -3.112598035536815, "front_wheel_angle": -0.14930169193003684, "heading_rate": -0.10104824503899919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.75904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2936318107745416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.155383315105271, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7197296109267672, "gear": 1, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.112598035536815, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.75904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 36.52484704605236, "y": -0.15096114662610471, "z": null, "yaw": 3.1875865283045615, "pitch": null, "roll": null}, "v": 1.7197296109267672, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "acceleration": 0.2774803951322864, "steering_wheel_angle": -3.112598035536815, "front_wheel_angle": -0.14930169193003684, "heading_rate": -0.10104824503899919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.77904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941533050648114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.155383315105271, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7278445049441236, "gear": 1, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9958961110971183, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.77904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 36.52484704605236, "y": -0.15096114662610471, "z": null, "yaw": 3.1875865283045615, "pitch": null, "roll": null}, "v": 1.7197296109267672, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "acceleration": 0.2774803951322864, "steering_wheel_angle": -3.112598035536815, "front_wheel_angle": -0.14930169193003684, "heading_rate": -0.10104824503899919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.79904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941533050648114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.155383315105271, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7305666195948757, "gear": 1, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9569010751691613, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.79904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 36.52484704605236, "y": -0.15096114662610471, "z": null, "yaw": 3.1875865283045615, "pitch": null, "roll": null}, "v": 1.7197296109267672, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "acceleration": 0.2774803951322864, "steering_wheel_angle": -3.112598035536815, "front_wheel_angle": -0.14930169193003684, "heading_rate": -0.10104824503899919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.81904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941533050648114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.155383315105271, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.736003941934354, "gear": 1, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9569010751691613, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.81904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 36.52484704605236, "y": -0.15096114662610471, "z": null, "yaw": 3.1875865283045615, "pitch": null, "roll": null}, "v": 1.7197296109267672, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "acceleration": 0.2774803951322864, "steering_wheel_angle": -3.112598035536815, "front_wheel_angle": -0.14930169193003684, "heading_rate": -0.10104824503899919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.84904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941533050648114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.155383315105271, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7468509719706742, "gear": 1, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9569010751691613, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.84904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941533050648114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.155383315105271, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7468509719706742, "gear": 1, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9569010751691613, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.85904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.86904, "x": 40.33436350801378, "y": 4.8408164661027655, "z": null, "yaw": 3.1813875841466803, "pitch": null, "roll": null}, "v": 1.7495569792194121, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "acceleration": 0.2703708114587471, "steering_wheel_angle": -2.9569010751691613, "front_wheel_angle": -0.14150469678025676, "heading_rate": -0.09735792536694608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.87904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2909293965413579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9163592804851397, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7549620968052457, "gear": 1, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9569010751691613, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.87904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 36.33436350801378, "y": -0.1591835338972345, "z": null, "yaw": 3.1813875841466803, "pitch": null, "roll": null}, "v": 1.7495569792194121, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "acceleration": 0.2703708114587471, "steering_wheel_angle": -2.9569010751691613, "front_wheel_angle": -0.14150469678025676, "heading_rate": -0.09735792536694608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.89904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29206317696345163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9163592804851397, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7574597138445556, "gear": 1, "accelerator_pedal_position": 0.2909293965413579, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.918131406761431, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.89904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 36.33436350801378, "y": -0.1591835338972345, "z": null, "yaw": 3.1813875841466803, "pitch": null, "roll": null}, "v": 1.7495569792194121, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "acceleration": 0.2703708114587471, "steering_wheel_angle": -2.9569010751691613, "front_wheel_angle": -0.14150469678025676, "heading_rate": -0.09735792536694608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.91904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29206317696345163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9163592804851397, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.762590232435115, "gear": 1, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.840452447177407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.91904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 36.33436350801378, "y": -0.1591835338972345, "z": null, "yaw": 3.1813875841466803, "pitch": null, "roll": null}, "v": 1.7495569792194121, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "acceleration": 0.2703708114587471, "steering_wheel_angle": -2.9569010751691613, "front_wheel_angle": -0.14150469678025676, "heading_rate": -0.09735792536694608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.93904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29206317696345163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9163592804851397, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7702696216466656, "gear": 1, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.7235849508799603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.93904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 36.33436350801378, "y": -0.1591835338972345, "z": null, "yaw": 3.1813875841466803, "pitch": null, "roll": null}, "v": 1.7495569792194121, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "acceleration": 0.2703708114587471, "steering_wheel_angle": -2.9569010751691613, "front_wheel_angle": -0.14150469678025676, "heading_rate": -0.09735792536694608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.95904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29206317696345163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9163592804851397, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7728250499427254, "gear": 1, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.7235849508799603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.95904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.97904, "x": 40.140615005445106, "y": 4.8336322959416655, "z": null, "yaw": 3.175520636570718, "pitch": null, "roll": null}, "v": 1.7779293577157833, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "acceleration": 0.2548880601255068, "steering_wheel_angle": -2.7235849508799603, "front_wheel_angle": -0.129890804581545, "heading_rate": -0.0907204135111752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.97904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2953413928190022, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8425772438521026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7806831268080103, "gear": 1, "accelerator_pedal_position": 0.2953413928190022, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.684619623709269, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.97904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 36.140615005445106, "y": -0.16636770405833445, "z": null, "yaw": 3.175520636570718, "pitch": null, "roll": null}, "v": 1.7779293577157833, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "acceleration": 0.2548880601255068, "steering_wheel_angle": -2.7235849508799603, "front_wheel_angle": -0.129890804581545, "heading_rate": -0.0907204135111752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.99904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2944379223067683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8425772438521026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.783434539055984, "gear": 1, "accelerator_pedal_position": 0.2953413928190022, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.645607954532138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.99904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 36.140615005445106, "y": -0.16636770405833445, "z": null, "yaw": 3.175520636570718, "pitch": null, "roll": null}, "v": 1.7779293577157833, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "acceleration": 0.2548880601255068, "steering_wheel_angle": -2.7235849508799603, "front_wheel_angle": -0.129890804581545, "heading_rate": -0.0907204135111752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.0190399} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2944379223067683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8425772438521026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7888174096235072, "gear": 1, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.645607954532138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.0190399} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 36.140615005445106, "y": -0.16636770405833445, "z": null, "yaw": 3.175520636570718, "pitch": null, "roll": null}, "v": 1.7779293577157833, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "acceleration": 0.2548880601255068, "steering_wheel_angle": -2.7235849508799603, "front_wheel_angle": -0.129890804581545, "heading_rate": -0.0907204135111752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.0390399} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2944379223067683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8425772438521026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7968744150527651, "gear": 1, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.645607954532138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.0390399} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 36.140615005445106, "y": -0.16636770405833445, "z": null, "yaw": 3.175520636570718, "pitch": null, "roll": null}, "v": 1.7779293577157833, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "acceleration": 0.2548880601255068, "steering_wheel_angle": -2.7235849508799603, "front_wheel_angle": -0.129890804581545, "heading_rate": -0.0907204135111752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.0590398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2944379223067683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8425772438521026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7995554722230647, "gear": 1, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.645607954532138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.0590398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 36.140615005445106, "y": -0.16636770405833445, "z": null, "yaw": 3.175520636570718, "pitch": null, "roll": null}, "v": 1.7779293577157833, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "acceleration": 0.2548880601255068, "steering_wheel_angle": -2.7235849508799603, "front_wheel_angle": -0.129890804581545, "heading_rate": -0.0907204135111752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.0790398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2944379223067683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8425772438521026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8075848174072195, "gear": 1, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.645607954532138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.0790398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.0890398, "x": 39.94364991917917, "y": 4.827440490640906, "z": null, "yaw": 3.170053518827438, "pitch": null, "roll": null}, "v": 1.8075848174072195, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "acceleration": 0.26718414482572994, "steering_wheel_angle": -2.645607954532138, "front_wheel_angle": -0.12602778902438197, "heading_rate": -0.089460824533111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.0990398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2925906742710726, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6466968110503561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.810256658855477, "gear": 1, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.645607954532138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.0990398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 35.94364991917917, "y": -0.17255950935909414, "z": null, "yaw": 3.170053518827438, "pitch": null, "roll": null}, "v": 1.8075848174072195, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "acceleration": 0.26718414482572994, "steering_wheel_angle": -2.645607954532138, "front_wheel_angle": -0.12602778902438197, "heading_rate": -0.089460824533111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.1190398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29329524342895436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6466968110503561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8153626282408362, "gear": 1, "accelerator_pedal_position": 0.2925906742710726, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.5678858192026772, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.1190398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 35.94364991917917, "y": -0.17255950935909414, "z": null, "yaw": 3.170053518827438, "pitch": null, "roll": null}, "v": 1.8075848174072195, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "acceleration": 0.26718414482572994, "steering_wheel_angle": -2.645607954532138, "front_wheel_angle": -0.12602778902438197, "heading_rate": -0.089460824533111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.1390398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29329524342895436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6466968110503561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8231370628727626, "gear": 1, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.450958950687865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.1390398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 35.94364991917917, "y": -0.17255950935909414, "z": null, "yaw": 3.170053518827438, "pitch": null, "roll": null}, "v": 1.8075848174072195, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "acceleration": 0.26718414482572994, "steering_wheel_angle": -2.645607954532138, "front_wheel_angle": -0.12602778902438197, "heading_rate": -0.089460824533111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.1590397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29329524342895436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6466968110503561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8257240641806338, "gear": 1, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.450958950687865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.1590397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 35.94364991917917, "y": -0.17255950935909414, "z": null, "yaw": 3.170053518827438, "pitch": null, "roll": null}, "v": 1.8075848174072195, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "acceleration": 0.26718414482572994, "steering_wheel_angle": -2.645607954532138, "front_wheel_angle": -0.12602778902438197, "heading_rate": -0.089460824533111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.1790397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29329524342895436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6466968110503561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8334716457316518, "gear": 1, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.450958950687865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.1790397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.1990397, "x": 39.74345759630508, "y": 4.822223150545385, "z": null, "yaw": 3.164875931346321, "pitch": null, "roll": null}, "v": 1.8360497007955254, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "acceleration": 0.2575820013532749, "steering_wheel_angle": -2.450958950687865, "front_wheel_angle": -0.11642457962881146, "heading_rate": -0.0838798446540698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.1990397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.294545986640303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5294054567036064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8360497007955254, "gear": 1, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.450958950687865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.1990397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 35.74345759630508, "y": -0.1777768494546148, "z": null, "yaw": 3.164875931346321, "pitch": null, "roll": null}, "v": 1.8360497007955254, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "acceleration": 0.2575820013532749, "steering_wheel_angle": -2.450958950687865, "front_wheel_angle": -0.11642457962881146, "heading_rate": -0.0838798446540698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.2190397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2942781492354546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5294054567036064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8413553814518635, "gear": 1, "accelerator_pedal_position": 0.294545986640303, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3730401984672156, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.2190397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 35.74345759630508, "y": -0.1777768494546148, "z": null, "yaw": 3.164875931346321, "pitch": null, "roll": null}, "v": 1.8360497007955254, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "acceleration": 0.2575820013532749, "steering_wheel_angle": -2.450958950687865, "front_wheel_angle": -0.11642457962881146, "heading_rate": -0.0838798446540698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.2390397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2942781492354546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5294054567036064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8492464654359404, "gear": 1, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3340125479318177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.2390397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 35.74345759630508, "y": -0.1777768494546148, "z": null, "yaw": 3.164875931346321, "pitch": null, "roll": null}, "v": 1.8360497007955254, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "acceleration": 0.2575820013532749, "steering_wheel_angle": -2.450958950687865, "front_wheel_angle": -0.11642457962881146, "heading_rate": -0.0838798446540698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.2590396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2942781492354546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5294054567036064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8518722552814455, "gear": 1, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3340125479318177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.2590396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 35.74345759630508, "y": -0.1777768494546148, "z": null, "yaw": 3.164875931346321, "pitch": null, "roll": null}, "v": 1.8360497007955254, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "acceleration": 0.2575820013532749, "steering_wheel_angle": -2.450958950687865, "front_wheel_angle": -0.11642457962881146, "heading_rate": -0.0838798446540698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.2790396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2942781492354546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5294054567036064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8597359188787814, "gear": 1, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3340125479318177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.2790396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 35.74345759630508, "y": -0.1777768494546148, "z": null, "yaw": 3.164875931346321, "pitch": null, "roll": null}, "v": 1.8360497007955254, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "acceleration": 0.2575820013532749, "steering_wheel_angle": -2.450958950687865, "front_wheel_angle": -0.11642457962881146, "heading_rate": -0.0838798446540698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.2990396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2942781492354546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5294054567036064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.862352573477761, "gear": 1, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3340125479318177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.2990396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.3090396, "x": 39.54008758103605, "y": 4.817937941951472, "z": null, "yaw": 3.1600551101479155, "pitch": null, "roll": null}, "v": 1.8649669458074443, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "acceleration": 0.26120906834167545, "steering_wheel_angle": -2.3340125479318177, "front_wheel_angle": -0.11068191180466777, "heading_rate": -0.08096295521734155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.3190396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29462344722324824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4163242328172074, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.867579036490861, "gear": 1, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3340125479318177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.3190396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 35.54008758103605, "y": -0.18206205804852793, "z": null, "yaw": 3.1600551101479155, "pitch": null, "roll": null}, "v": 1.8649669458074443, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "acceleration": 0.26120906834167545, "steering_wheel_angle": -2.3340125479318177, "front_wheel_angle": -0.11068191180466777, "heading_rate": -0.08096295521734155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.3390396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2946413463289096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4163242328172074, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8728395188118985, "gear": 1, "accelerator_pedal_position": 0.29462344722324824, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2560713165382955, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.3390396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 35.54008758103605, "y": -0.18206205804852793, "z": null, "yaw": 3.1600551101479155, "pitch": null, "roll": null}, "v": 1.8649669458074443, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "acceleration": 0.26120906834167545, "steering_wheel_angle": -2.3340125479318177, "front_wheel_angle": -0.11068191180466777, "heading_rate": -0.08096295521734155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.3590395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2946413463289096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4163242328172074, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8780930430338243, "gear": 1, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2170328628722777, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.3590395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 35.54008758103605, "y": -0.18206205804852793, "z": null, "yaw": 3.1600551101479155, "pitch": null, "roll": null}, "v": 1.8649669458074443, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "acceleration": 0.26120906834167545, "steering_wheel_angle": -2.3340125479318177, "front_wheel_angle": -0.11068191180466777, "heading_rate": -0.08096295521734155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.3790395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2946413463289096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4163242328172074, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8833373738752714, "gear": 1, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2170328628722777, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.3790395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 35.54008758103605, "y": -0.18206205804852793, "z": null, "yaw": 3.1600551101479155, "pitch": null, "roll": null}, "v": 1.8649669458074443, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "acceleration": 0.26120906834167545, "steering_wheel_angle": -2.3340125479318177, "front_wheel_angle": -0.11068191180466777, "heading_rate": -0.08096295521734155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.3990395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2946413463289096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4163242328172074, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8885725164277691, "gear": 1, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2170328628722777, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.3990395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.4190395, "x": 39.33352609979971, "y": 4.814561542705868, "z": null, "yaw": 3.155460716914593, "pitch": null, "roll": null}, "v": 1.8937984758317072, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "acceleration": 0.2609537640934746, "steering_wheel_angle": -2.2170328628722777, "front_wheel_angle": -0.10495762889770956, "heading_rate": -0.07793035679955877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.4190395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2934775404176858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2455386156618735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.896408013472642, "gear": 1, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2170328628722777, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.4190395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 35.33352609979971, "y": -0.1854384572941319, "z": null, "yaw": 3.155460716914593, "pitch": null, "roll": null}, "v": 1.8937984758317072, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "acceleration": 0.2609537640934746, "steering_wheel_angle": -2.2170328628722777, "front_wheel_angle": -0.10495762889770956, "heading_rate": -0.07793035679955877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.4390395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2939674943902968, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2455386156618735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.906624450293653, "gear": 1, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.061179089878834, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.4390395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 35.33352609979971, "y": -0.1854384572941319, "z": null, "yaw": 3.155460716914593, "pitch": null, "roll": null}, "v": 1.8937984758317072, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "acceleration": 0.2609537640934746, "steering_wheel_angle": -2.2170328628722777, "front_wheel_angle": -0.10495762889770956, "heading_rate": -0.07793035679955877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.4690394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2939674943902968, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2455386156618735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.906624450293653, "gear": 1, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.061179089878834, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.4690394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 35.33352609979971, "y": -0.1854384572941319, "z": null, "yaw": 3.155460716914593, "pitch": null, "roll": null}, "v": 1.8937984758317072, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "acceleration": 0.2609537640934746, "steering_wheel_angle": -2.2170328628722777, "front_wheel_angle": -0.10495762889770956, "heading_rate": -0.07793035679955877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.4890394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2939674943902968, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2455386156618735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.914286094144601, "gear": 1, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.061179089878834, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.4890394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 35.33352609979971, "y": -0.1854384572941319, "z": null, "yaw": 3.155460716914593, "pitch": null, "roll": null}, "v": 1.8937984758317072, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "acceleration": 0.2609537640934746, "steering_wheel_angle": -2.2170328628722777, "front_wheel_angle": -0.10495762889770956, "heading_rate": -0.07793035679955877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.5090394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2939674943902968, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2455386156618735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9168354703718986, "gear": 1, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.061179089878834, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.5090394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.5290394, "x": 39.123813401798905, "y": 4.8120714128793916, "z": null, "yaw": 3.1511590265545477, "pitch": null, "roll": null}, "v": 1.921927469361164, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "acceleration": 0.2542624144964466, "steering_wheel_angle": -2.061179089878834, "front_wheel_angle": -0.09736183153816765, "heading_rate": -0.07332652099331632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.5290394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29403088714574593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1137239466760775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9244740555533442, "gear": 1, "accelerator_pedal_position": 0.29403088714574593, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.022247150120725, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.5290394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 35.123813401798905, "y": -0.18792858712060845, "z": null, "yaw": 3.1511590265545477, "pitch": null, "roll": null}, "v": 1.921927469361164, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "acceleration": 0.2542624144964466, "steering_wheel_angle": -2.061179089878834, "front_wheel_angle": -0.09736183153816765, "heading_rate": -0.07332652099331632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.5490394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29413506572700776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1137239466760775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9270183889331267, "gear": 1, "accelerator_pedal_position": 0.29403088714574593, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.98327074568462, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.5490394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 35.123813401798905, "y": -0.18792858712060845, "z": null, "yaw": 3.1511590265545477, "pitch": null, "roll": null}, "v": 1.921927469361164, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "acceleration": 0.2542624144964466, "steering_wheel_angle": -2.061179089878834, "front_wheel_angle": -0.09736183153816765, "heading_rate": -0.07332652099331632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.5690393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29413506572700776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1137239466760775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9321133166031725, "gear": 1, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9442498765705194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.5690393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 35.123813401798905, "y": -0.18792858712060845, "z": null, "yaw": 3.1511590265545477, "pitch": null, "roll": null}, "v": 1.921927469361164, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "acceleration": 0.2542624144964466, "steering_wheel_angle": -2.061179089878834, "front_wheel_angle": -0.09736183153816765, "heading_rate": -0.07332652099331632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.5890393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29413506572700776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1137239466760775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9371992183525, "gear": 1, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9442498765705194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.5890393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 35.123813401798905, "y": -0.18792858712060845, "z": null, "yaw": 3.1511590265545477, "pitch": null, "roll": null}, "v": 1.921927469361164, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "acceleration": 0.2542624144964466, "steering_wheel_angle": -2.061179089878834, "front_wheel_angle": -0.09736183153816765, "heading_rate": -0.07332652099331632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.6090393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29413506572700776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1137239466760775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.94227609982901, "gear": 1, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9442498765705194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.6090393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 35.123813401798905, "y": -0.18792858712060845, "z": null, "yaw": 3.1511590265545477, "pitch": null, "roll": null}, "v": 1.921927469361164, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "acceleration": 0.2542624144964466, "steering_wheel_angle": -2.061179089878834, "front_wheel_angle": -0.09736183153816765, "heading_rate": -0.07332652099331632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.6290393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29413506572700776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1137239466760775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9473439667255978, "gear": 1, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9442498765705194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.6290393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.6390393, "x": 38.91100862753623, "y": 4.810426850383858, "z": null, "yaw": 3.147163585334509, "pitch": null, "roll": null}, "v": 1.9498745214976987, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "acceleration": 0.25283032822305473, "steering_wheel_angle": -1.9442498765705194, "front_wheel_angle": -0.09168589049959114, "heading_rate": -0.0700307110918112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.6490393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29558802245693416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0450285171512055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9524028247799292, "gear": 1, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9442498765705194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.6490393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 34.91100862753623, "y": -0.1895731496161419, "z": null, "yaw": 3.147163585334509, "pitch": null, "roll": null}, "v": 1.9498745214976987, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "acceleration": 0.25283032822305473, "steering_wheel_angle": -1.9442498765705194, "front_wheel_angle": -0.09168589049959114, "heading_rate": -0.0700307110918112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.6690392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29525794361880736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0450285171512055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9576342184543973, "gear": 1, "accelerator_pedal_position": 0.29558802245693416, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.866223729501545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.6690392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 34.91100862753623, "y": -0.1895731496161419, "z": null, "yaw": 3.147163585334509, "pitch": null, "roll": null}, "v": 1.9498745214976987, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "acceleration": 0.25283032822305473, "steering_wheel_angle": -1.9442498765705194, "front_wheel_angle": -0.09168589049959114, "heading_rate": -0.0700307110918112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.6890392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29525794361880736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0450285171512055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9628150497147305, "gear": 1, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.866223729501545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.6890392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 34.91100862753623, "y": -0.1895731496161419, "z": null, "yaw": 3.147163585334509, "pitch": null, "roll": null}, "v": 1.9498745214976987, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "acceleration": 0.25283032822305473, "steering_wheel_angle": -1.9442498765705194, "front_wheel_angle": -0.09168589049959114, "heading_rate": -0.0700307110918112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.7090392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29525794361880736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0450285171512055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9679866393486838, "gear": 1, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.866223729501545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.7090392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 34.91100862753623, "y": -0.1895731496161419, "z": null, "yaw": 3.147163585334509, "pitch": null, "roll": null}, "v": 1.9498745214976987, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "acceleration": 0.25283032822305473, "steering_wheel_angle": -1.9442498765705194, "front_wheel_angle": -0.09168589049959114, "heading_rate": -0.0700307110918112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.7290392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29525794361880736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0450285171512055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9731489931482167, "gear": 1, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.866223729501545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.7290392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.7490392, "x": 38.69510227372672, "y": 4.809603412612841, "z": null, "yaw": 3.143339298949896, "pitch": null, "roll": null}, "v": 1.9783021169522192, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "acceleration": 0.2573102491105586, "steering_wheel_angle": -1.866223729501545, "front_wheel_angle": -0.0879091330537877, "heading_rate": -0.0681094564070379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.7490392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2950501648541503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9060048620890677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9783021169522192, "gear": 1, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.866223729501545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.7490392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 34.69510227372672, "y": -0.19039658738715914, "z": null, "yaw": 3.143339298949896, "pitch": null, "roll": null}, "v": 1.9783021169522192, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "acceleration": 0.2573102491105586, "steering_wheel_angle": -1.866223729501545, "front_wheel_angle": -0.0879091330537877, "heading_rate": -0.0681094564070379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.7690392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29524199914069416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9060048620890677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.983420055938563, "gear": 1, "accelerator_pedal_position": 0.2950501648541503, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.7883200028009507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.7690392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 34.69510227372672, "y": -0.19039658738715914, "z": null, "yaw": 3.143339298949896, "pitch": null, "roll": null}, "v": 1.9783021169522192, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "acceleration": 0.2573102491105586, "steering_wheel_angle": -1.866223729501545, "front_wheel_angle": -0.0879091330537877, "heading_rate": -0.0681094564070379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.7890391} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29524199914069416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9060048620890677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9885527918387358, "gear": 1, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.710240447367367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.7890391} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 34.69510227372672, "y": -0.19039658738715914, "z": null, "yaw": 3.143339298949896, "pitch": null, "roll": null}, "v": 1.9783021169522192, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "acceleration": 0.2573102491105586, "steering_wheel_angle": -1.866223729501545, "front_wheel_angle": -0.0879091330537877, "heading_rate": -0.0681094564070379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.809039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29524199914069416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9060048620890677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9936763190861908, "gear": 1, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.710240447367367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.809039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 34.69510227372672, "y": -0.19039658738715914, "z": null, "yaw": 3.143339298949896, "pitch": null, "roll": null}, "v": 1.9783021169522192, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "acceleration": 0.2573102491105586, "steering_wheel_angle": -1.866223729501545, "front_wheel_angle": -0.0879091330537877, "heading_rate": -0.0681094564070379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.829039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29524199914069416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9060048620890677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.001344356927397, "gear": 1, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.710240447367367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.829039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 34.69510227372672, "y": -0.19039658738715914, "z": null, "yaw": 3.143339298949896, "pitch": null, "roll": null}, "v": 1.9783021169522192, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "acceleration": 0.2573102491105586, "steering_wheel_angle": -1.866223729501545, "front_wheel_angle": -0.0879091330537877, "heading_rate": -0.0681094564070379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.849039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29524199914069416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9060048620890677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.003895771771726, "gear": 1, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.710240447367367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.849039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.859039, "x": 38.476080565423295, "y": 4.809579630493256, "z": null, "yaw": 3.139803823684501, "pitch": null, "roll": null}, "v": 2.006444889005721, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "acceleration": 0.2546820392528806, "steering_wheel_angle": -1.710240447367367, "front_wheel_angle": -0.08038452360066012, "heading_rate": -0.06313883265000647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.869039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29575973654584603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7704568356398145, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.00899170939825, "gear": 1, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.710240447367367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.869039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 34.476080565423295, "y": -0.1904203695067439, "z": null, "yaw": 3.139803823684501, "pitch": null, "roll": null}, "v": 2.006444889005721, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "acceleration": 0.2546820392528806, "steering_wheel_angle": -1.710240447367367, "front_wheel_angle": -0.08038452360066012, "heading_rate": -0.06313883265000647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.889039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2957243714270224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7704568356398145, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0141431507266274, "gear": 1, "accelerator_pedal_position": 0.29575973654584603, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6322751884717082, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.889039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 34.476080565423295, "y": -0.1904203695067439, "z": null, "yaw": 3.139803823684501, "pitch": null, "roll": null}, "v": 2.006444889005721, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "acceleration": 0.2546820392528806, "steering_wheel_angle": -1.710240447367367, "front_wheel_angle": -0.08038452360066012, "heading_rate": -0.06313883265000647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.909039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2957243714270224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7704568356398145, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0192808785258656, "gear": 1, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5932271107008547, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.909039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 34.476080565423295, "y": -0.1904203695067439, "z": null, "yaw": 3.139803823684501, "pitch": null, "roll": null}, "v": 2.006444889005721, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "acceleration": 0.2546820392528806, "steering_wheel_angle": -1.710240447367367, "front_wheel_angle": -0.08038452360066012, "heading_rate": -0.06313883265000647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.929039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2957243714270224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7704568356398145, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0244093256268303, "gear": 1, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5932271107008547, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.929039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 34.476080565423295, "y": -0.1904203695067439, "z": null, "yaw": 3.139803823684501, "pitch": null, "roll": null}, "v": 2.006444889005721, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "acceleration": 0.2546820392528806, "steering_wheel_angle": -1.710240447367367, "front_wheel_angle": -0.08038452360066012, "heading_rate": -0.06313883265000647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.949039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2957243714270224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7704568356398145, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.029528498278374, "gear": 1, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5932271107008547, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.949039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.969039, "x": 38.25396206853528, "y": 4.810314645387885, "z": null, "yaw": 3.1365191135984665, "pitch": null, "roll": null}, "v": 2.0346384027750832, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "acceleration": 0.2551478669796643, "steering_wheel_angle": -1.5932271107008547, "front_wheel_angle": -0.07476196576259385, "heading_rate": -0.059530315259257685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.969039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29624791386599536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6570970981282475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0346384027750832, "gear": 1, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5932271107008547, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.969039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 34.25396206853528, "y": -0.18968535461211466, "z": null, "yaw": 3.1365191135984665, "pitch": null, "roll": null}, "v": 2.0346384027750832, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "acceleration": 0.2551478669796643, "steering_wheel_angle": -1.5932271107008547, "front_wheel_angle": -0.07476196576259385, "heading_rate": -0.059530315259257685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.989039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2962117567832483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6570970981282475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0398044585691615, "gear": 1, "accelerator_pedal_position": 0.29624791386599536, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5152410367229452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.989039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 34.25396206853528, "y": -0.18968535461211466, "z": null, "yaw": 3.1365191135984665, "pitch": null, "roll": null}, "v": 2.0346384027750832, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "acceleration": 0.2551478669796643, "steering_wheel_angle": -1.5932271107008547, "front_wheel_angle": -0.07476196576259385, "heading_rate": -0.059530315259257685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.009039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2962117567832483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6570970981282475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0449566225540967, "gear": 1, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.47618295357009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.009039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 34.25396206853528, "y": -0.18968535461211466, "z": null, "yaw": 3.1365191135984665, "pitch": null, "roll": null}, "v": 2.0346384027750832, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "acceleration": 0.2551478669796643, "steering_wheel_angle": -1.5932271107008547, "front_wheel_angle": -0.07476196576259385, "heading_rate": -0.059530315259257685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.029039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2962117567832483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6570970981282475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.050099426904627, "gear": 1, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.47618295357009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.029039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 34.25396206853528, "y": -0.18968535461211466, "z": null, "yaw": 3.1365191135984665, "pitch": null, "roll": null}, "v": 2.0346384027750832, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "acceleration": 0.2551478669796643, "steering_wheel_angle": -1.5932271107008547, "front_wheel_angle": -0.07476196576259385, "heading_rate": -0.059530315259257685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.049039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2962117567832483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6570970981282475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0552328780492872, "gear": 1, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.47618295357009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.049039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 34.25396206853528, "y": -0.18968535461211466, "z": null, "yaw": 3.1365191135984665, "pitch": null, "roll": null}, "v": 2.0346384027750832, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "acceleration": 0.2551478669796643, "steering_wheel_angle": -1.5932271107008547, "front_wheel_angle": -0.07476196576259385, "heading_rate": -0.059530315259257685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.0690389} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2962117567832483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6570970981282475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.060356982462599, "gear": 1, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.47618295357009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.0690389} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.0790389, "x": 38.02874000583172, "y": 4.811771221091385, "z": null, "yaw": 3.1334987750664545, "pitch": null, "roll": null}, "v": 2.0629155316808023, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "acceleration": 0.25562149840276277, "steering_wheel_angle": -1.47618295357009, "front_wheel_angle": -0.06915670895742594, "heading_rate": -0.055817313685909385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.0890388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29660748283908617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5517068274350262, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.06547174666483, "gear": 1, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.47618295357009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.0890388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 34.02874000583172, "y": -0.18822877890861456, "z": null, "yaw": 3.1334987750664545, "pitch": null, "roll": null}, "v": 2.0629155316808023, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "acceleration": 0.25562149840276277, "steering_wheel_angle": -1.47618295357009, "front_wheel_angle": -0.06915670895742594, "heading_rate": -0.055817313685909385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.1090388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29661244480255583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5517068274350262, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.070626620382588, "gear": 1, "accelerator_pedal_position": 0.29660748283908617, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3981594863883593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.1090388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 34.02874000583172, "y": -0.18822877890861456, "z": null, "yaw": 3.1334987750664545, "pitch": null, "roll": null}, "v": 2.0629155316808023, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "acceleration": 0.25562149840276277, "steering_wheel_angle": -1.47618295357009, "front_wheel_angle": -0.06915670895742594, "heading_rate": -0.055817313685909385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.1290388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29661244480255583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5517068274350262, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0757726966245107, "gear": 1, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3981594863883593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.1290388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 34.02874000583172, "y": -0.18822877890861456, "z": null, "yaw": 3.1334987750664545, "pitch": null, "roll": null}, "v": 2.0629155316808023, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "acceleration": 0.25562149840276277, "steering_wheel_angle": -1.47618295357009, "front_wheel_angle": -0.06915670895742594, "heading_rate": -0.055817313685909385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.1490388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29661244480255583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5517068274350262, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.080909360913244, "gear": 1, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3981594863883593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.1490388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 34.02874000583172, "y": -0.18822877890861456, "z": null, "yaw": 3.1334987750664545, "pitch": null, "roll": null}, "v": 2.0629155316808023, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "acceleration": 0.25562149840276277, "steering_wheel_angle": -1.47618295357009, "front_wheel_angle": -0.06915670895742594, "heading_rate": -0.055817313685909385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.1690388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29661244480255583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5517068274350262, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0860366199135494, "gear": 1, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3981594863883593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.1690388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.1890388, "x": 37.800416217154975, "y": 4.813919221746631, "z": null, "yaw": 3.130646736140144, "pitch": null, "roll": null}, "v": 2.091154480335917, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "acceleration": 0.25554078539288827, "steering_wheel_angle": -1.3981594863883593, "front_wheel_angle": -0.065430499280994, "heading_rate": -0.053523778593964955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.1890388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2974969823913044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.46083181126322786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.091154480335917, "gear": 1, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3981594863883593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.1890388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 33.800416217154975, "y": -0.18608077825336888, "z": null, "yaw": 3.130646736140144, "pitch": null, "roll": null}, "v": 2.091154480335917, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "acceleration": 0.25554078539288827, "steering_wheel_angle": -1.3981594863883593, "front_wheel_angle": -0.065430499280994, "heading_rate": -0.053523778593964955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.2090387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2973498149548573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.46083181126322786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096373465343245, "gear": 1, "accelerator_pedal_position": 0.2974969823913044, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.320154555830319, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.2090387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 33.800416217154975, "y": -0.18608077825336888, "z": null, "yaw": 3.130646736140144, "pitch": null, "roll": null}, "v": 2.091154480335917, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "acceleration": 0.25554078539288827, "steering_wheel_angle": -1.3981594863883593, "front_wheel_angle": -0.065430499280994, "heading_rate": -0.053523778593964955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.2290387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2973498149548573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.46083181126322786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1015644746524904, "gear": 1, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.28108772910245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.2290387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 33.800416217154975, "y": -0.18608077825336888, "z": null, "yaw": 3.130646736140144, "pitch": null, "roll": null}, "v": 2.091154480335917, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "acceleration": 0.25554078539288827, "steering_wheel_angle": -1.3981594863883593, "front_wheel_angle": -0.065430499280994, "heading_rate": -0.053523778593964955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.2490387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2973498149548573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.46083181126322786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1067459363462007, "gear": 1, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.28108772910245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.2490387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 33.800416217154975, "y": -0.18608077825336888, "z": null, "yaw": 3.130646736140144, "pitch": null, "roll": null}, "v": 2.091154480335917, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "acceleration": 0.25554078539288827, "steering_wheel_angle": -1.3981594863883593, "front_wheel_angle": -0.065430499280994, "heading_rate": -0.053523778593964955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.2690387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2973498149548573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.46083181126322786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1119178572508472, "gear": 1, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.28108772910245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.2690387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 33.800416217154975, "y": -0.18608077825336888, "z": null, "yaw": 3.130646736140144, "pitch": null, "roll": null}, "v": 2.091154480335917, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "acceleration": 0.25554078539288827, "steering_wheel_angle": -1.3981594863883593, "front_wheel_angle": -0.065430499280994, "heading_rate": -0.053523778593964955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.2890387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2973498149548573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.46083181126322786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1170802442396104, "gear": 1, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.28108772910245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.2890387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.2990386, "x": 37.56897776872049, "y": 4.816732813650203, "z": null, "yaw": 3.128028045401894, "pitch": null, "roll": null}, "v": 2.1196578646761144, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "acceleration": 0.2575239556012192, "steering_wheel_angle": -1.28108772910245, "front_wheel_angle": -0.059854822679091375, "heading_rate": -0.04961854425630035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.3090386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2982589081304502, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.33125075809187166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1222331042321265, "gear": 1, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.28108772910245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.3090386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 33.56897776872049, "y": -0.18326718634979677, "z": null, "yaw": 3.128028045401894, "pitch": null, "roll": null}, "v": 2.1196578646761144, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "acceleration": 0.2575239556012192, "steering_wheel_angle": -1.28108772910245, "front_wheel_angle": -0.059854822679091375, "heading_rate": -0.04961854425630035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.3290386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2981060860750571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.33125075809187166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1274900282861187, "gear": 1, "accelerator_pedal_position": 0.2982589081304502, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2030962015667142, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.3290386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 33.56897776872049, "y": -0.18326718634979677, "z": null, "yaw": 3.128028045401894, "pitch": null, "roll": null}, "v": 2.1196578646761144, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "acceleration": 0.2575239556012192, "steering_wheel_angle": -1.28108772910245, "front_wheel_angle": -0.059854822679091375, "heading_rate": -0.04961854425630035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.3490386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2981060860750571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.33125075809187166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1327181351475617, "gear": 1, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1640365205761185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.3490386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 33.56897776872049, "y": -0.18326718634979677, "z": null, "yaw": 3.128028045401894, "pitch": null, "roll": null}, "v": 2.1196578646761144, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "acceleration": 0.2575239556012192, "steering_wheel_angle": -1.28108772910245, "front_wheel_angle": -0.059854822679091375, "heading_rate": -0.04961854425630035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.3690386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2981060860750571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.33125075809187166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1379365610911, "gear": 1, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1640365205761185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.3690386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 33.56897776872049, "y": -0.18326718634979677, "z": null, "yaw": 3.128028045401894, "pitch": null, "roll": null}, "v": 2.1196578646761144, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "acceleration": 0.2575239556012192, "steering_wheel_angle": -1.28108772910245, "front_wheel_angle": -0.059854822679091375, "heading_rate": -0.04961854425630035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.3890386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2981060860750571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.33125075809187166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1431453131552094, "gear": 1, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1640365205761185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.3890386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.4090385, "x": 37.33440544908093, "y": 4.820176962590474, "z": null, "yaw": 3.125627290703294, "pitch": null, "roll": null}, "v": 2.14834439842585, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "acceleration": 0.25959198150533713, "steering_wheel_angle": -1.1640365205761185, "front_wheel_angle": -0.05429842120150911, "heading_rate": -0.045611908799266965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.4090385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29836399956769866, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2598740965266701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.14834439842585, "gear": 1, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1640365205761185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.4090385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 33.33440544908093, "y": -0.179823037409526, "z": null, "yaw": 3.125627290703294, "pitch": null, "roll": null}, "v": 2.14834439842585, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "acceleration": 0.25959198150533713, "steering_wheel_angle": -1.1640365205761185, "front_wheel_angle": -0.05429842120150911, "heading_rate": -0.045611908799266965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.4290385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29841633506541854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2598740965266701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.153566048228511, "gear": 1, "accelerator_pedal_position": 0.29836399956769866, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0859378039822096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.4290385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 33.33440544908093, "y": -0.179823037409526, "z": null, "yaw": 3.125627290703294, "pitch": null, "roll": null}, "v": 2.14834439842585, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "acceleration": 0.25959198150533713, "steering_wheel_angle": -1.1640365205761185, "front_wheel_angle": -0.05429842120150911, "heading_rate": -0.045611908799266965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.4490385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29841633506541854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2598740965266701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1587845244538784, "gear": 1, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0859378039822096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.4490385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 33.33440544908093, "y": -0.179823037409526, "z": null, "yaw": 3.125627290703294, "pitch": null, "roll": null}, "v": 2.14834439842585, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "acceleration": 0.25959198150533713, "steering_wheel_angle": -1.1640365205761185, "front_wheel_angle": -0.05429842120150911, "heading_rate": -0.045611908799266965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.4690385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29841633506541854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2598740965266701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1639932832292414, "gear": 1, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0859378039822096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.4690385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 33.33440544908093, "y": -0.179823037409526, "z": null, "yaw": 3.125627290703294, "pitch": null, "roll": null}, "v": 2.14834439842585, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "acceleration": 0.25959198150533713, "steering_wheel_angle": -1.1640365205761185, "front_wheel_angle": -0.05429842120150911, "heading_rate": -0.045611908799266965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.4890385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29841633506541854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2598740965266701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1691923318022877, "gear": 1, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0859378039822096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.4890385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 33.33440544908093, "y": -0.179823037409526, "z": null, "yaw": 3.125627290703294, "pitch": null, "roll": null}, "v": 2.14834439842585, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "acceleration": 0.25959198150533713, "steering_wheel_angle": -1.1640365205761185, "front_wheel_angle": -0.05429842120150911, "heading_rate": -0.045611908799266965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.5090384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29841633506541854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2598740965266701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.174381677467841, "gear": 1, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0859378039822096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.5090384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.5190384, "x": 37.096688077958035, "y": 4.824212840268965, "z": null, "yaw": 3.1234294412578274, "pitch": null, "roll": null}, "v": 2.1769727140027646, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "acceleration": 0.25886135648360187, "steering_wheel_angle": -1.0859378039822096, "front_wheel_angle": -0.05060117503820693, "heading_rate": -0.043066989177701666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.5290384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2991992116450804, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16558050045049277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1795613275676007, "gear": 1, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0859378039822096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.5290384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 33.096688077958035, "y": -0.1757871597310352, "z": null, "yaw": 3.1234294412578274, "pitch": null, "roll": null}, "v": 2.1769727140027646, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "acceleration": 0.25886135648360187, "steering_wheel_angle": -1.0859378039822096, "front_wheel_angle": -0.05060117503820693, "heading_rate": -0.043066989177701666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.5490384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29908804670162537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16558050045049277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1848291032428047, "gear": 1, "accelerator_pedal_position": 0.2991992116450804, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0078645733021616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.5490384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 33.096688077958035, "y": -0.1757871597310352, "z": null, "yaw": 3.1234294412578274, "pitch": null, "roll": null}, "v": 2.1769727140027646, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "acceleration": 0.25886135648360187, "steering_wheel_angle": -1.0859378039822096, "front_wheel_angle": -0.05060117503820693, "heading_rate": -0.043066989177701666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.5690384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29908804670162537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16558050045049277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1900731257603194, "gear": 1, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0078645733021616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.5690384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 33.096688077958035, "y": -0.1757871597310352, "z": null, "yaw": 3.1234294412578274, "pitch": null, "roll": null}, "v": 2.1769727140027646, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "acceleration": 0.25886135648360187, "steering_wheel_angle": -1.0859378039822096, "front_wheel_angle": -0.05060117503820693, "heading_rate": -0.043066989177701666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.5890384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29908804670162537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16558050045049277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.195307317700953, "gear": 1, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0078645733021616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.5890384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 33.096688077958035, "y": -0.1757871597310352, "z": null, "yaw": 3.1234294412578274, "pitch": null, "roll": null}, "v": 2.1769727140027646, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "acceleration": 0.25886135648360187, "steering_wheel_angle": -1.0859378039822096, "front_wheel_angle": -0.05060117503820693, "heading_rate": -0.043066989177701666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.6090384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29908804670162537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16558050045049277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2005316865397875, "gear": 1, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0078645733021616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.6090384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.6290383, "x": 36.85582535440744, "y": 4.828816907906975, "z": null, "yaw": 3.1213760609101637, "pitch": null, "roll": null}, "v": 2.2057462397995287, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "acceleration": 0.2603598151512844, "steering_wheel_angle": -1.0078645733021616, "front_wheel_angle": -0.04691314383268309, "heading_rate": -0.04045096515669039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.6290383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.299639090641227, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08252677164855855, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2057462397995287, "gear": 1, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0078645733021616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.6290383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 32.85582535440744, "y": -0.17118309209302485, "z": null, "yaw": 3.1213760609101637, "pitch": null, "roll": null}, "v": 2.2057462397995287, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "acceleration": 0.2603598151512844, "steering_wheel_angle": -1.0078645733021616, "front_wheel_angle": -0.04691314383268309, "heading_rate": -0.04045096515669039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.6490383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2996018763386324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08252677164855855, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2110198331112256, "gear": 1, "accelerator_pedal_position": 0.299639090641227, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9297935599174404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.6490383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 32.85582535440744, "y": -0.17118309209302485, "z": null, "yaw": 3.1213760609101637, "pitch": null, "roll": null}, "v": 2.2057462397995287, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "acceleration": 0.2603598151512844, "steering_wheel_angle": -1.0078645733021616, "front_wheel_angle": -0.04691314383268309, "heading_rate": -0.04045096515669039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.6690383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2996018763386324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08252677164855855, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.216278846688106, "gear": 1, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9297935599174404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.6690383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 32.85582535440744, "y": -0.17118309209302485, "z": null, "yaw": 3.1213760609101637, "pitch": null, "roll": null}, "v": 2.2057462397995287, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "acceleration": 0.2603598151512844, "steering_wheel_angle": -1.0078645733021616, "front_wheel_angle": -0.04691314383268309, "heading_rate": -0.04045096515669039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.6890383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2996018763386324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08252677164855855, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2215279465187168, "gear": 1, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9297935599174404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.6890383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 32.85582535440744, "y": -0.17118309209302485, "z": null, "yaw": 3.1213760609101637, "pitch": null, "roll": null}, "v": 2.2057462397995287, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "acceleration": 0.2603598151512844, "steering_wheel_angle": -1.0078645733021616, "front_wheel_angle": -0.04691314383268309, "heading_rate": -0.04045096515669039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.7090383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2996018763386324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08252677164855855, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2267671402754026, "gear": 1, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9297935599174404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.7090383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 32.85582535440744, "y": -0.17118309209302485, "z": null, "yaw": 3.1213760609101637, "pitch": null, "roll": null}, "v": 2.2057462397995287, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "acceleration": 0.2603598151512844, "steering_wheel_angle": -1.0078645733021616, "front_wheel_angle": -0.04691314383268309, "heading_rate": -0.04045096515669039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.7290382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2996018763386324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08252677164855855, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.231996435678379, "gear": 1, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9297935599174404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.7290382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.7390382, "x": 36.61180155334639, "y": 4.8339623063422, "z": null, "yaw": 3.1194956216471166, "pitch": null, "roll": null}, "v": 2.234607373922816, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "acceleration": 0.26084665726440937, "steering_wheel_angle": -0.9297935599174404, "front_wheel_angle": -0.04323317233863132, "heading_rate": -0.037761485040426535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.7490382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2992638463076245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.013950478411688519, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.23721584049546, "gear": 1, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9297935599174404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.7490382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 32.61180155334639, "y": -0.16603769365779986, "z": null, "yaw": 3.1194956216471166, "pitch": null, "roll": null}, "v": 2.234607373922816, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "acceleration": 0.26084665726440937, "steering_wheel_angle": -0.9297935599174404, "front_wheel_angle": -0.04323317233863132, "heading_rate": -0.037761485040426535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.7690382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29950571050680147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.013950478411688519, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2423831288153933, "gear": 1, "accelerator_pedal_position": 0.2992638463076245, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8516603706092979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.7690382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 32.61180155334639, "y": -0.16603769365779986, "z": null, "yaw": 3.1194956216471166, "pitch": null, "roll": null}, "v": 2.234607373922816, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "acceleration": 0.26084665726440937, "steering_wheel_angle": -0.9297935599174404, "front_wheel_angle": -0.04323317233863132, "heading_rate": -0.037761485040426535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.7890382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29950571050680147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.013950478411688519, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2475708410277138, "gear": 1, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8516603706092979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.7890382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 32.61180155334639, "y": -0.16603769365779986, "z": null, "yaw": 3.1194956216471166, "pitch": null, "roll": null}, "v": 2.234607373922816, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "acceleration": 0.26084665726440937, "steering_wheel_angle": -0.9297935599174404, "front_wheel_angle": -0.04323317233863132, "heading_rate": -0.037761485040426535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.8090382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29950571050680147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.013950478411688519, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2527487089946208, "gear": 1, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8516603706092979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.8090382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 32.61180155334639, "y": -0.16603769365779986, "z": null, "yaw": 3.1194956216471166, "pitch": null, "roll": null}, "v": 2.234607373922816, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "acceleration": 0.26084665726440937, "steering_wheel_angle": -0.9297935599174404, "front_wheel_angle": -0.04323317233863132, "heading_rate": -0.037761485040426535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.8290381} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29950571050680147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.013950478411688519, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.257916740677601, "gear": 1, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8516603706092979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.8290381} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.8490381, "x": 36.36463428162872, "y": 4.839623904725449, "z": null, "yaw": 3.1177590191550646, "pitch": null, "roll": null}, "v": 2.263074944084088, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "acceleration": 0.25754186143789276, "steering_wheel_angle": -0.8516603706092979, "front_wheel_angle": -0.039558183140319454, "heading_rate": -0.03498822621099057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.8490381} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2863935316019894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08067060374779401, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.263074944084088, "gear": 1, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8516603706092979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.8490381} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 32.36463428162872, "y": -0.1603760952745512, "z": null, "yaw": 3.1177590191550646, "pitch": null, "roll": null}, "v": 2.263074944084088, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "acceleration": 0.25754186143789276, "steering_wheel_angle": -0.8516603706092979, "front_wheel_angle": -0.039558183140319454, "heading_rate": -0.03498822621099057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.869038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2906262782538268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08067060374779401, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2665850859376837, "gear": 1, "accelerator_pedal_position": 0.2863935316019894, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.773174338464776, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.869038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 32.36463428162872, "y": -0.1603760952745512, "z": null, "yaw": 3.1177590191550646, "pitch": null, "roll": null}, "v": 2.263074944084088, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "acceleration": 0.25754186143789276, "steering_wheel_angle": -0.8516603706092979, "front_wheel_angle": -0.039558183140319454, "heading_rate": -0.03498822621099057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.889038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2906262782538268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08067060374779401, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.270617380691857, "gear": 1, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.773174338464776, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.889038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 32.36463428162872, "y": -0.1603760952745512, "z": null, "yaw": 3.1177590191550646, "pitch": null, "roll": null}, "v": 2.263074944084088, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "acceleration": 0.25754186143789276, "steering_wheel_angle": -0.8516603706092979, "front_wheel_angle": -0.039558183140319454, "heading_rate": -0.03498822621099057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.909038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2906262782538268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08067060374779401, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.274641986127824, "gear": 1, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.773174338464776, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.909038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 32.36463428162872, "y": -0.1603760952745512, "z": null, "yaw": 3.1177590191550646, "pitch": null, "roll": null}, "v": 2.263074944084088, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "acceleration": 0.25754186143789276, "steering_wheel_angle": -0.8516603706092979, "front_wheel_angle": -0.039558183140319454, "heading_rate": -0.03498822621099057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.929038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2906262782538268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08067060374779401, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.278658910432715, "gear": 1, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.773174338464776, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.929038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 32.36463428162872, "y": -0.1603760952745512, "z": null, "yaw": 3.1177590191550646, "pitch": null, "roll": null}, "v": 2.263074944084088, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "acceleration": 0.25754186143789276, "steering_wheel_angle": -0.8516603706092979, "front_wheel_angle": -0.039558183140319454, "heading_rate": -0.03498822621099057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.949038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2906262782538268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08067060374779401, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2826681618151046, "gear": 1, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.773174338464776, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.949038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.959038, "x": 36.11471340858202, "y": 4.845761904140923, "z": null, "yaw": 3.116195260150512, "pitch": null, "roll": null}, "v": 2.2846699127313648, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "acceleration": 0.19998357734844985, "steering_wheel_angle": -0.773174338464776, "front_wheel_angle": -0.03587451665462896, "heading_rate": -0.032029924951956584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.969038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.276685337379066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.155133746033362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.286669748504849, "gear": 1, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.773174338464776, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.969038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 32.11471340858202, "y": -0.15423809585907744, "z": null, "yaw": 3.116195260150512, "pitch": null, "roll": null}, "v": 2.2846699127313648, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "acceleration": 0.19998357734844985, "steering_wheel_angle": -0.773174338464776, "front_wheel_angle": -0.03587451665462896, "heading_rate": -0.032029924951956584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.989038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811449759518132, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.155133746033362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.288921895549319, "gear": 1, "accelerator_pedal_position": 0.276685337379066, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.694364878610045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.989038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 32.11471340858202, "y": -0.15423809585907744, "z": null, "yaw": 3.116195260150512, "pitch": null, "roll": null}, "v": 2.2846699127313648, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "acceleration": 0.19998357734844985, "steering_wheel_angle": -0.773174338464776, "front_wheel_angle": -0.03587451665462896, "heading_rate": -0.032029924951956584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.009038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811449759518132, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.155133746033362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.291726918814635, "gear": 1, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.694364878610045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.009038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 32.11471340858202, "y": -0.15423809585907744, "z": null, "yaw": 3.116195260150512, "pitch": null, "roll": null}, "v": 2.2846699127313648, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "acceleration": 0.19998357734844985, "steering_wheel_angle": -0.773174338464776, "front_wheel_angle": -0.03587451665462896, "heading_rate": -0.032029924951956584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.029038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811449759518132, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.155133746033362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2945265690804004, "gear": 1, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.694364878610045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.029038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 32.11471340858202, "y": -0.15423809585907744, "z": null, "yaw": 3.116195260150512, "pitch": null, "roll": null}, "v": 2.2846699127313648, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "acceleration": 0.19998357734844985, "steering_wheel_angle": -0.773174338464776, "front_wheel_angle": -0.03587451665462896, "heading_rate": -0.032029924951956584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.049038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811449759518132, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.155133746033362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.297320853504836, "gear": 1, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.694364878610045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.049038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.069038, "x": 35.86270175715927, "y": 4.85233009548508, "z": null, "yaw": 3.114775807808298, "pitch": null, "roll": null}, "v": 2.300109779250462, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "acceleration": 0.13924556077027328, "steering_wheel_angle": -0.694364878610045, "front_wheel_angle": -0.032183604738648286, "heading_rate": -0.02892632533179134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.069038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2734935275971756, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2078725325277134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.300109779250462, "gear": 1, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.694364878610045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.069038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 31.86270175715927, "y": -0.14766990451492035, "z": null, "yaw": 3.114775807808298, "pitch": null, "roll": null}, "v": 2.300109779250462, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "acceleration": 0.13924556077027328, "steering_wheel_angle": -0.694364878610045, "front_wheel_angle": -0.032183604738648286, "heading_rate": -0.02892632533179134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.089038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27595860068375727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2078725325277134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.301937381647399, "gear": 1, "accelerator_pedal_position": 0.2734935275971756, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6548415105692499, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.089038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 31.86270175715927, "y": -0.14766990451492035, "z": null, "yaw": 3.114775807808298, "pitch": null, "roll": null}, "v": 2.300109779250462, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "acceleration": 0.13924556077027328, "steering_wheel_angle": -0.694364878610045, "front_wheel_angle": -0.032183604738648286, "heading_rate": -0.02892632533179134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.1090379} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27595860068375727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2078725325277134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3040694617922095, "gear": 1, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6548415105692499, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.1090379} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 31.86270175715927, "y": -0.14766990451492035, "z": null, "yaw": 3.114775807808298, "pitch": null, "roll": null}, "v": 2.300109779250462, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "acceleration": 0.13924556077027328, "steering_wheel_angle": -0.694364878610045, "front_wheel_angle": -0.032183604738648286, "heading_rate": -0.02892632533179134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.1290379} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27595860068375727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2078725325277134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3061974472951903, "gear": 1, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6548415105692499, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.1290379} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 31.86270175715927, "y": -0.14766990451492035, "z": null, "yaw": 3.114775807808298, "pitch": null, "roll": null}, "v": 2.300109779250462, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "acceleration": 0.13924556077027328, "steering_wheel_angle": -0.694364878610045, "front_wheel_angle": -0.032183604738648286, "heading_rate": -0.02892632533179134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.1590378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27595860068375727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2078725325277134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.309381761337424, "gear": 1, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6548415105692499, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.1590378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27595860068375727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2078725325277134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.31044115858753, "gear": 1, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6548415105692499, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.1690378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.1790378, "x": 35.6092282677087, "y": 4.859281225267133, "z": null, "yaw": 3.1134647003493026, "pitch": null, "roll": null}, "v": 2.3114995367162416, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "acceleration": 0.10573597635527682, "steering_wheel_angle": -0.6548415105692499, "front_wheel_angle": -0.030335570009545985, "heading_rate": -0.027399286476662964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.1890378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26969745858023725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26369157764620604, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3132219172528736, "gear": 1, "accelerator_pedal_position": 0.26969745858023725, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6152169998461865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.1890378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 31.6092282677087, "y": -0.14071877473286687, "z": null, "yaw": 3.1134647003493026, "pitch": null, "roll": null}, "v": 2.3114995367162416, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "acceleration": 0.10573597635527682, "steering_wheel_angle": -0.6548415105692499, "front_wheel_angle": -0.030335570009545985, "heading_rate": -0.027399286476662964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.2090378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2717088037558103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26369157764620604, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.313886297891666, "gear": 1, "accelerator_pedal_position": 0.26969745858023725, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.575549940099965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.2090378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 31.6092282677087, "y": -0.14071877473286687, "z": null, "yaw": 3.1134647003493026, "pitch": null, "roll": null}, "v": 2.3114995367162416, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "acceleration": 0.10573597635527682, "steering_wheel_angle": -0.6548415105692499, "front_wheel_angle": -0.030335570009545985, "heading_rate": -0.027399286476662964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.2290378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2717088037558103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26369157764620604, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.315464437976404, "gear": 1, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.575549940099965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.2290378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 31.6092282677087, "y": -0.14071877473286687, "z": null, "yaw": 3.1134647003493026, "pitch": null, "roll": null}, "v": 2.3114995367162416, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "acceleration": 0.10573597635527682, "steering_wheel_angle": -0.6548415105692499, "front_wheel_angle": -0.030335570009545985, "heading_rate": -0.027399286476662964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.2490377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2717088037558103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26369157764620604, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3170395399828925, "gear": 1, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.575549940099965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.2490377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 31.6092282677087, "y": -0.14071877473286687, "z": null, "yaw": 3.1134647003493026, "pitch": null, "roll": null}, "v": 2.3114995367162416, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "acceleration": 0.10573597635527682, "steering_wheel_angle": -0.6548415105692499, "front_wheel_angle": -0.030335570009545985, "heading_rate": -0.027399286476662964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.2690377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2717088037558103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26369157764620604, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3186116087678363, "gear": 1, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.575549940099965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.2690377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.2890377, "x": 35.35462871132415, "y": 4.866584859601271, "z": null, "yaw": 3.112283822223347, "pitch": null, "roll": null}, "v": 2.320180649184318, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "acceleration": 0.07833860856610475, "steering_wheel_angle": -0.575549940099965, "front_wheel_angle": -0.0266340181568204, "heading_rate": -0.024144667858200086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.2890377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26656023700405335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32272928217876345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.320642249847994, "gear": 1, "accelerator_pedal_position": 0.26656023700405335, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.2890377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 31.354628711324153, "y": -0.13341514039872937, "z": null, "yaw": 3.112283822223347, "pitch": null, "roll": null}, "v": 2.320180649184318, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "acceleration": 0.07833860856610475, "steering_wheel_angle": -0.575549940099965, "front_wheel_angle": -0.0266340181568204, "heading_rate": -0.024144667858200086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.3090377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2682109720457588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32272928217876345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3211034054906454, "gear": 1, "accelerator_pedal_position": 0.26656023700405335, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.3090377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 31.354628711324153, "y": -0.13341514039872937, "z": null, "yaw": 3.112283822223347, "pitch": null, "roll": null}, "v": 2.320180649184318, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "acceleration": 0.07833860856610475, "steering_wheel_angle": -0.575549940099965, "front_wheel_angle": -0.0266340181568204, "heading_rate": -0.024144667858200086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.3290377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2682109720457588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32272928217876345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3222306256486465, "gear": 1, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.3290377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 31.354628711324153, "y": -0.13341514039872937, "z": null, "yaw": 3.112283822223347, "pitch": null, "roll": null}, "v": 2.320180649184318, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "acceleration": 0.07833860856610475, "steering_wheel_angle": -0.575549940099965, "front_wheel_angle": -0.0266340181568204, "heading_rate": -0.024144667858200086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.3490376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2682109720457588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32272928217876345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.323355672695912, "gear": 1, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.3490376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 31.354628711324153, "y": -0.13341514039872937, "z": null, "yaw": 3.112283822223347, "pitch": null, "roll": null}, "v": 2.320180649184318, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "acceleration": 0.07833860856610475, "steering_wheel_angle": -0.575549940099965, "front_wheel_angle": -0.0266340181568204, "heading_rate": -0.024144667858200086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.3690376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2682109720457588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32272928217876345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3244785503158245, "gear": 1, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.3690376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 31.354628711324153, "y": -0.13341514039872937, "z": null, "yaw": 3.112283822223347, "pitch": null, "roll": null}, "v": 2.320180649184318, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "acceleration": 0.07833860856610475, "steering_wheel_angle": -0.575549940099965, "front_wheel_angle": -0.0266340181568204, "heading_rate": -0.024144667858200086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.3890376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2682109720457588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32272928217876345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3255992621875907, "gear": 1, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.3890376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.3990376, "x": 35.099232087745094, "y": 4.874197865730856, "z": null, "yaw": 3.111211578671895, "pitch": null, "roll": null}, "v": 2.3261588071165282, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "acceleration": 0.05590048697090794, "steering_wheel_angle": -0.5357778065723359, "front_wheel_angle": -0.024780329654388297, "heading_rate": -0.022521399925202037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.4090376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585585900131328, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.37577558991048204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3267178119862373, "gear": 1, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.4090376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 31.099232087745094, "y": -0.12580213426914444, "z": null, "yaw": 3.111211578671895, "pitch": null, "roll": null}, "v": 2.3261588071165282, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "acceleration": 0.05590048697090794, "steering_wheel_angle": -0.5357778065723359, "front_wheel_angle": -0.024780329654388297, "heading_rate": -0.022521399925202037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.4290376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616037950652892, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.37577558991048204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3266282380260703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.4290376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 31.099232087745094, "y": -0.12580213426914444, "z": null, "yaw": 3.111211578671895, "pitch": null, "roll": null}, "v": 2.3261588071165282, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "acceleration": 0.05590048697090794, "steering_wheel_angle": -0.5357778065723359, "front_wheel_angle": -0.024780329654388297, "heading_rate": -0.022521399925202037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.4490376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616037950652892, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.37577558991048204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3269193038230087, "gear": 1, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.4490376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 31.099232087745094, "y": -0.12580213426914444, "z": null, "yaw": 3.111211578671895, "pitch": null, "roll": null}, "v": 2.3261588071165282, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "acceleration": 0.05590048697090794, "steering_wheel_angle": -0.5357778065723359, "front_wheel_angle": -0.024780329654388297, "heading_rate": -0.022521399925202037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.4690375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616037950652892, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.37577558991048204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3272098079192323, "gear": 1, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.4690375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 31.099232087745094, "y": -0.12580213426914444, "z": null, "yaw": 3.111211578671895, "pitch": null, "roll": null}, "v": 2.3261588071165282, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "acceleration": 0.05590048697090794, "steering_wheel_angle": -0.5357778065723359, "front_wheel_angle": -0.024780329654388297, "heading_rate": -0.022521399925202037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.4890375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616037950652892, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.37577558991048204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3274997513649747, "gear": 1, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.4890375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.5090375, "x": 34.84338723321948, "y": 4.882086269981095, "z": null, "yaw": 3.1102699172022543, "pitch": null, "roll": null}, "v": 2.3277891352086373, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "acceleration": 0.014448239817671737, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019159534659391804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.5090375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525840311529365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4090981817490842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3277891352086373, "gear": 1, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.5090375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.84338723321948, "y": -0.1179137300189046, "z": null, "yaw": 3.1102699172022543, "pitch": null, "roll": null}, "v": 2.3277891352086373, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "acceleration": 0.014448239817671737, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019159534659391804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.5290375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554105787800408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4090981817490842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3269510343112367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.5290375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.84338723321948, "y": -0.1179137300189046, "z": null, "yaw": 3.1102699172022543, "pitch": null, "roll": null}, "v": 2.3277891352086373, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "acceleration": 0.014448239817671737, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019159534659391804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.5490375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554105787800408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4090981817490842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3264676988117134, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.5490375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.84338723321948, "y": -0.1179137300189046, "z": null, "yaw": 3.1102699172022543, "pitch": null, "roll": null}, "v": 2.3277891352086373, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "acceleration": 0.014448239817671737, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019159534659391804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.5690374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554105787800408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4090981817490842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.325985296006442, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.5690374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.84338723321948, "y": -0.1179137300189046, "z": null, "yaw": 3.1102699172022543, "pitch": null, "roll": null}, "v": 2.3277891352086373, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "acceleration": 0.014448239817671737, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019159534659391804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.5890374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554105787800408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4090981817490842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3255038240025603, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.5890374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.84338723321948, "y": -0.1179137300189046, "z": null, "yaw": 3.1102699172022543, "pitch": null, "roll": null}, "v": 2.3277891352086373, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "acceleration": 0.014448239817671737, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019159534659391804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.6090374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554105787800408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4090981817490842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.325023280911395, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.6090374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.6190374, "x": 34.58762574269163, "y": 4.890205377424326, "z": null, "yaw": 3.109364530721727, "pitch": null, "roll": null}, "v": 2.3247833571190135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3702853444313262, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019134794742611747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.6290374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2535500138977793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46763700546419906, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.324543664848453, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.6290374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 30.58762574269163, "y": -0.10979462257567363, "z": null, "yaw": 3.109364530721727, "pitch": null, "roll": null}, "v": 2.3247833571190135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3702853444313262, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019134794742611747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.6490374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541169340497349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46763700546419906, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3238325155209147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37583830951744507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.6490374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 30.58762574269163, "y": -0.10979462257567363, "z": null, "yaw": 3.109364530721727, "pitch": null, "roll": null}, "v": 2.3247833571190135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3702853444313262, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019134794742611747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.6690373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541169340497349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46763700546419906, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3231935686053924, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37583830951744507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.6690373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 30.58762574269163, "y": -0.10979462257567363, "z": null, "yaw": 3.109364530721727, "pitch": null, "roll": null}, "v": 2.3247833571190135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3702853444313262, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019134794742611747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.6890373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541169340497349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46763700546419906, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3225558538419793, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37583830951744507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.6890373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 30.58762574269163, "y": -0.10979462257567363, "z": null, "yaw": 3.109364530721727, "pitch": null, "roll": null}, "v": 2.3247833571190135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3702853444313262, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019134794742611747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.7090373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541169340497349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46763700546419906, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.321919368691986, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37583830951744507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.7090373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.7290373, "x": 34.332209082228815, "y": 4.898534209811155, "z": null, "yaw": 3.1085827653744764, "pitch": null, "roll": null}, "v": 2.3212841106225595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3699478047534156, "steering_wheel_angle": -0.37583830951744507, "front_wheel_angle": -0.017345902915606205, "heading_rate": -0.0157300029691507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.7290373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2527959397800835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5301462842782595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3212841106225595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37583830951744507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.7290373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 30.332209082228815, "y": -0.10146579018884516, "z": null, "yaw": 3.1085827653744764, "pitch": null, "roll": null}, "v": 2.3212841106225595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3699478047534156, "steering_wheel_angle": -0.37583830951744507, "front_wheel_angle": -0.017345902915606205, "heading_rate": -0.0157300029691507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.7490373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531918737650486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5301462842782595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.320485032428149, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3356290822056074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.7490373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 30.332209082228815, "y": -0.10146579018884516, "z": null, "yaw": 3.1085827653744764, "pitch": null, "roll": null}, "v": 2.3212841106225595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3699478047534156, "steering_wheel_angle": -0.37583830951744507, "front_wheel_angle": -0.017345902915606205, "heading_rate": -0.0157300029691507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.7690372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531918737650486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5301462842782595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3197369622252317, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3356290822056074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.7690372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 30.332209082228815, "y": -0.10146579018884516, "z": null, "yaw": 3.1085827653744764, "pitch": null, "roll": null}, "v": 2.3212841106225595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3699478047534156, "steering_wheel_angle": -0.37583830951744507, "front_wheel_angle": -0.017345902915606205, "heading_rate": -0.0157300029691507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.7890372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531918737650486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5301462842782595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.318990333583789, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3356290822056074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.7890372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 30.332209082228815, "y": -0.10146579018884516, "z": null, "yaw": 3.1085827653744764, "pitch": null, "roll": null}, "v": 2.3212841106225595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3699478047534156, "steering_wheel_angle": -0.37583830951744507, "front_wheel_angle": -0.017345902915606205, "heading_rate": -0.0157300029691507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.8090372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531918737650486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5301462842782595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.318245143502998, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3356290822056074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.8090372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 30.332209082228815, "y": -0.10146579018884516, "z": null, "yaw": 3.1085827653744764, "pitch": null, "roll": null}, "v": 2.3212841106225595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3699478047534156, "steering_wheel_angle": -0.37583830951744507, "front_wheel_angle": -0.017345902915606205, "heading_rate": -0.0157300029691507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.8290372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531918737650486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5301462842782595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.317501388989109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3356290822056074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.8290372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.8390372, "x": 34.07721976699525, "y": 4.90703329697986, "z": null, "yaw": 3.1079101922136614, "pitch": null, "roll": null}, "v": 2.317130049136133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3695474191029029, "steering_wheel_angle": -0.3356290822056074, "front_wheel_angle": -0.015481871576332056, "heading_rate": -0.014014209482540571, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.8490372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25238606998263996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.597756143992925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3167590670554197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3356290822056074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.8490372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 30.07721976699525, "y": -0.09296670302014043, "z": null, "yaw": 3.1079101922136614, "pitch": null, "roll": null}, "v": 2.317130049136133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3695474191029029, "steering_wheel_angle": -0.3356290822056074, "front_wheel_angle": -0.015481871576332056, "heading_rate": -0.014014209482540571, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.8690372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526178645340934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.597756143992925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3159174977625065, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2549336804954348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.8690372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 30.07721976699525, "y": -0.09296670302014043, "z": null, "yaw": 3.1079101922136614, "pitch": null, "roll": null}, "v": 2.317130049136133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3695474191029029, "steering_wheel_angle": -0.3356290822056074, "front_wheel_angle": -0.015481871576332056, "heading_rate": -0.014014209482540571, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.8890371} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526178645340934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.597756143992925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3147016007610817, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2549336804954348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.8890371} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 30.07721976699525, "y": -0.09296670302014043, "z": null, "yaw": 3.1079101922136614, "pitch": null, "roll": null}, "v": 2.317130049136133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3695474191029029, "steering_wheel_angle": -0.3356290822056074, "front_wheel_angle": -0.015481871576332056, "heading_rate": -0.014014209482540571, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.909037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526178645340934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.597756143992925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.314297082144025, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2549336804954348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.909037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 30.07721976699525, "y": -0.09296670302014043, "z": null, "yaw": 3.1079101922136614, "pitch": null, "roll": null}, "v": 2.317130049136133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3695474191029029, "steering_wheel_angle": -0.3356290822056074, "front_wheel_angle": -0.015481871576332056, "heading_rate": -0.014014209482540571, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.929037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526178645340934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.597756143992925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.313489213034942, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2549336804954348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.929037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.949037, "x": 33.82270415460252, "y": 4.915675469169977, "z": null, "yaw": 3.1073689354149177, "pitch": null, "roll": null}, "v": 2.312682898710067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36911916683536333, "steering_wheel_angle": -0.2549336804954348, "front_wheel_angle": -0.011746990979243758, "heading_rate": -0.010612622979957175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.949037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2482378524969912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6357624167418585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.312682898710067, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2549336804954348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.949037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.82270415460252, "y": -0.08432453083002311, "z": null, "yaw": 3.1073689354149177, "pitch": null, "roll": null}, "v": 2.312682898710067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36911916683536333, "steering_wheel_angle": -0.2549336804954348, "front_wheel_angle": -0.011746990979243758, "heading_rate": -0.010612622979957175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.969037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24958519452859493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6357624167418585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.311330897878148, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21447933075109482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.969037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.82270415460252, "y": -0.08432453083002311, "z": null, "yaw": 3.1073689354149177, "pitch": null, "roll": null}, "v": 2.312682898710067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36911916683536333, "steering_wheel_angle": -0.2549336804954348, "front_wheel_angle": -0.011746990979243758, "heading_rate": -0.010612622979957175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.989037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24958519452859493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6357624167418585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.310149834679645, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21447933075109482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.989037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.82270415460252, "y": -0.08432453083002311, "z": null, "yaw": 3.1073689354149177, "pitch": null, "roll": null}, "v": 2.312682898710067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36911916683536333, "steering_wheel_angle": -0.2549336804954348, "front_wheel_angle": -0.011746990979243758, "heading_rate": -0.010612622979957175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.009037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24958519452859493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6357624167418585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.308971042963869, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21447933075109482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.009037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.82270415460252, "y": -0.08432453083002311, "z": null, "yaw": 3.1073689354149177, "pitch": null, "roll": null}, "v": 2.312682898710067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36911916683536333, "steering_wheel_angle": -0.2549336804954348, "front_wheel_angle": -0.011746990979243758, "heading_rate": -0.010612622979957175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.029037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24958519452859493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6357624167418585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.307794517806633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21447933075109482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.029037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.82270415460252, "y": -0.08432453083002311, "z": null, "yaw": 3.1073689354149177, "pitch": null, "roll": null}, "v": 2.312682898710067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36911916683536333, "steering_wheel_angle": -0.2549336804954348, "front_wheel_angle": -0.011746990979243758, "heading_rate": -0.010612622979957175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.049037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24958519452859493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6357624167418585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.306620254296422, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21447933075109482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.049037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.059037, "x": 33.568800204722336, "y": 4.924419105645775, "z": null, "yaw": 3.1069371893006466, "pitch": null, "roll": null}, "v": 2.3060339691275575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3684796251240799, "steering_wheel_angle": -0.21447933075109482, "front_wheel_angle": -0.009877626133906773, "heading_rate": -0.008898000871145442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.069037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24103324586975222, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6812693193751557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.305448247534354, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21447933075109482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.069037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 29.568800204722336, "y": -0.07558089435422488, "z": null, "yaw": 3.1069371893006466, "pitch": null, "roll": null}, "v": 2.3060339691275575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3684796251240799, "steering_wheel_angle": -0.21447933075109482, "front_wheel_angle": -0.009877626133906773, "heading_rate": -0.008898000871145442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.089037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367375447132875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6812693193751557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3032100126599984, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1739314546464441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.089037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 29.568800204722336, "y": -0.07558089435422488, "z": null, "yaw": 3.1069371893006466, "pitch": null, "roll": null}, "v": 2.3060339691275575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3684796251240799, "steering_wheel_angle": -0.21447933075109482, "front_wheel_angle": -0.009877626133906773, "heading_rate": -0.008898000871145442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.109037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367375447132875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6812693193751557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.301305981578609, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1739314546464441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.109037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 29.568800204722336, "y": -0.07558089435422488, "z": null, "yaw": 3.1069371893006466, "pitch": null, "roll": null}, "v": 2.3060339691275575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3684796251240799, "steering_wheel_angle": -0.21447933075109482, "front_wheel_angle": -0.009877626133906773, "heading_rate": -0.008898000871145442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.129037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367375447132875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6812693193751557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.299405605838197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1739314546464441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.129037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 29.568800204722336, "y": -0.07558089435422488, "z": null, "yaw": 3.1069371893006466, "pitch": null, "roll": null}, "v": 2.3060339691275575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3684796251240799, "steering_wheel_angle": -0.21447933075109482, "front_wheel_angle": -0.009877626133906773, "heading_rate": -0.008898000871145442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.149037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367375447132875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6812693193751557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2975088769773944, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1739314546464441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.149037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.1690369, "x": 33.31580496327356, "y": 4.93323305824738, "z": null, "yaw": 3.106578552675704, "pitch": null, "roll": null}, "v": 2.2956157865593845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674793077229759, "steering_wheel_angle": -0.1739314546464441, "front_wheel_angle": -0.008005949081471264, "heading_rate": -0.007179287409243456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.1690369} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2353535006868759, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7237504581795141, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2956157865593845, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1739314546464441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.1690369} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.315804963273557, "y": -0.06676694175262021, "z": null, "yaw": 3.106578552675704, "pitch": null, "roll": null}, "v": 2.2956157865593845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674793077229759, "steering_wheel_angle": -0.1739314546464441, "front_wheel_angle": -0.008005949081471264, "heading_rate": -0.007179287409243456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.1890368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379035657964152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7237504581795141, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.292686793082667, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1332930584582144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.1890368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.315804963273557, "y": -0.06676694175262021, "z": null, "yaw": 3.106578552675704, "pitch": null, "roll": null}, "v": 2.2956157865593845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674793077229759, "steering_wheel_angle": -0.1739314546464441, "front_wheel_angle": -0.008005949081471264, "heading_rate": -0.007179287409243456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.2090368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379035657964152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7237504581795141, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.290082018283613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1332930584582144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.2090368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.315804963273557, "y": -0.06676694175262021, "z": null, "yaw": 3.106578552675704, "pitch": null, "roll": null}, "v": 2.2956157865593845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674793077229759, "steering_wheel_angle": -0.1739314546464441, "front_wheel_angle": -0.008005949081471264, "heading_rate": -0.007179287409243456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.2290368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379035657964152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7237504581795141, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.287482232606039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1332930584582144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.2290368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.315804963273557, "y": -0.06676694175262021, "z": null, "yaw": 3.106578552675704, "pitch": null, "roll": null}, "v": 2.2956157865593845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674793077229759, "steering_wheel_angle": -0.1739314546464441, "front_wheel_angle": -0.008005949081471264, "heading_rate": -0.007179287409243456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.2490368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379035657964152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7237504581795141, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.284887423791644, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1332930584582144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.2490368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.315804963273557, "y": -0.06676694175262021, "z": null, "yaw": 3.106578552675704, "pitch": null, "roll": null}, "v": 2.2956157865593845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674793077229759, "steering_wheel_angle": -0.1739314546464441, "front_wheel_angle": -0.008005949081471264, "heading_rate": -0.007179287409243456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.2690368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379035657964152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7237504581795141, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.282297579621113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1332930584582144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.2690368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.2790368, "x": 33.064188959637875, "y": 4.942078582635412, "z": null, "yaw": 3.106307740383685, "pitch": null, "roll": null}, "v": 2.281004515469384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3660800417693864, "steering_wheel_angle": -0.1332930584582144, "front_wheel_angle": -0.006132105799829896, "heading_rate": -0.0054638813837235185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.2890368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24054944982631846, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7918624122913377, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2797126879139658, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1332930584582144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.2890368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 29.064188959637875, "y": -0.05792141736458767, "z": null, "yaw": 3.106307740383685, "pitch": null, "roll": null}, "v": 2.281004515469384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3660800417693864, "steering_wheel_angle": -0.1332930584582144, "front_wheel_angle": -0.006132105799829896, "heading_rate": -0.0054638813837235185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.3090367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23965264718130458, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7918624122913377, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2774633139900193, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05173367917221305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.3090367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 29.064188959637875, "y": -0.05792141736458767, "z": null, "yaw": 3.106307740383685, "pitch": null, "roll": null}, "v": 2.281004515469384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3660800417693864, "steering_wheel_angle": -0.1332930584582144, "front_wheel_angle": -0.006132105799829896, "heading_rate": -0.0054638813837235185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.3290367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23965264718130458, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7918624122913377, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275106190250748, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05173367917221305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.3290367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 29.064188959637875, "y": -0.05792141736458767, "z": null, "yaw": 3.106307740383685, "pitch": null, "roll": null}, "v": 2.281004515469384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3660800417693864, "steering_wheel_angle": -0.1332930584582144, "front_wheel_angle": -0.006132105799829896, "heading_rate": -0.0054638813837235185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.3490367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23965264718130458, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7918624122913377, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2727535671234262, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05173367917221305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.3490367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 29.064188959637875, "y": -0.05792141736458767, "z": null, "yaw": 3.106307740383685, "pitch": null, "roll": null}, "v": 2.281004515469384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3660800417693864, "steering_wheel_angle": -0.1332930584582144, "front_wheel_angle": -0.006132105799829896, "heading_rate": -0.0054638813837235185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.3690367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23965264718130458, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7918624122913377, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27040543380186, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05173367917221305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.3690367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.3890367, "x": 32.814084828268065, "y": 4.950926441550263, "z": null, "yaw": 3.106168917216454, "pitch": null, "roll": null}, "v": 2.268061779513149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364844131332541, "steering_wheel_angle": -0.05173367917221305, "front_wheel_angle": -0.0023774413032310563, "heading_rate": -0.0021063257469530186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.3890367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2433964628786806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8719767483001376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.268061779513149, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05173367917221305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.3890367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.814084828268065, "y": -0.04907355844973704, "z": null, "yaw": 3.106168917216454, "pitch": null, "roll": null}, "v": 2.268061779513149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364844131332541, "steering_wheel_angle": -0.05173367917221305, "front_wheel_angle": -0.0023774413032310563, "heading_rate": -0.0021063257469530186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.4090366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24216472414381748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8719767483001376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2661903473947094, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.4090366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.814084828268065, "y": -0.04907355844973704, "z": null, "yaw": 3.106168917216454, "pitch": null, "roll": null}, "v": 2.268061779513149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364844131332541, "steering_wheel_angle": -0.05173367917221305, "front_wheel_angle": -0.0023774413032310563, "heading_rate": -0.0021063257469530186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.4290366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24216472414381748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8719767483001376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2641685877934363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.4290366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.814084828268065, "y": -0.04907355844973704, "z": null, "yaw": 3.106168917216454, "pitch": null, "roll": null}, "v": 2.268061779513149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364844131332541, "steering_wheel_angle": -0.05173367917221305, "front_wheel_angle": -0.0023774413032310563, "heading_rate": -0.0021063257469530186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.4490366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24216472414381748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8719767483001376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2621506795666133, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.4490366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.814084828268065, "y": -0.04907355844973704, "z": null, "yaw": 3.106168917216454, "pitch": null, "roll": null}, "v": 2.268061779513149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364844131332541, "steering_wheel_angle": -0.05173367917221305, "front_wheel_angle": -0.0023774413032310563, "heading_rate": -0.0021063257469530186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.4690366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24216472414381748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8719767483001376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2601366137495136, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.4690366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.814084828268065, "y": -0.04907355844973704, "z": null, "yaw": 3.106168917216454, "pitch": null, "roll": null}, "v": 2.268061779513149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364844131332541, "steering_wheel_angle": -0.05173367917221305, "front_wheel_angle": -0.0023774413032310563, "heading_rate": -0.0021063257469530186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.4890366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24216472414381748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8719767483001376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2581263814037813, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.4890366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.4990366, "x": 32.56529521473258, "y": 4.959741277805636, "z": null, "yaw": 3.1062064012380866, "pitch": null, "roll": null}, "v": 2.257122699996629, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36380216382823216, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012215633860527026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.5090365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23772368864842694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8677235410518033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.256119973617335, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.5090365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 28.56529521473258, "y": -0.04025872219436444, "z": null, "yaw": 3.1062064012380866, "pitch": null, "roll": null}, "v": 2.257122699996629, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36380216382823216, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012215633860527026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.5290365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23905941474129133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8677235410518033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2535625160302524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.5290365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 28.56529521473258, "y": -0.04025872219436444, "z": null, "yaw": 3.1062064012380866, "pitch": null, "roll": null}, "v": 2.257122699996629, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36380216382823216, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012215633860527026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.5490365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23905941474129133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8677235410518033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.25117680601317, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.5490365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 28.56529521473258, "y": -0.04025872219436444, "z": null, "yaw": 3.1062064012380866, "pitch": null, "roll": null}, "v": 2.257122699996629, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36380216382823216, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012215633860527026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.5690365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23905941474129133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8677235410518033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2487956283828474, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.5690365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 28.56529521473258, "y": -0.04025872219436444, "z": null, "yaw": 3.1062064012380866, "pitch": null, "roll": null}, "v": 2.257122699996629, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36380216382823216, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012215633860527026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.5890365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23905941474129133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8677235410518033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.246418972261701, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.5890365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.6090364, "x": 32.31781769232265, "y": 4.968495538922834, "z": null, "yaw": 3.106265933656267, "pitch": null, "roll": null}, "v": 2.244046826805718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36255980294925405, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012144866737717492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.6090364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2420056694900519, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9394993529986189, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.244046826805718, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.6090364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.31781769232265, "y": -0.03150446107716576, "z": null, "yaw": 3.106265933656267, "pitch": null, "roll": null}, "v": 2.244046826805718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36255980294925405, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012144866737717492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.6290364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102284619272613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9394993529986189, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.242047288373518, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1120938757317114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.6290364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.31781769232265, "y": -0.03150446107716576, "z": null, "yaw": 3.106265933656267, "pitch": null, "roll": null}, "v": 2.244046826805718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36255980294925405, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012144866737717492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.6490364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102284619272613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9394993529986189, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.239928746637341, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1120938757317114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.6490364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.31781769232265, "y": -0.03150446107716576, "z": null, "yaw": 3.106265933656267, "pitch": null, "roll": null}, "v": 2.244046826805718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36255980294925405, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012144866737717492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.6690364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102284619272613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9394993529986189, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2378142201406397, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1120938757317114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.6690364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.31781769232265, "y": -0.03150446107716576, "z": null, "yaw": 3.106265933656267, "pitch": null, "roll": null}, "v": 2.244046826805718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36255980294925405, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012144866737717492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.6890364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102284619272613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9394993529986189, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.235703699485749, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1120938757317114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.6890364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.31781769232265, "y": -0.03150446107716576, "z": null, "yaw": 3.106265933656267, "pitch": null, "roll": null}, "v": 2.244046826805718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36255980294925405, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012144866737717492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.7090364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102284619272613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9394993529986189, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2335971753029695, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1120938757317114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.7090364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.7190363, "x": 32.07169612949886, "y": 4.9771738172235755, "z": null, "yaw": 3.1064653672295077, "pitch": null, "roll": null}, "v": 2.2325454089682113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36146986047946095, "steering_wheel_angle": 0.1120938757317114, "front_wheel_angle": 0.0051554052490366525, "heading_rate": 0.004496007144543144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.7290363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24389778188906658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.015570533045331, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.231494638250462, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1120938757317114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.7290363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 28.07169612949886, "y": -0.022826182776424453, "z": null, "yaw": 3.1064653672295077, "pitch": null, "roll": null}, "v": 2.2325454089682113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36146986047946095, "steering_wheel_angle": 0.1120938757317114, "front_wheel_angle": 0.0051554052490366525, "heading_rate": 0.004496007144543144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.7490363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24294486673569068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.015570533045331, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.229755275976398, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.7490363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 28.07169612949886, "y": -0.022826182776424453, "z": null, "yaw": 3.1064653672295077, "pitch": null, "roll": null}, "v": 2.2325454089682113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36146986047946095, "steering_wheel_angle": 0.1120938757317114, "front_wheel_angle": 0.0051554052490366525, "heading_rate": 0.004496007144543144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.7690363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24294486673569068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.015570533045331, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2279001450847864, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.7690363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 28.07169612949886, "y": -0.022826182776424453, "z": null, "yaw": 3.1064653672295077, "pitch": null, "roll": null}, "v": 2.2325454089682113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36146986047946095, "steering_wheel_angle": 0.1120938757317114, "front_wheel_angle": 0.0051554052490366525, "heading_rate": 0.004496007144543144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.7890363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24294486673569068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.015570533045331, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.226048521227895, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.7890363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 28.07169612949886, "y": -0.022826182776424453, "z": null, "yaw": 3.1064653672295077, "pitch": null, "roll": null}, "v": 2.2325454089682113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36146986047946095, "steering_wheel_angle": 0.1120938757317114, "front_wheel_angle": 0.0051554052490366525, "heading_rate": 0.004496007144543144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.8090363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24294486673569068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.015570533045331, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2242003964050885, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.8090363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.8290362, "x": 31.826778362855208, "y": 4.985745467238181, "z": null, "yaw": 3.1068123335510975, "pitch": null, "roll": null}, "v": 2.222355762638622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.360506439489262, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007755242985895074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.8290362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23908961232874584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9665037303301173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.222355762638622, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.8290362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.826778362855208, "y": -0.014254532761818872, "z": null, "yaw": 3.1068123335510975, "pitch": null, "roll": null}, "v": 2.222355762638622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.360506439489262, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007755242985895074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.8490362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24024620903973004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9665037303301173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2200329326960375, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.8490362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.826778362855208, "y": -0.014254532761818872, "z": null, "yaw": 3.1068123335510975, "pitch": null, "roll": null}, "v": 2.222355762638622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.360506439489262, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007755242985895074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.8690362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24024620903973004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9665037303301173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2178589931217316, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.8690362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.826778362855208, "y": -0.014254532761818872, "z": null, "yaw": 3.1068123335510975, "pitch": null, "roll": null}, "v": 2.222355762638622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.360506439489262, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007755242985895074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.8890362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24024620903973004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9665037303301173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2156891546204336, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.8890362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.826778362855208, "y": -0.014254532761818872, "z": null, "yaw": 3.1068123335510975, "pitch": null, "roll": null}, "v": 2.222355762638622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.360506439489262, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007755242985895074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.9090362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24024620903973004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9665037303301173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2135234075731978, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.9090362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.826778362855208, "y": -0.014254532761818872, "z": null, "yaw": 3.1068123335510975, "pitch": null, "roll": null}, "v": 2.222355762638622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.360506439489262, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007755242985895074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.9290361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24024620903973004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9665037303301173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.211361742389865, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.9290361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.9390361, "x": 31.58307653651783, "y": 4.994182383245208, "z": null, "yaw": 3.10719619501144, "pitch": null, "roll": null}, "v": 2.2102824375080825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3593676064109709, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007713111311205925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.9490361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24378507568325133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0383422460519423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.209204149508956, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.9490361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 27.58307653651783, "y": -0.0058176167547916435, "z": null, "yaw": 3.10719619501144, "pitch": null, "roll": null}, "v": 2.2102824375080825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3593676064109709, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007713111311205925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.969036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426222374408202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0383422460519423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2074927694551976, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.969036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 27.58307653651783, "y": -0.0058176167547916435, "z": null, "yaw": 3.10719619501144, "pitch": null, "roll": null}, "v": 2.2102824375080825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3593676064109709, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007713111311205925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.989036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426222374408202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0383422460519423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2056393243332795, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.989036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 27.58307653651783, "y": -0.0058176167547916435, "z": null, "yaw": 3.10719619501144, "pitch": null, "roll": null}, "v": 2.2102824375080825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3593676064109709, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007713111311205925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.009036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426222374408202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0383422460519423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2037893665707893, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.009036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 27.58307653651783, "y": -0.0058176167547916435, "z": null, "yaw": 3.10719619501144, "pitch": null, "roll": null}, "v": 2.2102824375080825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3593676064109709, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007713111311205925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.029036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426222374408202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0383422460519423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2019428882377734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.029036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.049036, "x": 31.340599944413864, "y": 5.002483687583062, "z": null, "yaw": 3.1075800564717824, "pitch": null, "roll": null}, "v": 2.2000998814269144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35840938895389296, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007677577758048259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.049036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2456649323701362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1185389731335724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2000998814269144, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.049036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.340599944413864, "y": 0.0024836875830622773, "z": null, "yaw": 3.1075800564717824, "pitch": null, "roll": null}, "v": 2.2000998814269144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35840938895389296, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007677577758048259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.069036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446661786770371, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1185389731335724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1986404963888715, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.069036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.340599944413864, "y": 0.0024836875830622773, "z": null, "yaw": 3.1075800564717824, "pitch": null, "roll": null}, "v": 2.2000998814269144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35840938895389296, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007677577758048259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.089036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446661786770371, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1185389731335724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1970590675638806, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.089036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.340599944413864, "y": 0.0024836875830622773, "z": null, "yaw": 3.1075800564717824, "pitch": null, "roll": null}, "v": 2.2000998814269144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35840938895389296, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007677577758048259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.109036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446661786770371, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1185389731335724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.195480608819102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.109036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.340599944413864, "y": 0.0024836875830622773, "z": null, "yaw": 3.1075800564717824, "pitch": null, "roll": null}, "v": 2.2000998814269144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35840938895389296, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007677577758048259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.129036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446661786770371, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1185389731335724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1931184752260715, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.129036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.340599944413864, "y": 0.0024836875830622773, "z": null, "yaw": 3.1075800564717824, "pitch": null, "roll": null}, "v": 2.2000998814269144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35840938895389296, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007677577758048259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.149036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446661786770371, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1185389731335724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1923325752911356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.149036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.159036, "x": 31.099149627479964, "y": 5.010643899496992, "z": null, "yaw": 3.1081045300602463, "pitch": null, "roll": null}, "v": 2.1915474129587365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3576061712803981, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.01089150609527421, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.169036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24080215198886154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0858580897813228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1907629874132475, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.169036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 27.099149627479964, "y": 0.010643899496992404, "z": null, "yaw": 3.1081045300602463, "pitch": null, "roll": null}, "v": 2.1915474129587365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3576061712803981, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.01089150609527421, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.189036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419695002106148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0858580897813228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1887135666117623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.189036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 27.099149627479964, "y": 0.010643899496992404, "z": null, "yaw": 3.1081045300602463, "pitch": null, "roll": null}, "v": 2.1915474129587365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3576061712803981, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.01089150609527421, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.2090359} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419695002106148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0858580897813228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.186813838211857, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.2090359} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 27.099149627479964, "y": 0.010643899496992404, "z": null, "yaw": 3.1081045300602463, "pitch": null, "roll": null}, "v": 2.1915474129587365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3576061712803981, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.01089150609527421, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.2290359} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419695002106148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0858580897813228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.184917669972826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.2290359} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 27.099149627479964, "y": 0.010643899496992404, "z": null, "yaw": 3.1081045300602463, "pitch": null, "roll": null}, "v": 2.1915474129587365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3576061712803981, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.01089150609527421, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.2490358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419695002106148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0858580897813228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.183025053785289, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.2490358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.2690358, "x": 30.85873053082815, "y": 5.0186383391461655, "z": null, "yaw": 3.1086512057394478, "pitch": null, "roll": null}, "v": 2.181135981563135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566303407788506, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.010839763583186538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.2690358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24543174220471778, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1640880703523728, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.181135981563135, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.2690358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 26.85873053082815, "y": 0.018638339146165528, "z": null, "yaw": 3.1086512057394478, "pitch": null, "roll": null}, "v": 2.181135981563135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566303407788506, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.010839763583186538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.2890358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443009993151104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1640880703523728, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.179683022938523, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.2890358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 26.85873053082815, "y": 0.018638339146165528, "z": null, "yaw": 3.1086512057394478, "pitch": null, "roll": null}, "v": 2.181135981563135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566303407788506, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.010839763583186538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.3090358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443009993151104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1640880703523728, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1780915062785096, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.3090358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 26.85873053082815, "y": 0.018638339146165528, "z": null, "yaw": 3.1086512057394478, "pitch": null, "roll": null}, "v": 2.181135981563135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566303407788506, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.010839763583186538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.3290358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443009993151104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1640880703523728, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.176502966582713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.3290358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 26.85873053082815, "y": 0.018638339146165528, "z": null, "yaw": 3.1086512057394478, "pitch": null, "roll": null}, "v": 2.181135981563135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566303407788506, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.010839763583186538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.3490357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443009993151104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1640880703523728, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1749173972737506, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.3490357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 26.85873053082815, "y": 0.018638339146165528, "z": null, "yaw": 3.1086512057394478, "pitch": null, "roll": null}, "v": 2.181135981563135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566303407788506, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.010839763583186538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.3690357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443009993151104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1640880703523728, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.173334791792197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.3690357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.3790357, "x": 30.619357339301683, "y": 5.026459730897971, "z": null, "yaw": 3.1092719870687766, "pitch": null, "roll": null}, "v": 2.1725445984417737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35582673024427397, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012407044607574084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.3890357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24181600484462912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1486221513773818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1717551435965254, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.3890357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 26.619357339301683, "y": 0.0264597308979706, "z": null, "yaw": 3.1092719870687766, "pitch": null, "roll": null}, "v": 2.1725445984417737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35582673024427397, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012407044607574084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.4090357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24255238557273454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1486221513773818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1698679669433973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.4090357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 26.619357339301683, "y": 0.0264597308979706, "z": null, "yaw": 3.1092719870687766, "pitch": null, "roll": null}, "v": 2.1725445984417737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35582673024427397, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012407044607574084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.4290357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24255238557273454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1486221513773818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1680763187608347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.4290357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 26.619357339301683, "y": 0.0264597308979706, "z": null, "yaw": 3.1092719870687766, "pitch": null, "roll": null}, "v": 2.1725445984417737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35582673024427397, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012407044607574084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.4490356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24255238557273454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1486221513773818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1662880147576353, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.4490356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 26.619357339301683, "y": 0.0264597308979706, "z": null, "yaw": 3.1092719870687766, "pitch": null, "roll": null}, "v": 2.1725445984417737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35582673024427397, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012407044607574084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.4690356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24255238557273454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1486221513773818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.164503047413146, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.4690356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.4890356, "x": 30.38098964360499, "y": 5.03409853952491, "z": null, "yaw": 3.109900178963118, "pitch": null, "roll": null}, "v": 2.1627214092279026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35490970940072236, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012350945990840254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.4890356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2457765079813335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2239439633837197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1627214092279026, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.4890356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.38098964360499, "y": 0.034098539524910265, "z": null, "yaw": 3.109900178963118, "pitch": null, "roll": null}, "v": 2.1627214092279026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35490970940072236, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012350945990840254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.5090356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24472311799581242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2239439633837197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1613459201416143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.5090356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.38098964360499, "y": 0.034098539524910265, "z": null, "yaw": 3.109900178963118, "pitch": null, "roll": null}, "v": 2.1627214092279026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35490970940072236, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012350945990840254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.5290356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24472311799581242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2239439633837197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.15984138232116, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.5290356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.38098964360499, "y": 0.034098539524910265, "z": null, "yaw": 3.109900178963118, "pitch": null, "roll": null}, "v": 2.1627214092279026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35490970940072236, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012350945990840254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.5490355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24472311799581242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2239439633837197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1583396477832144, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.5490355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.38098964360499, "y": 0.034098539524910265, "z": null, "yaw": 3.109900178963118, "pitch": null, "roll": null}, "v": 2.1627214092279026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35490970940072236, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012350945990840254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.5690355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24472311799581242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2239439633837197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.156840710402986, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.5690355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.38098964360499, "y": 0.034098539524910265, "z": null, "yaw": 3.109900178963118, "pitch": null, "roll": null}, "v": 2.1627214092279026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35490970940072236, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012350945990840254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.5890355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24472311799581242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2239439633837197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1553445640721316, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.5890355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.5990355, "x": 30.143608042403464, "y": 5.041543488415549, "z": null, "yaw": 3.110669419601192, "pitch": null, "roll": null}, "v": 2.154597535645846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35415278218840385, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015503539019511063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.6090355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24237768806864066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176943281445883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1538512026987005, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.6090355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 26.143608042403464, "y": 0.04154348841554878, "z": null, "yaw": 3.110669419601192, "pitch": null, "roll": null}, "v": 2.154597535645846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35415278218840385, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015503539019511063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.6290355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430727890160096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176943281445883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.152067577883197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.6290355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 26.143608042403464, "y": 0.04154348841554878, "z": null, "yaw": 3.110669419601192, "pitch": null, "roll": null}, "v": 2.154597535645846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35415278218840385, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015503539019511063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.6490355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430727890160096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176943281445883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.150374118064181, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.6490355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 26.143608042403464, "y": 0.04154348841554878, "z": null, "yaw": 3.110669419601192, "pitch": null, "roll": null}, "v": 2.154597535645846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35415278218840385, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015503539019511063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.6690354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430727890160096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176943281445883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.148683807155588, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.6690354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 26.143608042403464, "y": 0.04154348841554878, "z": null, "yaw": 3.110669419601192, "pitch": null, "roll": null}, "v": 2.154597535645846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35415278218840385, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015503539019511063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.6890354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430727890160096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176943281445883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1469966381598344, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.6890354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.7090354, "x": 29.90717579281735, "y": 5.048771993222283, "z": null, "yaw": 3.1114609313633363, "pitch": null, "roll": null}, "v": 2.1453126040987147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35328929189798386, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015436728723781613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.7090354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2465757060583484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2449596902435376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1453126040987147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.7090354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 25.90717579281735, "y": 0.04877199322228343, "z": null, "yaw": 3.1114609313633363, "pitch": null, "roll": null}, "v": 2.1453126040987147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35328929189798386, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015436728723781613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.7290354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24543786922207256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2449596902435376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1440693592738422, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.7290354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 25.90717579281735, "y": 0.04877199322228343, "z": null, "yaw": 3.1114609313633363, "pitch": null, "roll": null}, "v": 2.1453126040987147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35328929189798386, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015436728723781613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.7490354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24543786922207256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2449596902435376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.142686259455547, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.7490354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 25.90717579281735, "y": 0.04877199322228343, "z": null, "yaw": 3.1114609313633363, "pitch": null, "roll": null}, "v": 2.1453126040987147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35328929189798386, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015436728723781613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.7690353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24543786922207256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2449596902435376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1413057271553853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.7690353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 25.90717579281735, "y": 0.04877199322228343, "z": null, "yaw": 3.1114609313633363, "pitch": null, "roll": null}, "v": 2.1453126040987147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35328929189798386, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015436728723781613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.7890353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24543786922207256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2449596902435376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1399277568451485, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.7890353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 25.90717579281735, "y": 0.04877199322228343, "z": null, "yaw": 3.1114609313633363, "pitch": null, "roll": null}, "v": 2.1453126040987147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35328929189798386, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015436728723781613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.8090353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24543786922207256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2449596902435376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1385523430111313, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.8090353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.8190353, "x": 29.671662474334322, "y": 5.055785808911519, "z": null, "yaw": 3.1122524431254805, "pitch": null, "roll": null}, "v": 2.1378655930536254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35259797259230663, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015383143298008968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.8290353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24789411865465044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2926588368318093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.137179480154082, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.8290353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 25.671662474334322, "y": 0.0557858089115193, "z": null, "yaw": 3.1122524431254805, "pitch": null, "roll": null}, "v": 2.1378655930536254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35259797259230663, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015383143298008968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.8490353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709197421575912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2926588368318093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.136116051611051, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.8490353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 25.671662474334322, "y": 0.0557858089115193, "z": null, "yaw": 3.1122524431254805, "pitch": null, "roll": null}, "v": 2.1378655930536254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35259797259230663, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015383143298008968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.8690352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709197421575912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2926588368318093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1349543727630325, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.8690352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 25.671662474334322, "y": 0.0557858089115193, "z": null, "yaw": 3.1122524431254805, "pitch": null, "roll": null}, "v": 2.1378655930536254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35259797259230663, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015383143298008968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.8890352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709197421575912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2926588368318093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133794846783039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.8890352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 25.671662474334322, "y": 0.0557858089115193, "z": null, "yaw": 3.1122524431254805, "pitch": null, "roll": null}, "v": 2.1378655930536254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35259797259230663, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015383143298008968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.9090352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709197421575912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2926588368318093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1326374691437415, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.9090352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.9290352, "x": 29.436917000673038, "y": 5.062580624078933, "z": null, "yaw": 3.113170417768091, "pitch": null, "roll": null}, "v": 2.131482235329187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35200627696169845, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01850843494479745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.9290352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.248375202494087, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3041873285170986, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131482235329187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.9290352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.436917000673038, "y": 0.06258062407893306, "z": null, "yaw": 3.113170417768091, "pitch": null, "roll": null}, "v": 2.131482235329187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35200627696169845, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01850843494479745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.9490352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24794460859325979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3041873285170986, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.130489470087551, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.9490352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.436917000673038, "y": 0.06258062407893306, "z": null, "yaw": 3.113170417768091, "pitch": null, "roll": null}, "v": 2.131482235329187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35200627696169845, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01850843494479745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.9690351} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24794460859325979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3041873285170986, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.129444743571487, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.9690351} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.436917000673038, "y": 0.06258062407893306, "z": null, "yaw": 3.113170417768091, "pitch": null, "roll": null}, "v": 2.131482235329187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35200627696169845, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01850843494479745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.9890351} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24794460859325979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3041873285170986, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128401950870376, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.9890351} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.436917000673038, "y": 0.06258062407893306, "z": null, "yaw": 3.113170417768091, "pitch": null, "roll": null}, "v": 2.131482235329187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35200627696169845, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01850843494479745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.009035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24794460859325979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3041873285170986, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1273610879699127, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.009035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.436917000673038, "y": 0.06258062407893306, "z": null, "yaw": 3.113170417768091, "pitch": null, "roll": null}, "v": 2.131482235329187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35200627696169845, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01850843494479745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.029035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24794460859325979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3041873285170986, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1263221508656343, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.029035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.039035, "x": 29.202827726728685, "y": 5.0691340912646305, "z": null, "yaw": 3.1141255877480174, "pitch": null, "roll": null}, "v": 2.125803403238354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514805712541154, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018459123581759336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.049035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24768946164358754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2381846391075275, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.125285135562892, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.049035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 25.202827726728685, "y": 0.06913409126463055, "z": null, "yaw": 3.1141255877480174, "pitch": null, "roll": null}, "v": 2.125803403238354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514805712541154, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018459123581759336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.069035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2477429098150243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2381846391075275, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1242181594580263, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.069035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 25.202827726728685, "y": 0.06913409126463055, "z": null, "yaw": 3.1141255877480174, "pitch": null, "roll": null}, "v": 2.125803403238354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514805712541154, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018459123581759336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.089035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2477429098150243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2381846391075275, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.123159834058775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.089035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 25.202827726728685, "y": 0.06913409126463055, "z": null, "yaw": 3.1141255877480174, "pitch": null, "roll": null}, "v": 2.125803403238354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514805712541154, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018459123581759336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.109035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2477429098150243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2381846391075275, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1221034649896597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.109035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 25.202827726728685, "y": 0.06913409126463055, "z": null, "yaw": 3.1141255877480174, "pitch": null, "roll": null}, "v": 2.125803403238354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514805712541154, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018459123581759336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.129035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2477429098150243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2381846391075275, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1210490481882136, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.129035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.149035, "x": 28.96936517560978, "y": 5.075446848843851, "z": null, "yaw": 3.115080757727944, "pitch": null, "roll": null}, "v": 2.1199965796019535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35094368395533754, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018408700821612035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.149035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24404869848387808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1067987070536842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1199965796019535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.149035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 24.96936517560978, "y": 0.07544684884385067, "z": null, "yaw": 3.115080757727944, "pitch": null, "roll": null}, "v": 2.1199965796019535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35094368395533754, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018408700821612035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.169035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517629589923287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1067987070536842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1184844920829033, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.169035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 24.96936517560978, "y": 0.07544684884385067, "z": null, "yaw": 3.115080757727944, "pitch": null, "roll": null}, "v": 2.1199965796019535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35094368395533754, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018408700821612035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.189035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517629589923287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1067987070536842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1164328239157144, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.189035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 24.96936517560978, "y": 0.07544684884385067, "z": null, "yaw": 3.115080757727944, "pitch": null, "roll": null}, "v": 2.1199965796019535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35094368395533754, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018408700821612035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.209035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517629589923287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1067987070536842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.115750197207644, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.209035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 24.96936517560978, "y": 0.07544684884385067, "z": null, "yaw": 3.115080757727944, "pitch": null, "roll": null}, "v": 2.1199965796019535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35094368395533754, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018408700821612035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.229035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517629589923287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1067987070536842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.114386833757022, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.229035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 24.96936517560978, "y": 0.07544684884385067, "z": null, "yaw": 3.115080757727944, "pitch": null, "roll": null}, "v": 2.1199965796019535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35094368395533754, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018408700821612035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.249035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517629589923287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1067987070536842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.113025985765553, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.249035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.2590349, "x": 28.73663426814703, "y": 5.081517384318908, "z": null, "yaw": 3.11603592770787, "pitch": null, "roll": null}, "v": 2.11234650338472, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502374026728526, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01834227242936811, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.2690349} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24910865525306555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.171033920132796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111667647851694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.2690349} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 24.73663426814703, "y": 0.08151738431890809, "z": null, "yaw": 3.11603592770787, "pitch": null, "roll": null}, "v": 2.11234650338472, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502374026728526, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01834227242936811, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.2890348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24784447806200943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.171033920132796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110292462236102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.2890348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 24.73663426814703, "y": 0.08151738431890809, "z": null, "yaw": 3.11603592770787, "pitch": null, "roll": null}, "v": 2.11234650338472, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502374026728526, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01834227242936811, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.3090348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24784447806200943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.171033920132796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1097822624562426, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.3090348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 24.73663426814703, "y": 0.08151738431890809, "z": null, "yaw": 3.11603592770787, "pitch": null, "roll": null}, "v": 2.11234650338472, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502374026728526, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01834227242936811, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.3290348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24784447806200943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.171033920132796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1087632736348434, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.3290348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 24.73663426814703, "y": 0.08151738431890809, "z": null, "yaw": 3.11603592770787, "pitch": null, "roll": null}, "v": 2.11234650338472, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502374026728526, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01834227242936811, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.3490348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24784447806200943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.171033920132796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1077461625627714, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.3490348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.3690348, "x": 28.504633490556156, "y": 5.087347111754682, "z": null, "yaw": 3.1169910976877966, "pitch": null, "roll": null}, "v": 2.106730925366174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3497196981872509, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0182935103244296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.3690348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512132168395612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.242088770229883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106730925366174, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.3690348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 24.504633490556156, "y": 0.08734711175468224, "z": null, "yaw": 3.1169910976877966, "pitch": null, "roll": null}, "v": 2.106730925366174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3497196981872509, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0182935103244296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.3890347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501346000400999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.242088770229883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106138456558816, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.3890347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 24.504633490556156, "y": 0.08734711175468224, "z": null, "yaw": 3.1169910976877966, "pitch": null, "roll": null}, "v": 2.106730925366174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3497196981872509, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0182935103244296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.4090347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501346000400999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.242088770229883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105412313879935, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.4090347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 24.504633490556156, "y": 0.08734711175468224, "z": null, "yaw": 3.1169910976877966, "pitch": null, "roll": null}, "v": 2.106730925366174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3497196981872509, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0182935103244296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.4290347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501346000400999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.242088770229883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1046875083122782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.4290347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 24.504633490556156, "y": 0.08734711175468224, "z": null, "yaw": 3.1169910976877966, "pitch": null, "roll": null}, "v": 2.106730925366174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3497196981872509, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0182935103244296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.4490347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501346000400999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.242088770229883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1039640371836623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.4490347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 24.504633490556156, "y": 0.08734711175468224, "z": null, "yaw": 3.1169910976877966, "pitch": null, "roll": null}, "v": 2.106730925366174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3497196981872509, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0182935103244296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.4690347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501346000400999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.242088770229883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1032418978279845, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.4690347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.4790347, "x": 28.27314748709074, "y": 5.092942646976216, "z": null, "yaw": 3.117946267667723, "pitch": null, "roll": null}, "v": 2.102881326733499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493651650799193, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018260082860350618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.4890347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253006023174405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3211479268021353, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102521087585206, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.4890347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 24.27314748709074, "y": 0.09294264697621557, "z": null, "yaw": 3.117946267667723, "pitch": null, "roll": null}, "v": 2.102881326733499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493651650799193, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018260082860350618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.5090346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520909761896165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3211479268021353, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102160366505501, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.5090346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 24.27314748709074, "y": 0.09294264697621557, "z": null, "yaw": 3.117946267667723, "pitch": null, "roll": null}, "v": 2.102881326733499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493651650799193, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018260082860350618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.5290346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520909761896165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3211479268021353, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1016859809361295, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.5290346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 24.27314748709074, "y": 0.09294264697621557, "z": null, "yaw": 3.117946267667723, "pitch": null, "roll": null}, "v": 2.102881326733499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493651650799193, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018260082860350618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.5490346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520909761896165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3211479268021353, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101212468176807, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.5490346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 24.27314748709074, "y": 0.09294264697621557, "z": null, "yaw": 3.117946267667723, "pitch": null, "roll": null}, "v": 2.102881326733499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493651650799193, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018260082860350618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.5690346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520909761896165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3211479268021353, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100739826532028, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.5690346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.5890346, "x": 28.042025837779523, "y": 5.098308478901062, "z": null, "yaw": 3.1189014376476494, "pitch": null, "roll": null}, "v": 2.100268054309901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34912466171504203, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018237390866092582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.5890346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25150713319424656, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2607888108358332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100268054309901, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.5890346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.042025837779523, "y": 0.0983084789010622, "z": null, "yaw": 3.1189014376476494, "pitch": null, "roll": null}, "v": 2.100268054309901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34912466171504203, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018237390866092582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.6090345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25167755907379574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2607888108358332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0997242030187935, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.6090345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.042025837779523, "y": 0.0983084789010622, "z": null, "yaw": 3.1189014376476494, "pitch": null, "roll": null}, "v": 2.100268054309901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34912466171504203, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018237390866092582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.6290345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25167755907379574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2607888108358332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0992026453599784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.6290345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.042025837779523, "y": 0.0983084789010622, "z": null, "yaw": 3.1189014376476494, "pitch": null, "roll": null}, "v": 2.100268054309901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34912466171504203, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018237390866092582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.6490345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25167755907379574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2607888108358332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0986820467868053, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.6490345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.042025837779523, "y": 0.0983084789010622, "z": null, "yaw": 3.1189014376476494, "pitch": null, "roll": null}, "v": 2.100268054309901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34912466171504203, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018237390866092582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.6690345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25167755907379574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2607888108358332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0981624054272645, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.6690345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.042025837779523, "y": 0.0983084789010622, "z": null, "yaw": 3.1189014376476494, "pitch": null, "roll": null}, "v": 2.100268054309901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34912466171504203, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018237390866092582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.6890345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25167755907379574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2607888108358332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.097643719413387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.6890345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.6990345, "x": 27.811198935337504, "y": 5.103446877798125, "z": null, "yaw": 3.1198566076275758, "pitch": null, "roll": null}, "v": 2.097384734078433, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3488594639313743, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018212353948568898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.7090344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531731070877572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2569802529400453, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0971259868812315, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.7090344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 23.811198935337504, "y": 0.10344687779812478, "z": null, "yaw": 3.1198566076275758, "pitch": null, "roll": null}, "v": 2.097384734078433, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3488594639313743, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018212353948568898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.7290344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526924881290925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2569802529400453, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096796063536299, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.7290344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 23.811198935337504, "y": 0.10344687779812478, "z": null, "yaw": 3.1198566076275758, "pitch": null, "roll": null}, "v": 2.097384734078433, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3488594639313743, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018212353948568898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.7490344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526924881290925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2569802529400453, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0964066968049506, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.7490344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 23.811198935337504, "y": 0.10344687779812478, "z": null, "yaw": 3.1198566076275758, "pitch": null, "roll": null}, "v": 2.097384734078433, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3488594639313743, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018212353948568898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.7690344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526924881290925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2569802529400453, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096018045634851, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.7690344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 23.811198935337504, "y": 0.10344687779812478, "z": null, "yaw": 3.1198566076275758, "pitch": null, "roll": null}, "v": 2.097384734078433, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3488594639313743, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018212353948568898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.7890344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526924881290925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2569802529400453, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095630108650581, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.7890344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.8090343, "x": 27.580647297491975, "y": 5.1083588219052976, "z": null, "yaw": 3.120811777607502, "pitch": null, "roll": null}, "v": 2.095242884479581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3486625716736022, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819375549003857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.8090343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25412294788735346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2488575657181733, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095242884479581, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.8090343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 23.580647297491975, "y": 0.10835882190529755, "z": null, "yaw": 3.120811777607502, "pitch": null, "roll": null}, "v": 2.095242884479581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3486625716736022, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819375549003857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.8290343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536660843004652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2488575657181733, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0950350970582114, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.8290343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 23.580647297491975, "y": 0.10835882190529755, "z": null, "yaw": 3.120811777607502, "pitch": null, "roll": null}, "v": 2.095242884479581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3486625716736022, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819375549003857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.8490343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536660843004652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2488575657181733, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0947706096741308, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.8490343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 23.580647297491975, "y": 0.10835882190529755, "z": null, "yaw": 3.120811777607502, "pitch": null, "roll": null}, "v": 2.095242884479581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3486625716736022, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819375549003857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.8690343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536660843004652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2488575657181733, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0945066081772326, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.8690343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 23.580647297491975, "y": 0.10835882190529755, "z": null, "yaw": 3.120811777607502, "pitch": null, "roll": null}, "v": 2.095242884479581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3486625716736022, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819375549003857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.8890343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536660843004652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2488575657181733, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.094243091647032, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.8890343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 23.580647297491975, "y": 0.10835882190529755, "z": null, "yaw": 3.120811777607502, "pitch": null, "roll": null}, "v": 2.095242884479581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3486625716736022, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819375549003857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.9090343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536660843004652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2488575657181733, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093980059164889, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.9090343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.9190342, "x": 27.350285548830747, "y": 5.11304658426857, "z": null, "yaw": 3.1217669475874286, "pitch": null, "roll": null}, "v": 2.0938487241552677, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485344610042298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018181649489229616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.9290342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25467048956662924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2448778431826115, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0937175098140046, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.9290342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 23.350285548830747, "y": 0.11304658426857017, "z": null, "yaw": 3.1217669475874286, "pitch": null, "roll": null}, "v": 2.0938487241552677, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485344610042298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018181649489229616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.9490342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25435020717749085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2448778431826115, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093580935664512, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.9490342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 23.350285548830747, "y": 0.11304658426857017, "z": null, "yaw": 3.1217669475874286, "pitch": null, "roll": null}, "v": 2.0938487241552677, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485344610042298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018181649489229616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.9690342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25435020717749085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2448778431826115, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093404595438956, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.9690342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 23.350285548830747, "y": 0.11304658426857017, "z": null, "yaw": 3.1217669475874286, "pitch": null, "roll": null}, "v": 2.0938487241552677, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485344610042298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018181649489229616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.9890342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25435020717749085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2448778431826115, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093228579068483, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.9890342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 23.350285548830747, "y": 0.11304658426857017, "z": null, "yaw": 3.1217669475874286, "pitch": null, "roll": null}, "v": 2.0938487241552677, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485344610042298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018181649489229616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.0090342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25435020717749085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2448778431826115, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0930528859459336, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.0090342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.0290341, "x": 27.12005487601691, "y": 5.117511678991158, "z": null, "yaw": 3.122722117567355, "pitch": null, "roll": null}, "v": 2.0928775154653336, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484452387206702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173216131185374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.0290341} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563920266492972, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3072721896025186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0928775154653336, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.0290341} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.12005487601691, "y": 0.11751167899115789, "z": null, "yaw": 3.122722117567355, "pitch": null, "roll": null}, "v": 2.0928775154653336, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484452387206702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173216131185374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.049034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574949652890416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3072721896025186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.092957577233636, "gear": 1, "accelerator_pedal_position": 0.2563920266492972, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.049034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.12005487601691, "y": 0.11751167899115789, "z": null, "yaw": 3.122722117567355, "pitch": null, "roll": null}, "v": 2.0928775154653336, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484452387206702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173216131185374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.069034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574949652890416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3072721896025186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0929572126060445, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.069034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.12005487601691, "y": 0.11751167899115789, "z": null, "yaw": 3.122722117567355, "pitch": null, "roll": null}, "v": 2.0928775154653336, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484452387206702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173216131185374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.089034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574949652890416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3072721896025186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0929568486480328, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.089034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.12005487601691, "y": 0.11751167899115789, "z": null, "yaw": 3.122722117567355, "pitch": null, "roll": null}, "v": 2.0928775154653336, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484452387206702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173216131185374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.109034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574949652890416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3072721896025186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0929564853583713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.109034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.12005487601691, "y": 0.11751167899115789, "z": null, "yaw": 3.122722117567355, "pitch": null, "roll": null}, "v": 2.0928775154653336, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484452387206702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173216131185374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.129034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574949652890416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3072721896025186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0929561227358326, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.129034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.139034, "x": 26.889869942888467, "y": 5.121755933504789, "z": null, "yaw": 3.1236772875472814, "pitch": null, "roll": null}, "v": 2.0929559416743513, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484524428216173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173897134462585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.149034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2568124780277934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2870336004955234, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0929557607791915, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.149034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 22.889869942888467, "y": 0.1217559335047893, "z": null, "yaw": 3.1236772875472814, "pitch": null, "roll": null}, "v": 2.0929559416743513, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484524428216173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173897134462585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.169034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564806562968786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2870336004955234, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0930882111463105, "gear": 1, "accelerator_pedal_position": 0.2568124780277934, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.169034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 22.889869942888467, "y": 0.1217559335047893, "z": null, "yaw": 3.1236772875472814, "pitch": null, "roll": null}, "v": 2.0929559416743513, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484524428216173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173897134462585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.189034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564806562968786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2870336004955234, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0931789596194124, "gear": 1, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.189034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 22.889869942888467, "y": 0.1217559335047893, "z": null, "yaw": 3.1236772875472814, "pitch": null, "roll": null}, "v": 2.0929559416743513, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484524428216173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173897134462585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.209034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564806562968786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2870336004955234, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093269541440328, "gear": 1, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.209034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 22.889869942888467, "y": 0.1217559335047893, "z": null, "yaw": 3.1236772875472814, "pitch": null, "roll": null}, "v": 2.0929559416743513, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484524428216173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173897134462585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.229034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564806562968786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2870336004955234, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0933599569118204, "gear": 1, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.229034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.249034, "x": 26.65965605038508, "y": 5.125780753594502, "z": null, "yaw": 3.1246324575272078, "pitch": null, "roll": null}, "v": 2.0934502063361147, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "acceleration": 0.004506253874598298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018178189014163074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.249034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2573261444034519, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2496628703992003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0934502063361147, "gear": 1, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.249034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 22.65965605038508, "y": 0.12578075359450214, "z": null, "yaw": 3.1246324575272078, "pitch": null, "roll": null}, "v": 2.0934502063361147, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "acceleration": 0.004506253874598298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018178189014163074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.269034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25706419945636705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2496628703992003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0936459274811203, "gear": 1, "accelerator_pedal_position": 0.2573261444034519, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.269034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 22.65965605038508, "y": 0.12578075359450214, "z": null, "yaw": 3.1246324575272078, "pitch": null, "roll": null}, "v": 2.0934502063361147, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "acceleration": 0.004506253874598298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018178189014163074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.289034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25706419945636705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2496628703992003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093808561088636, "gear": 1, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.289034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 22.65965605038508, "y": 0.12578075359450214, "z": null, "yaw": 3.1246324575272078, "pitch": null, "roll": null}, "v": 2.0934502063361147, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "acceleration": 0.004506253874598298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018178189014163074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.3090339} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25706419945636705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2496628703992003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0939708959930154, "gear": 1, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.3090339} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 22.65965605038508, "y": 0.12578075359450214, "z": null, "yaw": 3.1246324575272078, "pitch": null, "roll": null}, "v": 2.0934502063361147, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "acceleration": 0.004506253874598298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018178189014163074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.3290339} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25706419945636705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2496628703992003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0941329327323386, "gear": 1, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.3290339} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 22.65965605038508, "y": 0.12578075359450214, "z": null, "yaw": 3.1246324575272078, "pitch": null, "roll": null}, "v": 2.0934502063361147, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "acceleration": 0.004506253874598298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018178189014163074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.3490338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25706419945636705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2496628703992003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0942946718437563, "gear": 1, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.3490338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.3590338, "x": 26.42936016906471, "y": 5.129586968310505, "z": null, "yaw": 3.125587627507134, "pitch": null, "roll": null}, "v": 2.094375429956606, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "acceleration": 0.008068390688404481, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018186223067135892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.3690338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2561992563890647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0353110850625946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0944561138634903, "gear": 1, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.3690338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 22.42936016906471, "y": 0.1295869683105053, "z": null, "yaw": 3.125587627507134, "pitch": null, "roll": null}, "v": 2.094375429956606, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "acceleration": 0.008068390688404481, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018186223067135892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.3890338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25647380167425243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0353110850625946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0945091911182883, "gear": 1, "accelerator_pedal_position": 0.2561992563890647, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.3890338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 22.42936016906471, "y": 0.1295869683105053, "z": null, "yaw": 3.125587627507134, "pitch": null, "roll": null}, "v": 2.094375429956606, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "acceleration": 0.008068390688404481, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018186223067135892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.4090338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25647380167425243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0353110850625946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0945964732656286, "gear": 1, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.4090338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 22.42936016906471, "y": 0.1295869683105053, "z": null, "yaw": 3.125587627507134, "pitch": null, "roll": null}, "v": 2.094375429956606, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "acceleration": 0.008068390688404481, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018186223067135892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.4290338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25647380167425243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0353110850625946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0946835950769342, "gear": 1, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.4290338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 22.42936016906471, "y": 0.1295869683105053, "z": null, "yaw": 3.125587627507134, "pitch": null, "roll": null}, "v": 2.094375429956606, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "acceleration": 0.008068390688404481, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018186223067135892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.4490337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25647380167425243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0353110850625946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0947705568437054, "gear": 1, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.4490337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.4690337, "x": 26.198982028236397, "y": 5.133174439529274, "z": null, "yaw": 3.1265427974870605, "pitch": null, "roll": null}, "v": 2.0948573588569235, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "acceleration": 0.004334118981661361, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819040783093626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.4690337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25848563947347525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0862990913809534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0948573588569235, "gear": 1, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.4690337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 22.198982028236397, "y": 0.13317443952927377, "z": null, "yaw": 3.1265427974870605, "pitch": null, "roll": null}, "v": 2.0948573588569235, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "acceleration": 0.004334118981661361, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819040783093626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.4890337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578591540288886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0862990913809534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095195365577937, "gear": 1, "accelerator_pedal_position": 0.25848563947347525, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.4890337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 22.198982028236397, "y": 0.13317443952927377, "z": null, "yaw": 3.1265427974870605, "pitch": null, "roll": null}, "v": 2.0948573588569235, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "acceleration": 0.004334118981661361, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819040783093626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.5090337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578591540288886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0862990913809534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0954544766189773, "gear": 1, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.5090337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 22.198982028236397, "y": 0.13317443952927377, "z": null, "yaw": 3.1265427974870605, "pitch": null, "roll": null}, "v": 2.0948573588569235, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "acceleration": 0.004334118981661361, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819040783093626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.5290337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578591540288886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0862990913809534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0957131115924095, "gear": 1, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.5290337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 22.198982028236397, "y": 0.13317443952927377, "z": null, "yaw": 3.1265427974870605, "pitch": null, "roll": null}, "v": 2.0948573588569235, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "acceleration": 0.004334118981661361, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819040783093626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.5490336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578591540288886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0862990913809534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095971271346173, "gear": 1, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.5490336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 22.198982028236397, "y": 0.13317443952927377, "z": null, "yaw": 3.1265427974870605, "pitch": null, "roll": null}, "v": 2.0948573588569235, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "acceleration": 0.004334118981661361, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819040783093626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.5690336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578591540288886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0862990913809534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0962289567267978, "gear": 1, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.5690336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.5790336, "x": 25.968493674810173, "y": 5.136543412440239, "z": null, "yaw": 3.127497967466987, "pitch": null, "roll": null}, "v": 2.0963576217913378, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "acceleration": 0.012854678806560382, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018203435159272127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.5890336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25957929467269436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.142497520608681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0964861685794034, "gear": 1, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.5890336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 21.968493674810173, "y": 0.13654341244023893, "z": null, "yaw": 3.127497967466987, "pitch": null, "roll": null}, "v": 2.0963576217913378, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "acceleration": 0.012854678806560382, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018203435159272127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.6090336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590486449931629, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.142497520608681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0969578264917295, "gear": 1, "accelerator_pedal_position": 0.25957929467269436, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.6090336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 21.968493674810173, "y": 0.13654341244023893, "z": null, "yaw": 3.127497967466987, "pitch": null, "roll": null}, "v": 2.0963576217913378, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "acceleration": 0.012854678806560382, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018203435159272127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.6290336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590486449931629, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.142497520608681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0975642831169004, "gear": 1, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.6290336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 21.968493674810173, "y": 0.13654341244023893, "z": null, "yaw": 3.127497967466987, "pitch": null, "roll": null}, "v": 2.0963576217913378, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "acceleration": 0.012854678806560382, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018203435159272127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.6490335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590486449931629, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.142497520608681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.097766063695234, "gear": 1, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.6490335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 21.968493674810173, "y": 0.13654341244023893, "z": null, "yaw": 3.127497967466987, "pitch": null, "roll": null}, "v": 2.0963576217913378, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "acceleration": 0.012854678806560382, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018203435159272127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.6690335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590486449931629, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.142497520608681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09816906838266, "gear": 1, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.6690335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.6890335, "x": 25.737806373453065, "y": 5.1396948969128, "z": null, "yaw": 3.1284531374469133, "pitch": null, "roll": null}, "v": 2.0985713321936768, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "acceleration": 0.02008544823453262, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018222657611277216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.6890335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596408637601385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0762056610724053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0985713321936768, "gear": 1, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.6890335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 21.737806373453065, "y": 0.13969489691279957, "z": null, "yaw": 3.1284531374469133, "pitch": null, "roll": null}, "v": 2.0985713321936768, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "acceleration": 0.02008544823453262, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018222657611277216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.7090335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25946597273572825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0762056610724053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0990468497278454, "gear": 1, "accelerator_pedal_position": 0.2596408637601385, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.7090335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 21.737806373453065, "y": 0.13969489691279957, "z": null, "yaw": 3.1284531374469133, "pitch": null, "roll": null}, "v": 2.0985713321936768, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "acceleration": 0.02008544823453262, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018222657611277216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.7290335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25946597273572825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0762056610724053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099499641592565, "gear": 1, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.7290335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 21.737806373453065, "y": 0.13969489691279957, "z": null, "yaw": 3.1284531374469133, "pitch": null, "roll": null}, "v": 2.0985713321936768, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "acceleration": 0.02008544823453262, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018222657611277216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.7490335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25946597273572825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0762056610724053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0999516008145296, "gear": 1, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.7490335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 21.737806373453065, "y": 0.13969489691279957, "z": null, "yaw": 3.1284531374469133, "pitch": null, "roll": null}, "v": 2.0985713321936768, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "acceleration": 0.02008544823453262, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018222657611277216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.7690334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25946597273572825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0762056610724053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100402728843223, "gear": 1, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.7690334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 21.737806373453065, "y": 0.13969489691279957, "z": null, "yaw": 3.1284531374469133, "pitch": null, "roll": null}, "v": 2.0985713321936768, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "acceleration": 0.02008544823453262, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018222657611277216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.7890334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25946597273572825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0762056610724053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1008530271259147, "gear": 1, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.7890334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.7990334, "x": 25.506855636790856, "y": 5.142629342567666, "z": null, "yaw": 3.1294083074268397, "pitch": null, "roll": null}, "v": 2.1010778655641764, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "acceleration": 0.022463154348455472, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01824442275154248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.8090334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2608412967745821, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.129054748340912, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101302497107661, "gear": 1, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.8090334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 21.506855636790856, "y": 0.14262934256766613, "z": null, "yaw": 3.1294083074268397, "pitch": null, "roll": null}, "v": 2.1010778655641764, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "acceleration": 0.022463154348455472, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01824442275154248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.8290334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042303735206357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.129054748340912, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1022066469542646, "gear": 1, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.8290334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 21.506855636790856, "y": 0.14262934256766613, "z": null, "yaw": 3.1294083074268397, "pitch": null, "roll": null}, "v": 2.1010778655641764, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "acceleration": 0.022463154348455472, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01824442275154248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.8490334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042303735206357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.129054748340912, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1024900561866415, "gear": 1, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.8490334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 21.506855636790856, "y": 0.14262934256766613, "z": null, "yaw": 3.1294083074268397, "pitch": null, "roll": null}, "v": 2.1010778655641764, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "acceleration": 0.022463154348455472, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01824442275154248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.8690333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042303735206357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.129054748340912, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1030560922666677, "gear": 1, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.8690333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 21.506855636790856, "y": 0.14262934256766613, "z": null, "yaw": 3.1294083074268397, "pitch": null, "roll": null}, "v": 2.1010778655641764, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "acceleration": 0.022463154348455472, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01824442275154248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.8890333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042303735206357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.129054748340912, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103621086660118, "gear": 1, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.8890333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.9090333, "x": 25.2755985583672, "y": 5.145346752186839, "z": null, "yaw": 3.130363477406766, "pitch": null, "roll": null}, "v": 2.104185041156399, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "acceleration": 0.028158784518313718, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01827140348652469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.9090333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606666107783506, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0765647902471507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104185041156399, "gear": 1, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.9090333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 21.2755985583672, "y": 0.145346752186839, "z": null, "yaw": 3.130363477406766, "pitch": null, "roll": null}, "v": 2.104185041156399, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "acceleration": 0.028158784518313718, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01827140348652469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.9290333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606047952262184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0765647902471507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.10507079150087, "gear": 1, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.9290333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 21.2755985583672, "y": 0.145346752186839, "z": null, "yaw": 3.130363477406766, "pitch": null, "roll": null}, "v": 2.104185041156399, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "acceleration": 0.028158784518313718, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01827140348652469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.9490333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606047952262184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0765647902471507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1053629235030353, "gear": 1, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.9490333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 21.2755985583672, "y": 0.145346752186839, "z": null, "yaw": 3.130363477406766, "pitch": null, "roll": null}, "v": 2.104185041156399, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "acceleration": 0.028158784518313718, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01827140348652469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.9690332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606047952262184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0765647902471507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1059463805394105, "gear": 1, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.9690332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 21.2755985583672, "y": 0.145346752186839, "z": null, "yaw": 3.130363477406766, "pitch": null, "roll": null}, "v": 2.104185041156399, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "acceleration": 0.028158784518313718, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01827140348652469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.9890332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606047952262184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0765647902471507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1065287631561977, "gear": 1, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.9890332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 21.2755985583672, "y": 0.145346752186839, "z": null, "yaw": 3.130363477406766, "pitch": null, "roll": null}, "v": 2.104185041156399, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "acceleration": 0.028158784518313718, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01827140348652469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.0090332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606047952262184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0765647902471507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107110073196305, "gear": 1, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.0090332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.0190332, "x": 25.043990299761077, "y": 5.147847034402972, "z": null, "yaw": 3.1313186473866925, "pitch": null, "roll": null}, "v": 2.107400326575289, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "acceleration": 0.028998592470603934, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018299322978424796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.0290332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26140506716454065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0947072703890302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107690312499995, "gear": 1, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.0290332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 21.043990299761077, "y": 0.14784703440297164, "z": null, "yaw": 3.1313186473866925, "pitch": null, "roll": null}, "v": 2.107400326575289, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "acceleration": 0.028998592470603934, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018299322978424796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.0490332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611697909676147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0947072703890302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108369470801464, "gear": 1, "accelerator_pedal_position": 0.26140506716454065, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.0490332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 21.043990299761077, "y": 0.14784703440297164, "z": null, "yaw": 3.1313186473866925, "pitch": null, "roll": null}, "v": 2.107400326575289, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "acceleration": 0.028998592470603934, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018299322978424796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.0690331} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611697909676147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0947072703890302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1090179818303736, "gear": 1, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.0690331} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 21.043990299761077, "y": 0.14784703440297164, "z": null, "yaw": 3.1313186473866925, "pitch": null, "roll": null}, "v": 2.107400326575289, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "acceleration": 0.028998592470603934, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018299322978424796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.0890331} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611697909676147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0947072703890302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1096652978527763, "gear": 1, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.0890331} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 21.043990299761077, "y": 0.14784703440297164, "z": null, "yaw": 3.1313186473866925, "pitch": null, "roll": null}, "v": 2.107400326575289, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "acceleration": 0.028998592470603934, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018299322978424796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.109033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611697909676147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0947072703890302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1103114209031726, "gear": 1, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.109033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.129033, "x": 24.81201010841919, "y": 5.150129724525278, "z": null, "yaw": 3.132273817366619, "pitch": null, "roll": null}, "v": 2.110956353013239, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "acceleration": 0.03220200865366046, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01833020124843703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.129033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26117446579489123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0456772257988505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110956353013239, "gear": 1, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.129033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 20.81201010841919, "y": 0.15012972452527773, "z": null, "yaw": 3.132273817366619, "pitch": null, "roll": null}, "v": 2.110956353013239, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "acceleration": 0.03220200865366046, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01833020124843703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.149033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611893952811894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0456772257988505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1116006802957776, "gear": 1, "accelerator_pedal_position": 0.26117446579489123, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.149033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 20.81201010841919, "y": 0.15012972452527773, "z": null, "yaw": 3.132273817366619, "pitch": null, "roll": null}, "v": 2.110956353013239, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "acceleration": 0.03220200865366046, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01833020124843703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.169033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611893952811894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0456772257988505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1122456849409885, "gear": 1, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.169033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 20.81201010841919, "y": 0.15012972452527773, "z": null, "yaw": 3.132273817366619, "pitch": null, "roll": null}, "v": 2.110956353013239, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "acceleration": 0.03220200865366046, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01833020124843703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.189033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611893952811894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0456772257988505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112889500208669, "gear": 1, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.189033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 20.81201010841919, "y": 0.15012972452527773, "z": null, "yaw": 3.132273817366619, "pitch": null, "roll": null}, "v": 2.110956353013239, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "acceleration": 0.03220200865366046, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01833020124843703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.209033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611893952811894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0456772257988505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1135321281262884, "gear": 1, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.209033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 20.81201010841919, "y": 0.15012972452527773, "z": null, "yaw": 3.132273817366619, "pitch": null, "roll": null}, "v": 2.110956353013239, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "acceleration": 0.03220200865366046, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01833020124843703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.229033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611893952811894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0456772257988505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1144938481494955, "gear": 1, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.229033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.239033, "x": 24.57963697251532, "y": 5.152194306289341, "z": null, "yaw": 3.1332289873465453, "pitch": null, "roll": null}, "v": 2.1144938481494955, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "acceleration": 0.03199818576133823, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018360918604421385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.249033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2622362867486526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0830920323446958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1148138300071087, "gear": 1, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.249033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 20.57963697251532, "y": 0.15219430628934116, "z": null, "yaw": 3.1332289873465453, "pitch": null, "roll": null}, "v": 2.1144938481494955, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "acceleration": 0.03199818576133823, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018360918604421385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.269033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619254504538784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0830920323446958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.115583709049848, "gear": 1, "accelerator_pedal_position": 0.2622362867486526, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.269033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 20.57963697251532, "y": 0.15219430628934116, "z": null, "yaw": 3.1332289873465453, "pitch": null, "roll": null}, "v": 2.1144938481494955, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "acceleration": 0.03199818576133823, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018360918604421385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.289033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619254504538784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0830920323446958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.116313330829659, "gear": 1, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.289033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 20.57963697251532, "y": 0.15219430628934116, "z": null, "yaw": 3.1332289873465453, "pitch": null, "roll": null}, "v": 2.1144938481494955, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "acceleration": 0.03199818576133823, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018360918604421385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.309033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619254504538784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0830920323446958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1170416060195203, "gear": 1, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.309033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 20.57963697251532, "y": 0.15219430628934116, "z": null, "yaw": 3.1332289873465453, "pitch": null, "roll": null}, "v": 2.1144938481494955, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "acceleration": 0.03199818576133823, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018360918604421385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.329033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619254504538784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0830920323446958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1177685368926427, "gear": 1, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.329033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.3490329, "x": 24.346850530940756, "y": 5.154040189647774, "z": null, "yaw": 3.1341841573264717, "pitch": null, "roll": null}, "v": 2.1184941257192142, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "acceleration": 0.0362291854437109, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018395654468475554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.3490329} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26218069223900736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0437542744082204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1184941257192142, "gear": 1, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.3490329} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 20.346850530940756, "y": 0.1540401896477741, "z": null, "yaw": 3.1341841573264717, "pitch": null, "roll": null}, "v": 2.1184941257192142, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "acceleration": 0.0362291854437109, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018395654468475554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.3690329} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26211939639831255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0437542744082204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119250265252954, "gear": 1, "accelerator_pedal_position": 0.26218069223900736, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.3690329} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 20.346850530940756, "y": 0.1540401896477741, "z": null, "yaw": 3.1341841573264717, "pitch": null, "roll": null}, "v": 2.1184941257192142, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "acceleration": 0.0362291854437109, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018395654468475554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.3890328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26211939639831255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0437542744082204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119997349929571, "gear": 1, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.3890328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 20.346850530940756, "y": 0.1540401896477741, "z": null, "yaw": 3.1341841573264717, "pitch": null, "roll": null}, "v": 2.1184941257192142, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "acceleration": 0.0362291854437109, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018395654468475554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.4090328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26211939639831255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0437542744082204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.120743054688127, "gear": 1, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.4090328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 20.346850530940756, "y": 0.1540401896477741, "z": null, "yaw": 3.1341841573264717, "pitch": null, "roll": null}, "v": 2.1184941257192142, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "acceleration": 0.0362291854437109, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018395654468475554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.4290328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26211939639831255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0437542744082204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121487381855101, "gear": 1, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.4290328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 20.346850530940756, "y": 0.1540401896477741, "z": null, "yaw": 3.1341841573264717, "pitch": null, "roll": null}, "v": 2.1184941257192142, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "acceleration": 0.0362291854437109, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018395654468475554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.4490328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26211939639831255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0437542744082204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1222303337539055, "gear": 1, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.4490328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.4590328, "x": 24.113615775453987, "y": 5.155666836068064, "z": null, "yaw": 3.135139327306398, "pitch": null, "roll": null}, "v": 2.1226012947029727, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "acceleration": 0.03706180019155736, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01843131850952793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.4690328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26113377960642004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8538458892015313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1229719127048883, "gear": 1, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.4690328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 20.113615775453987, "y": 0.15566683606806375, "z": null, "yaw": 3.135139327306398, "pitch": null, "roll": null}, "v": 2.1226012947029727, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "acceleration": 0.03706180019155736, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01843131850952793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.4890327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146076243851646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8538458892015313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1235889758865123, "gear": 1, "accelerator_pedal_position": 0.26113377960642004, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.4890327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 20.113615775453987, "y": 0.15566683606806375, "z": null, "yaw": 3.135139327306398, "pitch": null, "roll": null}, "v": 2.1226012947029727, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "acceleration": 0.03706180019155736, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01843131850952793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.5090327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146076243851646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8538458892015313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124245752370021, "gear": 1, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.5090327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 20.113615775453987, "y": 0.15566683606806375, "z": null, "yaw": 3.135139327306398, "pitch": null, "roll": null}, "v": 2.1226012947029727, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "acceleration": 0.03706180019155736, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01843131850952793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.5290327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146076243851646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8538458892015313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.125228641055481, "gear": 1, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.5290327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 20.113615775453987, "y": 0.15566683606806375, "z": null, "yaw": 3.135139327306398, "pitch": null, "roll": null}, "v": 2.1226012947029727, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "acceleration": 0.03706180019155736, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01843131850952793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.5490327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146076243851646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8538458892015313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1255556647096845, "gear": 1, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.5490327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.5690327, "x": 23.87995253967947, "y": 5.157073277870663, "z": null, "yaw": 3.1360944972863245, "pitch": null, "roll": null}, "v": 2.1262088047090026, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "acceleration": 0.032611686193056766, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0184626438300737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.5690327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628521951604697, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8870164870833079, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1262088047090026, "gear": 1, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.5690327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 19.87995253967947, "y": 0.15707327787066294, "z": null, "yaw": 3.1360944972863245, "pitch": null, "roll": null}, "v": 2.1262088047090026, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "acceleration": 0.032611686193056766, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0184626438300737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.5890326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624340547481938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8870164870833079, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127034585305876, "gear": 1, "accelerator_pedal_position": 0.2628521951604697, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.5890326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 19.87995253967947, "y": 0.15707327787066294, "z": null, "yaw": 3.1360944972863245, "pitch": null, "roll": null}, "v": 2.1262088047090026, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "acceleration": 0.032611686193056766, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0184626438300737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.6090326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624340547481938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8870164870833079, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1278065949468656, "gear": 1, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.6090326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 19.87995253967947, "y": 0.15707327787066294, "z": null, "yaw": 3.1360944972863245, "pitch": null, "roll": null}, "v": 2.1262088047090026, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "acceleration": 0.032611686193056766, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0184626438300737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.6290326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624340547481938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8870164870833079, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128577176224257, "gear": 1, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.6290326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 19.87995253967947, "y": 0.15707327787066294, "z": null, "yaw": 3.1360944972863245, "pitch": null, "roll": null}, "v": 2.1262088047090026, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "acceleration": 0.032611686193056766, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0184626438300737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.6490326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624340547481938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8870164870833079, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1293463315433843, "gear": 1, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.6490326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 19.87995253967947, "y": 0.15707327787066294, "z": null, "yaw": 3.1360944972863245, "pitch": null, "roll": null}, "v": 2.1262088047090026, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "acceleration": 0.032611686193056766, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0184626438300737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.6690326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624340547481938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8870164870833079, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.130114063306448, "gear": 1, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.6690326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.6790326, "x": 23.645855404118304, "y": 5.158258715999582, "z": null, "yaw": 3.137049667266251, "pitch": null, "roll": null}, "v": 2.1304973961042872, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "acceleration": 0.0382977808229254, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01849988322786403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.6890326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2635032258440831, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9248721600161183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1308803739125164, "gear": 1, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.6890326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 19.645855404118304, "y": 0.1582587159995823, "z": null, "yaw": 3.137049667266251, "pitch": null, "roll": null}, "v": 2.1304973961042872, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "acceleration": 0.0382977808229254, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01849988322786403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.7090325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631889587858489, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9248721600161183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1317788502489083, "gear": 1, "accelerator_pedal_position": 0.2635032258440831, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.7090325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 19.645855404118304, "y": 0.1582587159995823, "z": null, "yaw": 3.137049667266251, "pitch": null, "roll": null}, "v": 2.1304973961042872, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "acceleration": 0.0382977808229254, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01849988322786403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.7290325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631889587858489, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9248721600161183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.132636397634164, "gear": 1, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.7290325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 19.645855404118304, "y": 0.1582587159995823, "z": null, "yaw": 3.137049667266251, "pitch": null, "roll": null}, "v": 2.1304973961042872, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "acceleration": 0.0382977808229254, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01849988322786403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.7490325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631889587858489, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9248721600161183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1334923567469968, "gear": 1, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.7490325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 19.645855404118304, "y": 0.1582587159995823, "z": null, "yaw": 3.137049667266251, "pitch": null, "roll": null}, "v": 2.1304973961042872, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "acceleration": 0.0382977808229254, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01849988322786403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.7690325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631889587858489, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9248721600161183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134346730236131, "gear": 1, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.7690325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.7890325, "x": 23.411268119123843, "y": 5.159222556846911, "z": null, "yaw": 3.1380048372461773, "pitch": null, "roll": null}, "v": 2.135199520747014, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "acceleration": 0.042580246440222125, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018540713485142152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.7890325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641073181873912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9668029332828579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.135199520747014, "gear": 1, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.7890325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 19.411268119123843, "y": 0.15922255684691056, "z": null, "yaw": 3.1380048372461773, "pitch": null, "roll": null}, "v": 2.135199520747014, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "acceleration": 0.042580246440222125, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018540713485142152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.8090324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638421149314308, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9668029332828579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.136165472632049, "gear": 1, "accelerator_pedal_position": 0.2641073181873912, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.8090324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 19.411268119123843, "y": 0.15922255684691056, "z": null, "yaw": 3.1380048372461773, "pitch": null, "roll": null}, "v": 2.135199520747014, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "acceleration": 0.042580246440222125, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018540713485142152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.8290324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638421149314308, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9668029332828579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1370964990793775, "gear": 1, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.8290324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 19.411268119123843, "y": 0.15922255684691056, "z": null, "yaw": 3.1380048372461773, "pitch": null, "roll": null}, "v": 2.135199520747014, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "acceleration": 0.042580246440222125, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018540713485142152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.8490324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638421149314308, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9668029332828579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.138025799510337, "gear": 1, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.8490324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 19.411268119123843, "y": 0.15922255684691056, "z": null, "yaw": 3.1380048372461773, "pitch": null, "roll": null}, "v": 2.135199520747014, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "acceleration": 0.042580246440222125, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018540713485142152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.8690324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638421149314308, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9668029332828579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1389533767794844, "gear": 1, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.8690324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 19.411268119123843, "y": 0.15922255684691056, "z": null, "yaw": 3.1380048372461773, "pitch": null, "roll": null}, "v": 2.135199520747014, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "acceleration": 0.042580246440222125, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018540713485142152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.8890324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638421149314308, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9668029332828579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.139879233738004, "gear": 1, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.8890324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.8990324, "x": 23.176138281961148, "y": 5.159964031502003, "z": null, "yaw": 3.1389600072261037, "pitch": null, "roll": null}, "v": 2.1403415179908514, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "acceleration": 0.0461855242855459, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018585363316089114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.9090323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2642454943706318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9140687786096657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1408033732337066, "gear": 1, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.9090323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 19.176138281961148, "y": 0.15996403150200322, "z": null, "yaw": 3.1389600072261037, "pitch": null, "roll": null}, "v": 2.1403415179908514, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "acceleration": 0.0461855242855459, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018585363316089114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.9290323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641432856320963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9140687786096657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1417761971384786, "gear": 1, "accelerator_pedal_position": 0.2642454943706318, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.9290323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 19.176138281961148, "y": 0.15996403150200322, "z": null, "yaw": 3.1389600072261037, "pitch": null, "roll": null}, "v": 2.1403415179908514, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "acceleration": 0.0461855242855459, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018585363316089114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.9490323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641432856320963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9140687786096657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.142734445562605, "gear": 1, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.9490323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 19.176138281961148, "y": 0.15996403150200322, "z": null, "yaw": 3.1389600072261037, "pitch": null, "roll": null}, "v": 2.1403415179908514, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "acceleration": 0.0461855242855459, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018585363316089114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.9690323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641432856320963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9140687786096657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1436909153475274, "gear": 1, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.9690323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 19.176138281961148, "y": 0.15996403150200322, "z": null, "yaw": 3.1389600072261037, "pitch": null, "roll": null}, "v": 2.1403415179908514, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "acceleration": 0.0461855242855459, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018585363316089114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.9890323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641432856320963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9140687786096657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1446456094288777, "gear": 1, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.9890323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.0090322, "x": 22.94043844743375, "y": 5.16048216752556, "z": null, "yaw": 3.13991517720603, "pitch": null, "roll": null}, "v": 2.1455985307388743, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "acceleration": 0.04757967811257002, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01863101186846174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.0090322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2644488793956469, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8645341051525897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1455985307388743, "gear": 1, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.0090322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 18.94043844743375, "y": 0.16048216752555966, "z": null, "yaw": 3.13991517720603, "pitch": null, "roll": null}, "v": 2.1455985307388743, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "acceleration": 0.04757967811257002, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01863101186846174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.0290322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2643777894505339, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8645341051525897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1465878636790876, "gear": 1, "accelerator_pedal_position": 0.2644488793956469, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.0290322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 18.94043844743375, "y": 0.16048216752555966, "z": null, "yaw": 3.13991517720603, "pitch": null, "roll": null}, "v": 2.1455985307388743, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "acceleration": 0.04757967811257002, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01863101186846174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.0490322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2643777894505339, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8645341051525897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1475664766489473, "gear": 1, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.0490322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 18.94043844743375, "y": 0.16048216752555966, "z": null, "yaw": 3.13991517720603, "pitch": null, "roll": null}, "v": 2.1455985307388743, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "acceleration": 0.04757967811257002, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01863101186846174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.0690322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2643777894505339, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8645341051525897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1485432712925148, "gear": 1, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.0690322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 18.94043844743375, "y": 0.16048216752555966, "z": null, "yaw": 3.13991517720603, "pitch": null, "roll": null}, "v": 2.1455985307388743, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "acceleration": 0.04757967811257002, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01863101186846174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.0890322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2643777894505339, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8645341051525897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.149518250606884, "gear": 1, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.0890322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 18.94043844743375, "y": 0.16048216752555966, "z": null, "yaw": 3.13991517720603, "pitch": null, "roll": null}, "v": 2.1455985307388743, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "acceleration": 0.04757967811257002, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01863101186846174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.1090322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2643777894505339, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8645341051525897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.150491417585706, "gear": 1, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.1090322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.1190321, "x": 22.70415296106543, "y": 5.160775896657828, "z": null, "yaw": 3.1408703471859565, "pitch": null, "roll": null}, "v": 2.1509773223838606, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "acceleration": 0.048545283532547445, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018677717871257712, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.1290321} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2648019194091415, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7911239654259389, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.151462775219186, "gear": 1, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.1290321} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 18.70415296106543, "y": 0.1607758966578281, "z": null, "yaw": 3.1408703471859565, "pitch": null, "roll": null}, "v": 2.1509773223838606, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "acceleration": 0.048545283532547445, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018677717871257712, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.149032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26469438089883174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7911239654259389, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1524853180759576, "gear": 1, "accelerator_pedal_position": 0.2648019194091415, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.149032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 18.70415296106543, "y": 0.1607758966578281, "z": null, "yaw": 3.1408703471859565, "pitch": null, "roll": null}, "v": 2.1509773223838606, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "acceleration": 0.048545283532547445, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018677717871257712, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.169032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26469438089883174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7911239654259389, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1534925229172415, "gear": 1, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.169032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 18.70415296106543, "y": 0.1607758966578281, "z": null, "yaw": 3.1408703471859565, "pitch": null, "roll": null}, "v": 2.1509773223838606, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "acceleration": 0.048545283532547445, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018677717871257712, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.189032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26469438089883174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7911239654259389, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.154497853924285, "gear": 1, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.189032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 18.70415296106543, "y": 0.1607758966578281, "z": null, "yaw": 3.1408703471859565, "pitch": null, "roll": null}, "v": 2.1509773223838606, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "acceleration": 0.048545283532547445, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018677717871257712, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.209032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26469438089883174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7911239654259389, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.155501314179139, "gear": 1, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.209032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.229032, "x": 22.467269198514625, "y": 5.160844103833324, "z": null, "yaw": 3.141825517165883, "pitch": null, "roll": null}, "v": 2.1565029067603723, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "acceleration": 0.050009687411020354, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018725698528693904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.229032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26570599365676606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8166205210337456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1565029067603723, "gear": 1, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.229032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 18.467269198514625, "y": 0.16084410383332415, "z": null, "yaw": 3.141825517165883, "pitch": null, "roll": null}, "v": 2.1565029067603723, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "acceleration": 0.050009687411020354, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018725698528693904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.249032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654155791131704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8166205210337456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.15762902744887, "gear": 1, "accelerator_pedal_position": 0.26570599365676606, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.249032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 18.467269198514625, "y": 0.16084410383332415, "z": null, "yaw": 3.141825517165883, "pitch": null, "roll": null}, "v": 2.1565029067603723, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "acceleration": 0.050009687411020354, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018725698528693904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.269032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654155791131704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8166205210337456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1587167663124394, "gear": 1, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.269032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 18.467269198514625, "y": 0.16084410383332415, "z": null, "yaw": 3.141825517165883, "pitch": null, "roll": null}, "v": 2.1565029067603723, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "acceleration": 0.050009687411020354, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018725698528693904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.289032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654155791131704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8166205210337456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.159802479251675, "gear": 1, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.289032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 18.467269198514625, "y": 0.16084410383332415, "z": null, "yaw": 3.141825517165883, "pitch": null, "roll": null}, "v": 2.1565029067603723, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "acceleration": 0.050009687411020354, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018725698528693904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.309032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654155791131704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8166205210337456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1608861695685904, "gear": 1, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.309032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 18.467269198514625, "y": 0.16084410383332415, "z": null, "yaw": 3.141825517165883, "pitch": null, "roll": null}, "v": 2.1565029067603723, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "acceleration": 0.050009687411020354, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018725698528693904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.329032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654155791131704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8166205210337456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.161967840561683, "gear": 1, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.329032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.339032, "x": 22.22975149754553, "y": 5.160685619889306, "z": null, "yaw": 3.1427806871458093, "pitch": null, "roll": null}, "v": 2.1625079198416133, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "acceleration": 0.05395756843145705, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01877784223982347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.349032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26605519167123837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7381951040661748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.163047495525928, "gear": 1, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.349032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 18.22975149754553, "y": 0.16068561988930607, "z": null, "yaw": 3.1427806871458093, "pitch": null, "roll": null}, "v": 2.1625079198416133, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "acceleration": 0.05395756843145705, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01877784223982347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.369032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658832930250956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7381951040661748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.164205052036266, "gear": 1, "accelerator_pedal_position": 0.26605519167123837, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.369032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 18.22975149754553, "y": 0.16068561988930607, "z": null, "yaw": 3.1427806871458093, "pitch": null, "roll": null}, "v": 2.1625079198416133, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "acceleration": 0.05395756843145705, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01877784223982347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.389032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658832930250956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7381951040661748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.165338972748057, "gear": 1, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.389032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 18.22975149754553, "y": 0.16068561988930607, "z": null, "yaw": 3.1427806871458093, "pitch": null, "roll": null}, "v": 2.1625079198416133, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "acceleration": 0.05395756843145705, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01877784223982347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.4090319} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658832930250956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7381951040661748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.166470778525779, "gear": 1, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.4090319} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 18.22975149754553, "y": 0.16068561988930607, "z": null, "yaw": 3.1427806871458093, "pitch": null, "roll": null}, "v": 2.1625079198416133, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "acceleration": 0.05395756843145705, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01877784223982347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.4290318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658832930250956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7381951040661748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1676004728019493, "gear": 1, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.4290318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.4490318, "x": 21.99156506930546, "y": 5.160299178941491, "z": null, "yaw": 3.1437358571257357, "pitch": null, "roll": null}, "v": 2.168728059005549, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "acceleration": 0.05630036451739029, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01883185396891748, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.4490318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26679685134884246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7623411921056686, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.168728059005549, "gear": 1, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.4490318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 17.99156506930546, "y": 0.16029917894149115, "z": null, "yaw": 3.1437358571257357, "pitch": null, "roll": null}, "v": 2.168728059005549, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "acceleration": 0.05630036451739029, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01883185396891748, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.4690318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2665403849976991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7623411921056686, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.169967682031287, "gear": 1, "accelerator_pedal_position": 0.26679685134884246, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.4690318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 17.99156506930546, "y": 0.16029917894149115, "z": null, "yaw": 3.1437358571257357, "pitch": null, "roll": null}, "v": 2.168728059005549, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "acceleration": 0.05630036451739029, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01883185396891748, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.4890318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2665403849976991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7623411921056686, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.171172947371396, "gear": 1, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.4890318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 17.99156506930546, "y": 0.16029917894149115, "z": null, "yaw": 3.1437358571257357, "pitch": null, "roll": null}, "v": 2.168728059005549, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "acceleration": 0.05630036451739029, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01883185396891748, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.5090318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2665403849976991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7623411921056686, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.172375961907511, "gear": 1, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.5090318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 17.99156506930546, "y": 0.16029917894149115, "z": null, "yaw": 3.1437358571257357, "pitch": null, "roll": null}, "v": 2.168728059005549, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "acceleration": 0.05630036451739029, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01883185396891748, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.5290318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2665403849976991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7623411921056686, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1735767292643278, "gear": 1, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.5290318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 17.99156506930546, "y": 0.16029917894149115, "z": null, "yaw": 3.1437358571257357, "pitch": null, "roll": null}, "v": 2.168728059005549, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "acceleration": 0.05630036451739029, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01883185396891748, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.5490317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2665403849976991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7623411921056686, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1747752530630127, "gear": 1, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.5490317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.5590317, "x": 21.752671441705576, "y": 5.1596834022513764, "z": null, "yaw": 3.144691027105662, "pitch": null, "roll": null}, "v": 2.175373674758704, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "acceleration": 0.059786216249352264, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018889560265876786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.5690317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2670467046092279, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6487304172504287, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1759715369211974, "gear": 1, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.5690317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 17.752671441705576, "y": 0.15968340225137645, "z": null, "yaw": 3.144691027105662, "pitch": null, "roll": null}, "v": 2.175373674758704, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "acceleration": 0.059786216249352264, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018889560265876786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.5890317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2669195283020823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6487304172504287, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.177228844806332, "gear": 1, "accelerator_pedal_position": 0.2670467046092279, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.5890317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 17.752671441705576, "y": 0.15968340225137645, "z": null, "yaw": 3.144691027105662, "pitch": null, "roll": null}, "v": 2.175373674758704, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "acceleration": 0.059786216249352264, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018889560265876786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.6090317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2669195283020823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6487304172504287, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.178467912061017, "gear": 1, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.6090317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 17.752671441705576, "y": 0.15968340225137645, "z": null, "yaw": 3.144691027105662, "pitch": null, "roll": null}, "v": 2.175373674758704, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "acceleration": 0.059786216249352264, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018889560265876786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.6290317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2669195283020823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6487304172504287, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1797046617794336, "gear": 1, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.6290317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 17.752671441705576, "y": 0.15968340225137645, "z": null, "yaw": 3.144691027105662, "pitch": null, "roll": null}, "v": 2.175373674758704, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "acceleration": 0.059786216249352264, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018889560265876786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.6490316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2669195283020823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6487304172504287, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.180939097684739, "gear": 1, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.6490316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.6690316, "x": 21.513041955351085, "y": 5.158836838416539, "z": null, "yaw": 3.1456461970855885, "pitch": null, "roll": null}, "v": 2.1821712234965576, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "acceleration": 0.06151977822662191, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018948585852162855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.6690316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676572617020828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6639043584005557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1821712234965576, "gear": 1, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.6690316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 17.513041955351085, "y": 0.15883683841653884, "z": null, "yaw": 3.1456461970855885, "pitch": null, "roll": null}, "v": 2.1821712234965576, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "acceleration": 0.06151977822662191, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018948585852162855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.6890316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674585240680364, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6639043584005557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.183493216422661, "gear": 1, "accelerator_pedal_position": 0.2676572617020828, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.6890316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 17.513041955351085, "y": 0.15883683841653884, "z": null, "yaw": 3.1456461970855885, "pitch": null, "roll": null}, "v": 2.1821712234965576, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "acceleration": 0.06151977822662191, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018948585852162855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.7090316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674585240680364, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6639043584005557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1847879034976083, "gear": 1, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.7090316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 17.513041955351085, "y": 0.15883683841653884, "z": null, "yaw": 3.1456461970855885, "pitch": null, "roll": null}, "v": 2.1821712234965576, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "acceleration": 0.06151977822662191, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018948585852162855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.7290316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674585240680364, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6639043584005557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.186080165742952, "gear": 1, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.7290316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 17.513041955351085, "y": 0.15883683841653884, "z": null, "yaw": 3.1456461970855885, "pitch": null, "roll": null}, "v": 2.1821712234965576, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "acceleration": 0.06151977822662191, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018948585852162855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.7490315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674585240680364, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6639043584005557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1873700070325097, "gear": 1, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.7490315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 17.513041955351085, "y": 0.15883683841653884, "z": null, "yaw": 3.1456461970855885, "pitch": null, "roll": null}, "v": 2.1821712234965576, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "acceleration": 0.06151977822662191, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018948585852162855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.7690315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674585240680364, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6639043584005557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1886574312365954, "gear": 1, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.7690315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.7790315, "x": 21.27264731455648, "y": 5.157757947471164, "z": null, "yaw": 3.146601367065515, "pitch": null, "roll": null}, "v": 2.1893002381400986, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "acceleration": 0.06422040819101948, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019010489677380574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.7890315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26808179394339765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6803551466078215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1899424422220086, "gear": 1, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.7890315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 17.27264731455648, "y": 0.1577579474711639, "z": null, "yaw": 3.146601367065515, "pitch": null, "roll": null}, "v": 2.1893002381400986, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "acceleration": 0.06422040819101948, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019010489677380574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.8090315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679204266801874, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6803551466078215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1913029160425492, "gear": 1, "accelerator_pedal_position": 0.26808179394339765, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.8090315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 17.27264731455648, "y": 0.1577579474711639, "z": null, "yaw": 3.146601367065515, "pitch": null, "roll": null}, "v": 2.1893002381400986, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "acceleration": 0.06422040819101948, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019010489677380574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.8290315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679204266801874, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6803551466078215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.192640676844084, "gear": 1, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.8290315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 17.27264731455648, "y": 0.1577579474711639, "z": null, "yaw": 3.146601367065515, "pitch": null, "roll": null}, "v": 2.1893002381400986, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "acceleration": 0.06422040819101948, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019010489677380574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.8490314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679204266801874, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6803551466078215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.19397592795054, "gear": 1, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.8490314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 17.27264731455648, "y": 0.1577579474711639, "z": null, "yaw": 3.146601367065515, "pitch": null, "roll": null}, "v": 2.1893002381400986, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "acceleration": 0.06422040819101948, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019010489677380574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.8690314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679204266801874, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6803551466078215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1953086733573866, "gear": 1, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.8690314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.8890314, "x": 21.03146098340464, "y": 5.156445121962606, "z": null, "yaw": 3.1475565370454412, "pitch": null, "roll": null}, "v": 2.1966389170566076, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "acceleration": 0.06641849557906448, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019074214093683758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.8890314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26872573538268174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5893262407032084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1966389170566076, "gear": 1, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.8890314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.03146098340464, "y": 0.15644512196260596, "z": null, "yaw": 3.1475565370454412, "pitch": null, "roll": null}, "v": 2.1966389170566076, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "acceleration": 0.06641849557906448, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019074214093683758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.9090314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685085164676274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5893262407032084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.198067279339513, "gear": 1, "accelerator_pedal_position": 0.26872573538268174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.9090314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.03146098340464, "y": 0.15644512196260596, "z": null, "yaw": 3.1475565370454412, "pitch": null, "roll": null}, "v": 2.1966389170566076, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "acceleration": 0.06641849557906448, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019074214093683758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.9290314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685085164676274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5893262407032084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1994658192644647, "gear": 1, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.9290314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.03146098340464, "y": 0.15644512196260596, "z": null, "yaw": 3.1475565370454412, "pitch": null, "roll": null}, "v": 2.1966389170566076, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "acceleration": 0.06641849557906448, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019074214093683758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.9490314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685085164676274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5893262407032084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2008617316641557, "gear": 1, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.9490314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.03146098340464, "y": 0.15644512196260596, "z": null, "yaw": 3.1475565370454412, "pitch": null, "roll": null}, "v": 2.1966389170566076, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "acceleration": 0.06641849557906448, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019074214093683758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.9690313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685085164676274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5893262407032084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2022550206960196, "gear": 1, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.9690313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.03146098340464, "y": 0.15644512196260596, "z": null, "yaw": 3.1475565370454412, "pitch": null, "roll": null}, "v": 2.1966389170566076, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "acceleration": 0.06641849557906448, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019074214093683758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.9890313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685085164676274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5893262407032084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.203645690514072, "gear": 1, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.9890313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.9990313, "x": 20.78944866383005, "y": 5.154896626685437, "z": null, "yaw": 3.1485117070253676, "pitch": null, "roll": null}, "v": 2.2043400445151096, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "acceleration": 0.06937007537838702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01914108578241039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.0090313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26915562439350593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6041325204479405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2050337452688935, "gear": 1, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.0090313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 16.78944866383005, "y": 0.1548966266854368, "z": null, "yaw": 3.1485117070253676, "pitch": null, "roll": null}, "v": 2.2043400445151096, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "acceleration": 0.06937007537838702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01914108578241039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.0290313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689896021264251, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6041325204479405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2065000395342804, "gear": 1, "accelerator_pedal_position": 0.26915562439350593, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.0290313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 16.78944866383005, "y": 0.1548966266854368, "z": null, "yaw": 3.1485117070253676, "pitch": null, "roll": null}, "v": 2.2043400445151096, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "acceleration": 0.06937007537838702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01914108578241039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.0490313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689896021264251, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6041325204479405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.207942831853585, "gear": 1, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.0490313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 16.78944866383005, "y": 0.1548966266854368, "z": null, "yaw": 3.1485117070253676, "pitch": null, "roll": null}, "v": 2.2043400445151096, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "acceleration": 0.06937007537838702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01914108578241039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.0690312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689896021264251, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6041325204479405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2093829086266177, "gear": 1, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.0690312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 16.78944866383005, "y": 0.1548966266854368, "z": null, "yaw": 3.1485117070253676, "pitch": null, "roll": null}, "v": 2.2043400445151096, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "acceleration": 0.06937007537838702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01914108578241039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.0890312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689896021264251, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6041325204479405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2108202741352954, "gear": 1, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.0890312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.1090312, "x": 20.546582120143828, "y": 5.15311067407925, "z": null, "yaw": 3.149466877005294, "pitch": null, "roll": null}, "v": 2.212254932658156, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "acceleration": 0.07163154778654551, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019209813632853064, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.1090312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26949888359280194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5540327153281539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.212254932658156, "gear": 1, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.1090312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 16.546582120143828, "y": 0.15311067407925005, "z": null, "yaw": 3.149466877005294, "pitch": null, "roll": null}, "v": 2.212254932658156, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "acceleration": 0.07163154778654551, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019209813632853064, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.1290312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26937699870261156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5540327153281539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.213750518650682, "gear": 1, "accelerator_pedal_position": 0.26949888359280194, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.1290312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 16.546582120143828, "y": 0.15311067407925005, "z": null, "yaw": 3.149466877005294, "pitch": null, "roll": null}, "v": 2.212254932658156, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "acceleration": 0.07163154778654551, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019209813632853064, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.1490312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26937699870261156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5540327153281539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2152280578398695, "gear": 1, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.1490312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 16.546582120143828, "y": 0.15311067407925005, "z": null, "yaw": 3.149466877005294, "pitch": null, "roll": null}, "v": 2.212254932658156, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "acceleration": 0.07163154778654551, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019209813632853064, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.1690311} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26937699870261156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5540327153281539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.216702811787597, "gear": 1, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.1690311} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 16.546582120143828, "y": 0.15311067407925005, "z": null, "yaw": 3.149466877005294, "pitch": null, "roll": null}, "v": 2.212254932658156, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "acceleration": 0.07163154778654551, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019209813632853064, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.1890311} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26937699870261156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5540327153281539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2181747848746456, "gear": 1, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.1890311} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 16.546582120143828, "y": 0.15311067407925005, "z": null, "yaw": 3.149466877005294, "pitch": null, "roll": null}, "v": 2.212254932658156, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "acceleration": 0.07163154778654551, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019209813632853064, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.209031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26937699870261156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5540327153281539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.219643981478455, "gear": 1, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.209031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.219031, "x": 20.30283491841427, "y": 5.151085409751915, "z": null, "yaw": 3.1504220469852204, "pitch": null, "roll": null}, "v": 2.2203775399661776, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "acceleration": 0.07328660069315074, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01928034518430155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.229031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2702258967191302, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47040774893818027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2211104059731093, "gear": 1, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.229031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 16.30283491841427, "y": 0.1510854097519152, "z": null, "yaw": 3.1504220469852204, "pitch": null, "roll": null}, "v": 2.2203775399661776, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "acceleration": 0.07328660069315074, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01928034518430155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.249031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26999892472488174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47040774893818027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.222680124876572, "gear": 1, "accelerator_pedal_position": 0.2702258967191302, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.249031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 16.30283491841427, "y": 0.1510854097519152, "z": null, "yaw": 3.1504220469852204, "pitch": null, "roll": null}, "v": 2.2203775399661776, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "acceleration": 0.07328660069315074, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01928034518430155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.269031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26999892472488174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47040774893818027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2242185220165096, "gear": 1, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.269031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 16.30283491841427, "y": 0.1510854097519152, "z": null, "yaw": 3.1504220469852204, "pitch": null, "roll": null}, "v": 2.2203775399661776, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "acceleration": 0.07328660069315074, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01928034518430155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.289031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26999892472488174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47040774893818027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.225754013676669, "gear": 1, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.289031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 16.30283491841427, "y": 0.1510854097519152, "z": null, "yaw": 3.1504220469852204, "pitch": null, "roll": null}, "v": 2.2203775399661776, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "acceleration": 0.07328660069315074, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01928034518430155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.309031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26999892472488174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47040774893818027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2272866044018103, "gear": 1, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.309031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.329031, "x": 20.05818210946566, "y": 5.14881891506748, "z": null, "yaw": 3.151377216965147, "pitch": null, "roll": null}, "v": 2.2288162987334488, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "acceleration": 0.07637624365883966, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019353621993777166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.329031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27193637668606435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40423612595068786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2288162987334488, "gear": 1, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.329031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.05818210946566, "y": 0.1488189150674799, "z": null, "yaw": 3.151377216965147, "pitch": null, "roll": null}, "v": 2.2288162987334488, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "acceleration": 0.07637624365883966, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019353621993777166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.349031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2713707923110438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40423612595068786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.230585168161845, "gear": 1, "accelerator_pedal_position": 0.27193637668606435, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.349031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.05818210946566, "y": 0.1488189150674799, "z": null, "yaw": 3.151377216965147, "pitch": null, "roll": null}, "v": 2.2288162987334488, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "acceleration": 0.07637624365883966, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019353621993777166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.369031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2713707923110438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40423612595068786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2322800277749257, "gear": 1, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.369031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.05818210946566, "y": 0.1488189150674799, "z": null, "yaw": 3.151377216965147, "pitch": null, "roll": null}, "v": 2.2288162987334488, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "acceleration": 0.07637624365883966, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019353621993777166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.389031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2713707923110438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40423612595068786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2339716809732257, "gear": 1, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.389031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.05818210946566, "y": 0.1488189150674799, "z": null, "yaw": 3.151377216965147, "pitch": null, "roll": null}, "v": 2.2288162987334488, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "acceleration": 0.07637624365883966, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019353621993777166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.409031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2713707923110438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40423612595068786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2356601326786567, "gear": 1, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.409031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.05818210946566, "y": 0.1488189150674799, "z": null, "yaw": 3.151377216965147, "pitch": null, "roll": null}, "v": 2.2288162987334488, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "acceleration": 0.07637624365883966, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019353621993777166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.429031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2713707923110438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40423612595068786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.237345387810309, "gear": 1, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.429031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.439031, "x": 19.81255255905506, "y": 5.146308724034832, "z": null, "yaw": 3.1523323869450732, "pitch": null, "roll": null}, "v": 2.2381868181974087, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "acceleration": 0.08406330870262668, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01943498962003415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.4490309} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27190873339566546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4065710547313976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.239027451284435, "gear": 1, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.4490309} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 15.81255255905506, "y": 0.14630872403483242, "z": null, "yaw": 3.1523323869450732, "pitch": null, "roll": null}, "v": 2.2381868181974087, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "acceleration": 0.08406330870262668, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01943498962003415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.4690309} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27178498209406976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4065710547313976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2407735387777734, "gear": 1, "accelerator_pedal_position": 0.27190873339566546, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.4690309} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 15.81255255905506, "y": 0.14630872403483242, "z": null, "yaw": 3.1523323869450732, "pitch": null, "roll": null}, "v": 2.2381868181974087, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "acceleration": 0.08406330870262668, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01943498962003415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.4890308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27178498209406976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4065710547313976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.242500855445528, "gear": 1, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.4890308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 15.81255255905506, "y": 0.14630872403483242, "z": null, "yaw": 3.1523323869450732, "pitch": null, "roll": null}, "v": 2.2381868181974087, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "acceleration": 0.08406330870262668, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01943498962003415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.5090308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27178498209406976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4065710547313976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2442248972451777, "gear": 1, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.5090308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 15.81255255905506, "y": 0.14630872403483242, "z": null, "yaw": 3.1523323869450732, "pitch": null, "roll": null}, "v": 2.2381868181974087, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "acceleration": 0.08406330870262668, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01943498962003415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.5290308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27178498209406976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4065710547313976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2459456691972735, "gear": 1, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.5290308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.5490308, "x": 19.56589345298601, "y": 5.143552382309852, "z": null, "yaw": 3.1532875569249996, "pitch": null, "roll": null}, "v": 2.247663176319603, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "acceleration": 0.08575308173012447, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019517276281828047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.5490308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27232010546141316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4081995702687707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.247663176319603, "gear": 1, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.5490308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 15.56589345298601, "y": 0.1435523823098519, "z": null, "yaw": 3.1532875569249996, "pitch": null, "roll": null}, "v": 2.247663176319603, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "acceleration": 0.08575308173012447, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019517276281828047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.5690308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27219782498476575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4081995702687707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.249444282284924, "gear": 1, "accelerator_pedal_position": 0.27232010546141316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.5690308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 15.56589345298601, "y": 0.1435523823098519, "z": null, "yaw": 3.1532875569249996, "pitch": null, "roll": null}, "v": 2.247663176319603, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "acceleration": 0.08575308173012447, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019517276281828047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.5890307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27219782498476575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4081995702687707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.251206728670309, "gear": 1, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.5890307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 15.56589345298601, "y": 0.1435523823098519, "z": null, "yaw": 3.1532875569249996, "pitch": null, "roll": null}, "v": 2.247663176319603, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "acceleration": 0.08575308173012447, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019517276281828047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.6090307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27219782498476575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4081995702687707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.252965827458734, "gear": 1, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.6090307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 15.56589345298601, "y": 0.1435523823098519, "z": null, "yaw": 3.1532875569249996, "pitch": null, "roll": null}, "v": 2.247663176319603, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "acceleration": 0.08575308173012447, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019517276281828047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.6290307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27219782498476575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4081995702687707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2547215837714534, "gear": 1, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.6290307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 15.56589345298601, "y": 0.1435523823098519, "z": null, "yaw": 3.1532875569249996, "pitch": null, "roll": null}, "v": 2.247663176319603, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "acceleration": 0.08575308173012447, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019517276281828047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.6490307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27219782498476575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4081995702687707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.256474002727041, "gear": 1, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.6490307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.6590307, "x": 19.318182838286564, "y": 5.140547651095889, "z": null, "yaw": 3.154242726904926, "pitch": null, "roll": null}, "v": 2.2573489622947274, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "acceleration": 0.0874127146643186, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0196013814817863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.6690307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726534521957802, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40953957351731873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2582230894413704, "gear": 1, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.6690307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 15.318182838286564, "y": 0.14054765109588896, "z": null, "yaw": 3.154242726904926, "pitch": null, "roll": null}, "v": 2.2573489622947274, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "acceleration": 0.0874127146643186, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0196013814817863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.6890306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27255710038579783, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40953957351731873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2600257753242126, "gear": 1, "accelerator_pedal_position": 0.2726534521957802, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.6890306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 15.318182838286564, "y": 0.14054765109588896, "z": null, "yaw": 3.154242726904926, "pitch": null, "roll": null}, "v": 2.2573489622947274, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "acceleration": 0.0874127146643186, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0196013814817863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.7090306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27255710038579783, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40953957351731873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.261812992590956, "gear": 1, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.7090306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 15.318182838286564, "y": 0.14054765109588896, "z": null, "yaw": 3.154242726904926, "pitch": null, "roll": null}, "v": 2.2573489622947274, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "acceleration": 0.0874127146643186, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0196013814817863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.7290306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27255710038579783, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40953957351731873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2635968076401976, "gear": 1, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.7290306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 15.318182838286564, "y": 0.14054765109588896, "z": null, "yaw": 3.154242726904926, "pitch": null, "roll": null}, "v": 2.2573489622947274, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "acceleration": 0.0874127146643186, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0196013814817863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.7490306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27255710038579783, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40953957351731873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2653772256763403, "gear": 1, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.7490306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.7690306, "x": 19.069405260810598, "y": 5.137292314136363, "z": null, "yaw": 3.1551978968848524, "pitch": null, "roll": null}, "v": 2.267154251901143, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "acceleration": 0.08872428079704492, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019686524375209107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.7690306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2746436588723285, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35116747545371174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267154251901143, "gear": 1, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.7690306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.069405260810598, "y": 0.13729231413636267, "z": null, "yaw": 3.1551978968848524, "pitch": null, "roll": null}, "v": 2.267154251901143, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "acceleration": 0.08872428079704492, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019686524375209107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.7890306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2740383042045724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35116747545371174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2691885869628465, "gear": 1, "accelerator_pedal_position": 0.2746436588723285, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.7890306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.069405260810598, "y": 0.13729231413636267, "z": null, "yaw": 3.1551978968848524, "pitch": null, "roll": null}, "v": 2.267154251901143, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "acceleration": 0.08872428079704492, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019686524375209107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.8090305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2740383042045724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35116747545371174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2711434102002372, "gear": 1, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.8090305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.069405260810598, "y": 0.13729231413636267, "z": null, "yaw": 3.1551978968848524, "pitch": null, "roll": null}, "v": 2.267154251901143, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "acceleration": 0.08872428079704492, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019686524375209107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.8290305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2740383042045724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35116747545371174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.273094504902745, "gear": 1, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.8290305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.069405260810598, "y": 0.13729231413636267, "z": null, "yaw": 3.1551978968848524, "pitch": null, "roll": null}, "v": 2.267154251901143, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "acceleration": 0.08872428079704492, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019686524375209107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.8490305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2740383042045724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35116747545371174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275041876660014, "gear": 1, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.8490305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.069405260810598, "y": 0.13729231413636267, "z": null, "yaw": 3.1551978968848524, "pitch": null, "roll": null}, "v": 2.267154251901143, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "acceleration": 0.08872428079704492, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019686524375209107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.8690305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2740383042045724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35116747545371174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276985531059734, "gear": 1, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.8690305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.8790305, "x": 18.81949841473894, "y": 5.133783444908925, "z": null, "yaw": 3.156153066864779, "pitch": null, "roll": null}, "v": 2.277955965996124, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "acceleration": 0.09695076914859801, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01978031958462045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.8890305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27498914474301156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3173501896715621, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27892547368761, "gear": 1, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.8890305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 14.819498414738941, "y": 0.13378344490892502, "z": null, "yaw": 3.156153066864779, "pitch": null, "roll": null}, "v": 2.277955965996124, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "acceleration": 0.09695076914859801, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01978031958462045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.9090304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27474355868951994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3173501896715621, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2809805083828225, "gear": 1, "accelerator_pedal_position": 0.27498914474301156, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.9090304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 14.819498414738941, "y": 0.13378344490892502, "z": null, "yaw": 3.156153066864779, "pitch": null, "roll": null}, "v": 2.277955965996124, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "acceleration": 0.09695076914859801, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01978031958462045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.9290304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27474355868951994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3173501896715621, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283000931769978, "gear": 1, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.9290304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 14.819498414738941, "y": 0.13378344490892502, "z": null, "yaw": 3.156153066864779, "pitch": null, "roll": null}, "v": 2.277955965996124, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "acceleration": 0.09695076914859801, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01978031958462045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.9490304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27474355868951994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3173501896715621, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2850174919392283, "gear": 1, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.9490304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 14.819498414738941, "y": 0.13378344490892502, "z": null, "yaw": 3.156153066864779, "pitch": null, "roll": null}, "v": 2.277955965996124, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "acceleration": 0.09695076914859801, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01978031958462045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.9690304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27474355868951994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3173501896715621, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2870301946515403, "gear": 1, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.9690304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.9890304, "x": 18.56839741302652, "y": 5.130017911779184, "z": null, "yaw": 3.157108236844705, "pitch": null, "roll": null}, "v": 2.289039045666189, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "acceleration": 0.10029829200034635, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01987655799358365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.9890304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27707780457979625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2580850732572564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.289039045666189, "gear": 1, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.9890304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 14.56839741302652, "y": 0.1300179117791842, "z": null, "yaw": 3.157108236844705, "pitch": null, "roll": null}, "v": 2.289039045666189, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "acceleration": 0.10029829200034635, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01987655799358365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.0090303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2764013681795373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2580850732572564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2913356917106826, "gear": 1, "accelerator_pedal_position": 0.27707780457979625, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.0090303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 14.56839741302652, "y": 0.1300179117791842, "z": null, "yaw": 3.157108236844705, "pitch": null, "roll": null}, "v": 2.289039045666189, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "acceleration": 0.10029829200034635, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01987655799358365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.0290303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2764013681795373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2580850732572564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2935434247628783, "gear": 1, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.0290303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 14.56839741302652, "y": 0.1300179117791842, "z": null, "yaw": 3.157108236844705, "pitch": null, "roll": null}, "v": 2.289039045666189, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "acceleration": 0.10029829200034635, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01987655799358365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.0490303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2764013681795373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2580850732572564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2957469271857227, "gear": 1, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.0490303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 14.56839741302652, "y": 0.1300179117791842, "z": null, "yaw": 3.157108236844705, "pitch": null, "roll": null}, "v": 2.289039045666189, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "acceleration": 0.10029829200034635, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01987655799358365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.0690303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2764013681795373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2580850732572564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.297946205145038, "gear": 1, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.0690303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 14.56839741302652, "y": 0.1300179117791842, "z": null, "yaw": 3.157108236844705, "pitch": null, "roll": null}, "v": 2.289039045666189, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "acceleration": 0.10029829200034635, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01987655799358365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.0890303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2764013681795373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2580850732572564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3001412648059874, "gear": 1, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.0890303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.0990303, "x": 18.316020353051027, "y": 5.12599211326505, "z": null, "yaw": 3.1580634068246316, "pitch": null, "roll": null}, "v": 2.301237214700999, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "acceleration": 0.10948976320380999, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019982479128784456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.1090302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2782450938488509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20704877482909256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3023321123330374, "gear": 1, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.1090302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 14.316020353051027, "y": 0.1259921132650499, "z": null, "yaw": 3.1580634068246316, "pitch": null, "roll": null}, "v": 2.301237214700999, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "acceleration": 0.10948976320380999, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019982479128784456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.1290302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27772742114323495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20704877482909256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.304749108894752, "gear": 1, "accelerator_pedal_position": 0.2782450938488509, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.1290302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 14.316020353051027, "y": 0.1259921132650499, "z": null, "yaw": 3.1580634068246316, "pitch": null, "roll": null}, "v": 2.301237214700999, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "acceleration": 0.10948976320380999, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019982479128784456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.1490302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27772742114323495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20704877482909256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3070967850580515, "gear": 1, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.1490302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 14.316020353051027, "y": 0.1259921132650499, "z": null, "yaw": 3.1580634068246316, "pitch": null, "roll": null}, "v": 2.301237214700999, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "acceleration": 0.10948976320380999, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019982479128784456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.1690302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27772742114323495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20704877482909256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3094399497396503, "gear": 1, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.1690302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 14.316020353051027, "y": 0.1259921132650499, "z": null, "yaw": 3.1580634068246316, "pitch": null, "roll": null}, "v": 2.301237214700999, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "acceleration": 0.10948976320380999, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019982479128784456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.1890302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27772742114323495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20704877482909256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3117786094140578, "gear": 1, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.1890302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.2090302, "x": 18.062277390625983, "y": 5.121702087506923, "z": null, "yaw": 3.159018576804558, "pitch": null, "roll": null}, "v": 2.3141127705559956, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "acceleration": 0.11653956446891511, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020094282259943797, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.2090302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2785295611343749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17048213988258631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3141127705559956, "gear": 1, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.2090302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.062277390625983, "y": 0.12170208750692257, "z": null, "yaw": 3.159018576804558, "pitch": null, "roll": null}, "v": 2.3141127705559956, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "acceleration": 0.11653956446891511, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020094282259943797, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.2290301} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2783407937512784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17048213988258631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3165426588573994, "gear": 1, "accelerator_pedal_position": 0.2785295611343749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.2290301} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.062277390625983, "y": 0.12170208750692257, "z": null, "yaw": 3.159018576804558, "pitch": null, "roll": null}, "v": 2.3141127705559956, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "acceleration": 0.11653956446891511, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020094282259943797, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.24903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2783407937512784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17048213988258631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.318944283984576, "gear": 1, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.24903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.062277390625983, "y": 0.12170208750692257, "z": null, "yaw": 3.159018576804558, "pitch": null, "roll": null}, "v": 2.3141127705559956, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "acceleration": 0.11653956446891511, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020094282259943797, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.26903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2783407937512784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17048213988258631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.321341282600026, "gear": 1, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.26903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.062277390625983, "y": 0.12170208750692257, "z": null, "yaw": 3.159018576804558, "pitch": null, "roll": null}, "v": 2.3141127705559956, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "acceleration": 0.11653956446891511, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020094282259943797, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.28903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2783407937512784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17048213988258631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.323733661319168, "gear": 1, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.28903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.062277390625983, "y": 0.12170208750692257, "z": null, "yaw": 3.159018576804558, "pitch": null, "roll": null}, "v": 2.3141127705559956, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "acceleration": 0.11653956446891511, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020094282259943797, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.30903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2783407937512784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17048213988258631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.326121426757952, "gear": 1, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.30903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.31903, "x": 17.807103326135024, "y": 5.117144056113481, "z": null, "yaw": 3.1599737467844844, "pitch": null, "roll": null}, "v": 2.327313581564826, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "acceleration": 0.11910039679788764, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020208909699819113, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.32903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28059613086914265, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10972570945333895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3285045855328046, "gear": 1, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.32903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 13.807103326135024, "y": 0.11714405611348067, "z": null, "yaw": 3.1599737467844844, "pitch": null, "roll": null}, "v": 2.327313581564826, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "acceleration": 0.11910039679788764, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020208909699819113, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.34903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2799549749230004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10972570945333895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.331164925240962, "gear": 1, "accelerator_pedal_position": 0.28059613086914265, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.34903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 13.807103326135024, "y": 0.11714405611348067, "z": null, "yaw": 3.1599737467844844, "pitch": null, "roll": null}, "v": 2.327313581564826, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "acceleration": 0.11910039679788764, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020208909699819113, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.36903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2799549749230004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10972570945333895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3337400213606156, "gear": 1, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.36903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 13.807103326135024, "y": 0.11714405611348067, "z": null, "yaw": 3.1599737467844844, "pitch": null, "roll": null}, "v": 2.327313581564826, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "acceleration": 0.11910039679788764, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020208909699819113, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.38903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2799549749230004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10972570945333895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3363101416116803, "gear": 1, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.38903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 13.807103326135024, "y": 0.11714405611348067, "z": null, "yaw": 3.1599737467844844, "pitch": null, "roll": null}, "v": 2.327313581564826, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "acceleration": 0.11910039679788764, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020208909699819113, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.40903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2799549749230004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10972570945333895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3388752929681167, "gear": 1, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.40903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.42903, "x": 17.55043905530778, "y": 5.1123141576451, "z": null, "yaw": 3.160928916764411, "pitch": null, "roll": null}, "v": 2.3414354824057173, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "acceleration": 0.12782361796578173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020331535297479865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.42903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28178480033156705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0542742918567876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3414354824057173, "gear": 1, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.42903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 13.55043905530778, "y": 0.11231415764510011, "z": null, "yaw": 3.160928916764411, "pitch": null, "roll": null}, "v": 2.3414354824057173, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "acceleration": 0.12782361796578173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020331535297479865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.44903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2812812501190051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0542742918567876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3442193343103006, "gear": 1, "accelerator_pedal_position": 0.28178480033156705, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.44903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 13.55043905530778, "y": 0.11231415764510011, "z": null, "yaw": 3.160928916764411, "pitch": null, "roll": null}, "v": 2.3414354824057173, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "acceleration": 0.12782361796578173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020331535297479865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.46903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2812812501190051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0542742918567876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.346934882090314, "gear": 1, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.46903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 13.55043905530778, "y": 0.11231415764510011, "z": null, "yaw": 3.160928916764411, "pitch": null, "roll": null}, "v": 2.3414354824057173, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "acceleration": 0.12782361796578173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020331535297479865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.48903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2812812501190051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0542742918567876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3496451683259165, "gear": 1, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.48903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 13.55043905530778, "y": 0.11231415764510011, "z": null, "yaw": 3.160928916764411, "pitch": null, "roll": null}, "v": 2.3414354824057173, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "acceleration": 0.12782361796578173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020331535297479865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.5090299} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2812812501190051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0542742918567876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3523502002748438, "gear": 1, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.5090299} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 13.55043905530778, "y": 0.11231415764510011, "z": null, "yaw": 3.160928916764411, "pitch": null, "roll": null}, "v": 2.3414354824057173, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "acceleration": 0.12782361796578173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020331535297479865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.5290298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2812812501190051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0542742918567876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3563979122944, "gear": 1, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.5290298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.5390298, "x": 17.292179242106776, "y": 5.10720745453783, "z": null, "yaw": 3.161884086744337, "pitch": null, "roll": null}, "v": 2.3563979122944, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "acceleration": 0.13466180641840791, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02046145951435611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.5490298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2824024227906168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.008808776717991122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.357744530358584, "gear": 1, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.5490298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 13.292179242106776, "y": 0.10720745453783032, "z": null, "yaw": 3.161884086744337, "pitch": null, "roll": null}, "v": 2.3563979122944, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "acceleration": 0.13466180641840791, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02046145951435611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.5690298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28212460772470854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.008808776717991122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3605739215086032, "gear": 1, "accelerator_pedal_position": 0.2824024227906168, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.5690298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 13.292179242106776, "y": 0.10720745453783032, "z": null, "yaw": 3.161884086744337, "pitch": null, "roll": null}, "v": 2.3563979122944, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "acceleration": 0.13466180641840791, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02046145951435611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.5890298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28212460772470854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.008808776717991122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3633631051475334, "gear": 1, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.5890298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 13.292179242106776, "y": 0.10720745453783032, "z": null, "yaw": 3.161884086744337, "pitch": null, "roll": null}, "v": 2.3563979122944, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "acceleration": 0.13466180641840791, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02046145951435611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.6090298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28212460772470854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.008808776717991122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3661468662777425, "gear": 1, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.6090298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 13.292179242106776, "y": 0.10720745453783032, "z": null, "yaw": 3.161884086744337, "pitch": null, "roll": null}, "v": 2.3563979122944, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "acceleration": 0.13466180641840791, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02046145951435611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.6290298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28212460772470854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.008808776717991122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3689252123430165, "gear": 1, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.6290298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.6490297, "x": 17.032266233659133, "y": 5.101819696509134, "z": null, "yaw": 3.1628392567242636, "pitch": null, "roll": null}, "v": 2.3716981507907393, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "acceleration": 0.13844436955524925, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02059431704615048, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.6490297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2759000018253149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03870189619775816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3716981507907393, "gear": 1, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.6490297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.032266233659133, "y": 0.1018196965091338, "z": null, "yaw": 3.1628392567242636, "pitch": null, "roll": null}, "v": 2.3716981507907393, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "acceleration": 0.13844436955524925, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02059431704615048, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.6690297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2779196135879763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03870189619775816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3736879924819916, "gear": 1, "accelerator_pedal_position": 0.2759000018253149, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.6690297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.032266233659133, "y": 0.1018196965091338, "z": null, "yaw": 3.1628392567242636, "pitch": null, "roll": null}, "v": 2.3716981507907393, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "acceleration": 0.13844436955524925, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02059431704615048, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.6890297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2779196135879763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03870189619775816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.375926285719239, "gear": 1, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.6890297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.032266233659133, "y": 0.1018196965091338, "z": null, "yaw": 3.1628392567242636, "pitch": null, "roll": null}, "v": 2.3716981507907393, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "acceleration": 0.13844436955524925, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02059431704615048, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.7090297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2779196135879763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03870189619775816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3781602160846917, "gear": 1, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.7090297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.032266233659133, "y": 0.1018196965091338, "z": null, "yaw": 3.1628392567242636, "pitch": null, "roll": null}, "v": 2.3716981507907393, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "acceleration": 0.13844436955524925, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02059431704615048, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.7290297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2779196135879763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03870189619775816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3803897900872353, "gear": 1, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.7290297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.032266233659133, "y": 0.1018196965091338, "z": null, "yaw": 3.1628392567242636, "pitch": null, "roll": null}, "v": 2.3716981507907393, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "acceleration": 0.13844436955524925, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02059431704615048, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.7490296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2779196135879763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03870189619775816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3826150142347347, "gear": 1, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.7490296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.7590296, "x": 16.770849688226065, "y": 5.096150990780009, "z": null, "yaw": 3.16379442670419, "pitch": null, "roll": null}, "v": 2.3837259971462603, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "acceleration": 0.11098978877282933, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02069875920762259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.7690296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692037840001167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0957718140305492, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3848358950339885, "gear": 1, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.7690296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 12.770849688226065, "y": 0.09615099078000888, "z": null, "yaw": 3.16379442670419, "pitch": null, "roll": null}, "v": 2.3837259971462603, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "acceleration": 0.11098978877282933, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02069875920762259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.7890296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719861509419769, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0957718140305492, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3859634925757978, "gear": 1, "accelerator_pedal_position": 0.2692037840001167, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.7890296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 12.770849688226065, "y": 0.09615099078000888, "z": null, "yaw": 3.16379442670419, "pitch": null, "roll": null}, "v": 2.3837259971462603, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "acceleration": 0.11098978877282933, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02069875920762259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.8090296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719861509419769, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0957718140305492, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.387436513474609, "gear": 1, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.8090296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 12.770849688226065, "y": 0.09615099078000888, "z": null, "yaw": 3.16379442670419, "pitch": null, "roll": null}, "v": 2.3837259971462603, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "acceleration": 0.11098978877282933, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02069875920762259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.8290296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719861509419769, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0957718140305492, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3889066562792878, "gear": 1, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.8290296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 12.770849688226065, "y": 0.09615099078000888, "z": null, "yaw": 3.16379442670419, "pitch": null, "roll": null}, "v": 2.3837259971462603, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "acceleration": 0.11098978877282933, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02069875920762259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.8490295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719861509419769, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0957718140305492, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.390373925749154, "gear": 1, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.8490295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.8690295, "x": 16.508294359948373, "y": 5.090206719775156, "z": null, "yaw": 3.1647495966841164, "pitch": null, "roll": null}, "v": 2.391838326639294, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "acceleration": 0.07311262124758444, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020769201513068027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.8690295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26741335263356547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1327960413973916, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.391838326639294, "gear": 1, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.8690295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 12.508294359948373, "y": 0.09020671977515615, "z": null, "yaw": 3.1647495966841164, "pitch": null, "roll": null}, "v": 2.391838326639294, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "acceleration": 0.07311262124758444, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020769201513068027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.8890295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26888200436725457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1327960413973916, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3927285435629924, "gear": 1, "accelerator_pedal_position": 0.26741335263356547, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.8890295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 12.508294359948373, "y": 0.09020671977515615, "z": null, "yaw": 3.1647495966841164, "pitch": null, "roll": null}, "v": 2.391838326639294, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "acceleration": 0.07311262124758444, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020769201513068027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.9090295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26888200436725457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1327960413973916, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3938005108187093, "gear": 1, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.9090295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 12.508294359948373, "y": 0.09020671977515615, "z": null, "yaw": 3.1647495966841164, "pitch": null, "roll": null}, "v": 2.391838326639294, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "acceleration": 0.07311262124758444, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020769201513068027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.9290295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26888200436725457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1327960413973916, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3948703808186336, "gear": 1, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.9290295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 12.508294359948373, "y": 0.09020671977515615, "z": null, "yaw": 3.1647495966841164, "pitch": null, "roll": null}, "v": 2.391838326639294, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "acceleration": 0.07311262124758444, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020769201513068027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.9490294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26888200436725457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1327960413973916, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3959381572083274, "gear": 1, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.9490294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 12.508294359948373, "y": 0.09020671977515615, "z": null, "yaw": 3.1647495966841164, "pitch": null, "roll": null}, "v": 2.391838326639294, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "acceleration": 0.07311262124758444, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020769201513068027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.9690294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26888200436725457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1327960413973916, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.397003843628905, "gear": 1, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.9690294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.9790294, "x": 16.244988261261025, "y": 5.083993833703883, "z": null, "yaw": 3.1657047666640428, "pitch": null, "roll": null}, "v": 2.397535904237407, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "acceleration": 0.05315394796239581, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02081867565015898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.9890294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2620269000625193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.18522112355275888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3980674437170313, "gear": 1, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.9890294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 12.244988261261025, "y": 0.08399383370388325, "z": null, "yaw": 3.1657047666640428, "pitch": null, "roll": null}, "v": 2.397535904237407, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "acceleration": 0.05315394796239581, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02081867565015898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.0090294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641970094402424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.18522112355275888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.39827249280351, "gear": 1, "accelerator_pedal_position": 0.2620269000625193, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.0090294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 12.244988261261025, "y": 0.08399383370388325, "z": null, "yaw": 3.1657047666640428, "pitch": null, "roll": null}, "v": 2.397535904237407, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "acceleration": 0.05315394796239581, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02081867565015898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.0290294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641970094402424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.18522112355275888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3987482711317223, "gear": 1, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.0290294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 12.244988261261025, "y": 0.08399383370388325, "z": null, "yaw": 3.1657047666640428, "pitch": null, "roll": null}, "v": 2.397535904237407, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "acceleration": 0.05315394796239581, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02081867565015898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.0490294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641970094402424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.18522112355275888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.399223117651959, "gear": 1, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.0490294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 12.244988261261025, "y": 0.08399383370388325, "z": null, "yaw": 3.1657047666640428, "pitch": null, "roll": null}, "v": 2.397535904237407, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "acceleration": 0.05315394796239581, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02081867565015898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.0690293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641970094402424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.18522112355275888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3996970340990105, "gear": 1, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.0690293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.0890293, "x": 15.98120171574094, "y": 5.077517532718935, "z": null, "yaw": 3.166659936643969, "pitch": null, "roll": null}, "v": 2.4001700222048, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "acceleration": 0.02361464653636891, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02084154865385018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.0890293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2589298545631059, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2350991826489276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4001700222048, "gear": 1, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.0890293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 11.98120171574094, "y": 0.07751753271893502, "z": null, "yaw": 3.166659936643969, "pitch": null, "roll": null}, "v": 2.4001700222048, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "acceleration": 0.02361464653636891, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02084154865385018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.1090293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2605887457064749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2350991826489276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.399984011967884, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.1090293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 11.98120171574094, "y": 0.07751753271893502, "z": null, "yaw": 3.166659936643969, "pitch": null, "roll": null}, "v": 2.4001700222048, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "acceleration": 0.02361464653636891, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02084154865385018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.1290293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2605887457064749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2350991826489276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4000056259216787, "gear": 1, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.1290293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 11.98120171574094, "y": 0.07751753271893502, "z": null, "yaw": 3.166659936643969, "pitch": null, "roll": null}, "v": 2.4001700222048, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "acceleration": 0.02361464653636891, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02084154865385018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.1490293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2605887457064749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2350991826489276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.40002719753288, "gear": 1, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.1490293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 11.98120171574094, "y": 0.07751753271893502, "z": null, "yaw": 3.166659936643969, "pitch": null, "roll": null}, "v": 2.4001700222048, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "acceleration": 0.02361464653636891, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02084154865385018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.1690292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2605887457064749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2350991826489276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4000487268842527, "gear": 1, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.1690292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 11.98120171574094, "y": 0.07751753271893502, "z": null, "yaw": 3.166659936643969, "pitch": null, "roll": null}, "v": 2.4001700222048, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "acceleration": 0.02361464653636891, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02084154865385018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.1890292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2605887457064749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2350991826489276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.400070214058401, "gear": 1, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.1890292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.1990292, "x": 15.717282650855442, "y": 5.070785754447511, "z": null, "yaw": 3.1676151066238956, "pitch": null, "roll": null}, "v": 2.4000809418547857, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "acceleration": 0.0010717282981831389, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020840775136794408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.2090292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25644545140267083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.28966290750653356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4000916591377677, "gear": 1, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.2090292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 11.717282650855442, "y": 0.07078575444751056, "z": null, "yaw": 3.1676151066238956, "pitch": null, "roll": null}, "v": 2.4000809418547857, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "acceleration": 0.0010717282981831389, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020840775136794408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.2290292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577397952163545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.28966290750653356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3995954041920315, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.2290292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 11.717282650855442, "y": 0.07078575444751056, "z": null, "yaw": 3.1676151066238956, "pitch": null, "roll": null}, "v": 2.4000809418547857, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "acceleration": 0.0010717282981831389, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020840775136794408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.2490292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577397952163545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.28966290750653356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.399261835081818, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.2490292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 11.717282650855442, "y": 0.07078575444751056, "z": null, "yaw": 3.1676151066238956, "pitch": null, "roll": null}, "v": 2.4000809418547857, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "acceleration": 0.0010717282981831389, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020840775136794408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.2690291} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577397952163545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.28966290750653356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.398928919359427, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.2690291} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 11.717282650855442, "y": 0.07078575444751056, "z": null, "yaw": 3.1676151066238956, "pitch": null, "roll": null}, "v": 2.4000809418547857, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "acceleration": 0.0010717282981831389, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020840775136794408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.2890291} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577397952163545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.28966290750653356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3984307679822034, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.2890291} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.309029, "x": 15.45345385982394, "y": 5.063804123667583, "z": null, "yaw": 3.168570276603822, "pitch": null, "roll": null}, "v": 2.398265042784354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3774300042936321, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020825007025170334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.309029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522610653978607, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.34632023621993374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.397757059328784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.309029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 11.45345385982394, "y": 0.06380412366758303, "z": null, "yaw": 3.168570276603822, "pitch": null, "roll": null}, "v": 2.398265042784354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3774300042936321, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020825007025170334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.329029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539642731791674, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.34632023621993374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3964488892564324, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.329029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 11.45345385982394, "y": 0.06380412366758303, "z": null, "yaw": 3.168570276603822, "pitch": null, "roll": null}, "v": 2.398265042784354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3774300042936321, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020825007025170334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.349029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539642731791674, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.34632023621993374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3964488892564324, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.349029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 11.45345385982394, "y": 0.06380412366758303, "z": null, "yaw": 3.168570276603822, "pitch": null, "roll": null}, "v": 2.398265042784354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3774300042936321, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020825007025170334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.379029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539642731791674, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.34632023621993374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.394852219955418, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.379029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 11.45345385982394, "y": 0.06380412366758303, "z": null, "yaw": 3.168570276603822, "pitch": null, "roll": null}, "v": 2.398265042784354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3774300042936321, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020825007025170334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.399029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539642731791674, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.34632023621993374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3944540292035956, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.399029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.419029, "x": 15.189984068248583, "y": 5.056580174758179, "z": null, "yaw": 3.1695254465837484, "pitch": null, "roll": null}, "v": 2.3936588166900625, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37697896614168386, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020785009489842972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.419029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24763475839331534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40145684793248915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3936588166900625, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.419029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.189984068248583, "y": 0.05658017475817889, "z": null, "yaw": 3.1695254465837484, "pitch": null, "roll": null}, "v": 2.3936588166900625, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37697896614168386, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020785009489842972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.439029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24959018113837178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40145684793248915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3920743578632595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4409827205877354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.439029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.189984068248583, "y": 0.05658017475817889, "z": null, "yaw": 3.1695254465837484, "pitch": null, "roll": null}, "v": 2.3936588166900625, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37697896614168386, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020785009489842972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.459029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24959018113837178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40145684793248915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3907373065718036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4409827205877354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.459029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.189984068248583, "y": 0.05658017475817889, "z": null, "yaw": 3.1695254465837484, "pitch": null, "roll": null}, "v": 2.3936588166900625, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37697896614168386, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020785009489842972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.479029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24959018113837178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40145684793248915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.38940286984643, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4409827205877354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.479029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.189984068248583, "y": 0.05658017475817889, "z": null, "yaw": 3.1695254465837484, "pitch": null, "roll": null}, "v": 2.3936588166900625, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37697896614168386, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020785009489842972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.499029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24959018113837178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40145684793248915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3880710418624878, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4409827205877354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.499029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.189984068248583, "y": 0.05658017475817889, "z": null, "yaw": 3.1695254465837484, "pitch": null, "roll": null}, "v": 2.3936588166900625, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37697896614168386, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020785009489842972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.519029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24959018113837178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40145684793248915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.386741816810888, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4409827205877354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.519029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.529029, "x": 14.927177923122116, "y": 5.049131025558601, "z": null, "yaw": 3.1704080990216457, "pitch": null, "roll": null}, "v": 2.3860781785736194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376237599671333, "steering_wheel_angle": 0.4409827205877354, "front_wheel_angle": 0.020370143417154388, "heading_rate": 0.01898885880787921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.539029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24529708233643754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4526322184059812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.385415188898054, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4409827205877354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.539029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 10.927177923122116, "y": 0.049131025558600605, "z": null, "yaw": 3.1704080990216457, "pitch": null, "roll": null}, "v": 2.3860781785736194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376237599671333, "steering_wheel_angle": 0.4409827205877354, "front_wheel_angle": 0.020370143417154388, "heading_rate": 0.01898885880787921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.5590289} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24660160824383828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4526322184059812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.383554777122512, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.400970225024412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.5590289} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 10.927177923122116, "y": 0.049131025558600605, "z": null, "yaw": 3.1704080990216457, "pitch": null, "roll": null}, "v": 2.3860781785736194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376237599671333, "steering_wheel_angle": 0.4409827205877354, "front_wheel_angle": 0.020370143417154388, "heading_rate": 0.01898885880787921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.5790288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24660160824383828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4526322184059812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3818609842061322, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.400970225024412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.5790288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 10.927177923122116, "y": 0.049131025558600605, "z": null, "yaw": 3.1704080990216457, "pitch": null, "roll": null}, "v": 2.3860781785736194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376237599671333, "steering_wheel_angle": 0.4409827205877354, "front_wheel_angle": 0.020370143417154388, "heading_rate": 0.01898885880787921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.5990288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24660160824383828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4526322184059812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3801704975064304, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.400970225024412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.5990288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 10.927177923122116, "y": 0.049131025558600605, "z": null, "yaw": 3.1704080990216457, "pitch": null, "roll": null}, "v": 2.3860781785736194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376237599671333, "steering_wheel_angle": 0.4409827205877354, "front_wheel_angle": 0.020370143417154388, "heading_rate": 0.01898885880787921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.6190288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24660160824383828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4526322184059812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3784833094272613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.400970225024412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.6190288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.6390288, "x": 14.665282162575256, "y": 5.041484292270824, "z": null, "yaw": 3.1712181493928826, "pitch": null, "roll": null}, "v": 2.376799412393991, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533172508726376, "steering_wheel_angle": 0.400970225024412, "front_wheel_angle": 0.01851199309503013, "heading_rate": 0.017189187928119975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.6390288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24636912609496012, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5160590123106856, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.375089752754458, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32067979644808964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.6390288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.04994177818298, "x": 10.665282162575256, "y": 0.041484292270824064, "z": null, "yaw": 3.1712181493928826, "pitch": null, "roll": null}, "v": 2.376799412393991, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533172508726376, "steering_wheel_angle": 0.400970225024412, "front_wheel_angle": 0.01851199309503013, "heading_rate": 0.017189187928119975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.6590288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24639648305521772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5160590123106856, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.375089752754458, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32067979644808964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.6590288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.04994177818298, "x": 10.665282162575256, "y": 0.041484292270824064, "z": null, "yaw": 3.1712181493928826, "pitch": null, "roll": null}, "v": 2.376799412393991, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533172508726376, "steering_wheel_angle": 0.400970225024412, "front_wheel_angle": 0.01851199309503013, "heading_rate": 0.017189187928119975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.6890287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24639648305521772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5160590123106856, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3716872527569466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32067979644808964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.6890287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24639648305521772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5160590123106856, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3716872527569466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32067979644808964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.6990287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.04994177818298, "x": 10.665282162575256, "y": 0.041484292270824064, "z": null, "yaw": 3.1712181493928826, "pitch": null, "roll": null}, "v": 2.376799412393991, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533172508726376, "steering_wheel_angle": 0.400970225024412, "front_wheel_angle": 0.01851199309503013, "heading_rate": 0.017189187928119975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.7290287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24639648305521772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5160590123106856, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3674527429361856, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32067979644808964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.7290287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.7490287, "x": 14.404419540983893, "y": 5.033673471421998, "z": null, "yaw": 3.17187549411445, "pitch": null, "roll": null}, "v": 2.3674527429361856, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37442096204716996, "steering_wheel_angle": 0.32067979644808964, "front_wheel_angle": 0.014789357887998908, "heading_rate": 0.013677991746097417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.7490287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24325978468522066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5646394606134201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3674527429361856, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32067979644808964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.7490287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 10.404419540983893, "y": 0.033673471421997725, "z": null, "yaw": 3.17187549411445, "pitch": null, "roll": null}, "v": 2.3674527429361856, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37442096204716996, "steering_wheel_angle": 0.32067979644808964, "front_wheel_angle": 0.014789357887998908, "heading_rate": 0.013677991746097417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.7790287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419446538666448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5646394606134201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.364334360848566, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.7790287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 10.404419540983893, "y": 0.033673471421997725, "z": null, "yaw": 3.17187549411445, "pitch": null, "roll": null}, "v": 2.3674527429361856, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37442096204716996, "steering_wheel_angle": 0.32067979644808964, "front_wheel_angle": 0.014789357887998908, "heading_rate": 0.013677991746097417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.7990286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419446538666448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5646394606134201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.362377271628119, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.7990286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 10.404419540983893, "y": 0.033673471421997725, "z": null, "yaw": 3.17187549411445, "pitch": null, "roll": null}, "v": 2.3674527429361856, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37442096204716996, "steering_wheel_angle": 0.32067979644808964, "front_wheel_angle": 0.014789357887998908, "heading_rate": 0.013677991746097417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.8190286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419446538666448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5646394606134201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.360423987382127, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.8190286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 10.404419540983893, "y": 0.033673471421997725, "z": null, "yaw": 3.17187549411445, "pitch": null, "roll": null}, "v": 2.3674527429361856, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37442096204716996, "steering_wheel_angle": 0.32067979644808964, "front_wheel_angle": 0.014789357887998908, "heading_rate": 0.013677991746097417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.8390286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419446538666448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5646394606134201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3584744991875692, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.8390286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.8590286, "x": 14.14467520191236, "y": 5.025737966501749, "z": null, "yaw": 3.172438203758676, "pitch": null, "roll": null}, "v": 2.3565287981476595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37335871967237555, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011898926966146143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.8590286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23445020073300854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5789415715562822, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3565287981476595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.8590286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 10.14467520191236, "y": 0.0257379665017492, "z": null, "yaw": 3.172438203758676, "pitch": null, "roll": null}, "v": 2.3565287981476595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37335871967237555, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011898926966146143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.8790286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744217328022638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5789415715562822, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3533694336959043, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.8790286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 10.14467520191236, "y": 0.0257379665017492, "z": null, "yaw": 3.172438203758676, "pitch": null, "roll": null}, "v": 2.3565287981476595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37335871967237555, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011898926966146143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.8990285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744217328022638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5789415715562822, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3505900157997366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.8990285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 10.14467520191236, "y": 0.0257379665017492, "z": null, "yaw": 3.172438203758676, "pitch": null, "roll": null}, "v": 2.3565287981476595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37335871967237555, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011898926966146143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.9190285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744217328022638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5789415715562822, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.347815988786598, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.9190285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744217328022638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5789415715562822, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.34504733912388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.9290285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 10.14467520191236, "y": 0.0257379665017492, "z": null, "yaw": 3.172438203758676, "pitch": null, "roll": null}, "v": 2.3565287981476595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37335871967237555, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011898926966146143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.9590285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744217328022638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5789415715562822, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3422840533231, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.9590285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.9690285, "x": 13.886381535540163, "y": 5.017703033614648, "z": null, "yaw": 3.1729936317115612, "pitch": null, "roll": null}, "v": 2.3409044176678075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718435558099569, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011820034078281937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.9790285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23996738322761485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6407485235875497, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.339526117939722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.9790285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 9.886381535540163, "y": 0.01770303361464798, "z": null, "yaw": 3.1729936317115612, "pitch": null, "roll": null}, "v": 2.3409044176678075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718435558099569, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011820034078281937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.9990284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.239102496358871, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6407485235875497, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3370890180971315, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1995968059476741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.9990284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 9.886381535540163, "y": 0.01770303361464798, "z": null, "yaw": 3.1729936317115612, "pitch": null, "roll": null}, "v": 2.3409044176678075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718435558099569, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011820034078281937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.0190284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.239102496358871, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6407485235875497, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3345485733770226, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1995968059476741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.0190284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 9.886381535540163, "y": 0.01770303361464798, "z": null, "yaw": 3.1729936317115612, "pitch": null, "roll": null}, "v": 2.3409044176678075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718435558099569, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011820034078281937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.0390284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.239102496358871, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6407485235875497, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3320130396882477, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1995968059476741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.0390284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 9.886381535540163, "y": 0.01770303361464798, "z": null, "yaw": 3.1729936317115612, "pitch": null, "roll": null}, "v": 2.3409044176678075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718435558099569, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011820034078281937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.0590284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.239102496358871, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6407485235875497, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3294824049667726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1995968059476741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.0590284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.0790284, "x": 13.629710479534776, "y": 5.009586756207608, "z": null, "yaw": 3.1734250244478277, "pitch": null, "roll": null}, "v": 2.3269566571867726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37049510570359706, "steering_wheel_angle": 0.1995968059476741, "front_wheel_angle": 0.009190420167051058, "heading_rate": 0.008354027936196353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.0790284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24141343557002135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7090311929349393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3269566571867726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1995968059476741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.0790284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 9.629710479534776, "y": 0.009586756207608182, "z": null, "yaw": 3.1734250244478277, "pitch": null, "roll": null}, "v": 2.3269566571867726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37049510570359706, "steering_wheel_angle": 0.1995968059476741, "front_wheel_angle": 0.009190420167051058, "heading_rate": 0.008354027936196353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.0990283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24062384404352233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7090311929349393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3247245123611733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11845261662774584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.0990283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 9.629710479534776, "y": 0.009586756207608182, "z": null, "yaw": 3.1734250244478277, "pitch": null, "roll": null}, "v": 2.3269566571867726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37049510570359706, "steering_wheel_angle": 0.1995968059476741, "front_wheel_angle": 0.009190420167051058, "heading_rate": 0.008354027936196353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.1190283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24062384404352233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7090311929349393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3223980224161958, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11845261662774584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.1190283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 9.629710479534776, "y": 0.009586756207608182, "z": null, "yaw": 3.1734250244478277, "pitch": null, "roll": null}, "v": 2.3269566571867726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37049510570359706, "steering_wheel_angle": 0.1995968059476741, "front_wheel_angle": 0.009190420167051058, "heading_rate": 0.008354027936196353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.1390283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24062384404352233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7090311929349393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3200760185522666, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11845261662774584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.1390283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 9.629710479534776, "y": 0.009586756207608182, "z": null, "yaw": 3.1734250244478277, "pitch": null, "roll": null}, "v": 2.3269566571867726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37049510570359706, "steering_wheel_angle": 0.1995968059476741, "front_wheel_angle": 0.009190420167051058, "heading_rate": 0.008354027936196353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.1590283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24062384404352233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7090311929349393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3177584899634063, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11845261662774584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.1590283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 9.629710479534776, "y": 0.009586756207608182, "z": null, "yaw": 3.1734250244478277, "pitch": null, "roll": null}, "v": 2.3269566571867726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37049510570359706, "steering_wheel_angle": 0.1995968059476741, "front_wheel_angle": 0.009190420167051058, "heading_rate": 0.008354027936196353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.1790283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24062384404352233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7090311929349393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.315445425876927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11845261662774584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.1790283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.1890283, "x": 13.374505712917289, "y": 5.001428159460674, "z": null, "yaw": 3.173681061413053, "pitch": null, "roll": null}, "v": 2.314290564664687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36927393641019435, "steering_wheel_angle": 0.11845261662774584, "front_wheel_angle": 0.005448311387945088, "heading_rate": 0.004925429844522046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.1990283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430886218452244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7814399947919608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3131368155533054, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11845261662774584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.1990283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 9.374505712917289, "y": 0.0014281594606737613, "z": null, "yaw": 3.173681061413053, "pitch": null, "roll": null}, "v": 2.314290564664687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36927393641019435, "steering_wheel_angle": 0.11845261662774584, "front_wheel_angle": 0.005448311387945088, "heading_rate": 0.004925429844522046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.2190282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24225731977247825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7814399947919608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3111405972529973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07773503784527401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.2190282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 9.374505712917289, "y": 0.0014281594606737613, "z": null, "yaw": 3.173681061413053, "pitch": null, "roll": null}, "v": 2.314290564664687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36927393641019435, "steering_wheel_angle": 0.11845261662774584, "front_wheel_angle": 0.005448311387945088, "heading_rate": 0.004925429844522046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.2390282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24225731977247825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7814399947919608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3090443563616527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07773503784527401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.2390282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 9.374505712917289, "y": 0.0014281594606737613, "z": null, "yaw": 3.173681061413053, "pitch": null, "roll": null}, "v": 2.314290564664687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36927393641019435, "steering_wheel_angle": 0.11845261662774584, "front_wheel_angle": 0.005448311387945088, "heading_rate": 0.004925429844522046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.2590282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24225731977247825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7814399947919608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.306952146336508, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07773503784527401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.2590282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 9.374505712917289, "y": 0.0014281594606737613, "z": null, "yaw": 3.173681061413053, "pitch": null, "roll": null}, "v": 2.314290564664687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36927393641019435, "steering_wheel_angle": 0.11845261662774584, "front_wheel_angle": 0.005448311387945088, "heading_rate": 0.004925429844522046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.2790282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24225731977247825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7814399947919608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.304863957676505, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07773503784527401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.2790282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.2990282, "x": 13.120643285517101, "y": 4.993258386833993, "z": null, "yaw": 3.1738492604057638, "pitch": null, "roll": null}, "v": 2.30277978090894, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36816693623907726, "steering_wheel_angle": 0.07773503784527401, "front_wheel_angle": 0.003573563847827696, "heading_rate": 0.0032145178142160566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.2990282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23631764721650755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8833760444382817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.30277978090894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07773503784527401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.2990282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.120643285517101, "y": -0.0067416131660067435, "z": null, "yaw": 3.1738492604057638, "pitch": null, "roll": null}, "v": 2.30277978090894, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36816693623907726, "steering_wheel_angle": 0.07773503784527401, "front_wheel_angle": 0.003573563847827696, "heading_rate": 0.0032145178142160566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.3190281} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23811844606238827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8833760444382817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.299957504015562, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.004058733064131218, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.3190281} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.120643285517101, "y": -0.0067416131660067435, "z": null, "yaw": 3.1738492604057638, "pitch": null, "roll": null}, "v": 2.30277978090894, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36816693623907726, "steering_wheel_angle": 0.07773503784527401, "front_wheel_angle": 0.003573563847827696, "heading_rate": 0.0032145178142160566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.3390281} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23811844606238827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8833760444382817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.296071567054703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04496907956616924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.3390281} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.120643285517101, "y": -0.0067416131660067435, "z": null, "yaw": 3.1738492604057638, "pitch": null, "roll": null}, "v": 2.30277978090894, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36816693623907726, "steering_wheel_angle": 0.07773503784527401, "front_wheel_angle": 0.003573563847827696, "heading_rate": 0.0032145178142160566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.359028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23811844606238827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8833760444382817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2947787396859716, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04496907956616924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.359028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.120643285517101, "y": -0.0067416131660067435, "z": null, "yaw": 3.1738492604057638, "pitch": null, "roll": null}, "v": 2.30277978090894, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36816693623907726, "steering_wheel_angle": 0.07773503784527401, "front_wheel_angle": 0.003573563847827696, "heading_rate": 0.0032145178142160566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.379028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23811844606238827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8833760444382817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2909076910784583, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04496907956616924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.379028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.120643285517101, "y": -0.0067416131660067435, "z": null, "yaw": 3.1738492604057638, "pitch": null, "roll": null}, "v": 2.30277978090894, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36816693623907726, "steering_wheel_angle": 0.07773503784527401, "front_wheel_angle": 0.003573563847827696, "heading_rate": 0.0032145178142160566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.399028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23811844606238827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8833760444382817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.289619814306914, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04496907956616924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.399028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.409028, "x": 12.868202713299336, "y": 4.985113429254692, "z": null, "yaw": 3.1738045323924147, "pitch": null, "roll": null}, "v": 2.288333171389253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667813456022666, "steering_wheel_angle": -0.04496907956616924, "front_wheel_angle": -0.002066388045825318, "heading_rate": -0.0018471058752045732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.419028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21629728667252437, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.009465276918481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2870477608121296, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04496907956616924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.419028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 8.868202713299336, "y": -0.014886570745307637, "z": null, "yaw": 3.1738045323924147, "pitch": null, "roll": null}, "v": 2.288333171389253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667813456022666, "steering_wheel_angle": -0.04496907956616924, "front_wheel_angle": -0.002066388045825318, "heading_rate": -0.0018471058752045732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.439028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22304712387555445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.009465276918481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.281754290914754, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.12694185942218053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.439028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 8.868202713299336, "y": -0.014886570745307637, "z": null, "yaw": 3.1738045323924147, "pitch": null, "roll": null}, "v": 2.288333171389253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667813456022666, "steering_wheel_angle": -0.04496907956616924, "front_wheel_angle": -0.002066388045825318, "heading_rate": -0.0018471058752045732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.459028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22304712387555445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.009465276918481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2773142702104194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16786193660144705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.459028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 8.868202713299336, "y": -0.014886570745307637, "z": null, "yaw": 3.1738045323924147, "pitch": null, "roll": null}, "v": 2.288333171389253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667813456022666, "steering_wheel_angle": -0.04496907956616924, "front_wheel_angle": -0.002066388045825318, "heading_rate": -0.0018471058752045732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.479028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22304712387555445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.009465276918481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2728827319728926, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16786193660144705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.479028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 8.868202713299336, "y": -0.014886570745307637, "z": null, "yaw": 3.1738045323924147, "pitch": null, "roll": null}, "v": 2.288333171389253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667813456022666, "steering_wheel_angle": -0.04496907956616924, "front_wheel_angle": -0.002066388045825318, "heading_rate": -0.0018471058752045732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.499028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22304712387555445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.009465276918481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2684596521451224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16786193660144705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.499028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.519028, "x": 12.617814452929174, "y": 4.977069489772291, "z": null, "yaw": 3.173538876254534, "pitch": null, "roll": null}, "v": 2.2640450067609437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644612482644388, "steering_wheel_angle": -0.16786193660144705, "front_wheel_angle": -0.007725954779661228, "heading_rate": -0.006832913040059342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.519028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22948974986651796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0875031506360076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2640450067609437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16786193660144705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.519028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 8.617814452929174, "y": -0.022930510227708645, "z": null, "yaw": 3.173538876254534, "pitch": null, "roll": null}, "v": 2.2640450067609437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644612482644388, "steering_wheel_angle": -0.16786193660144705, "front_wheel_angle": -0.007725954779661228, "heading_rate": -0.006832913040059342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.539028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22736042298135498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0875031506360076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.260443716692813, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24974602436744323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.539028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 8.617814452929174, "y": -0.022930510227708645, "z": null, "yaw": 3.173538876254534, "pitch": null, "roll": null}, "v": 2.2640450067609437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644612482644388, "steering_wheel_angle": -0.16786193660144705, "front_wheel_angle": -0.007725954779661228, "heading_rate": -0.006832913040059342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.559028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22736042298135498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0875031506360076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.256583242948477, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24974602436744323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.559028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 8.617814452929174, "y": -0.022930510227708645, "z": null, "yaw": 3.173538876254534, "pitch": null, "roll": null}, "v": 2.2640450067609437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644612482644388, "steering_wheel_angle": -0.16786193660144705, "front_wheel_angle": -0.007725954779661228, "heading_rate": -0.006832913040059342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.579028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22736042298135498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0875031506360076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.252730112265904, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24974602436744323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.579028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 8.617814452929174, "y": -0.022930510227708645, "z": null, "yaw": 3.173538876254534, "pitch": null, "roll": null}, "v": 2.2640450067609437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644612482644388, "steering_wheel_angle": -0.16786193660144705, "front_wheel_angle": -0.007725954779661228, "heading_rate": -0.006832913040059342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.5990279} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22736042298135498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0875031506360076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.248884304741926, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24974602436744323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.5990279} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 8.617814452929174, "y": -0.022930510227708645, "z": null, "yaw": 3.173538876254534, "pitch": null, "roll": null}, "v": 2.2640450067609437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644612482644388, "steering_wheel_angle": -0.16786193660144705, "front_wheel_angle": -0.007725954779661228, "heading_rate": -0.006832913040059342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.6190279} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22736042298135498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0875031506360076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2450458005450526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24974602436744323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.6190279} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.6290278, "x": 12.369930236266711, "y": 4.96919867764226, "z": null, "yaw": 3.1730665638141184, "pitch": null, "roll": null}, "v": 2.2431292810164605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3624727537643573, "steering_wheel_angle": -0.24974602436744323, "front_wheel_angle": -0.01150716115829012, "heading_rate": -0.010083277146356697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.6390278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2333303852991189, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.169072121457426, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2412145799151517, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24974602436744323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.6390278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 8.369930236266711, "y": -0.030801322357739913, "z": null, "yaw": 3.1730665638141184, "pitch": null, "roll": null}, "v": 2.2431292810164605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3624727537643573, "steering_wheel_angle": -0.24974602436744323, "front_wheel_angle": -0.01150716115829012, "heading_rate": -0.010083277146356697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.6590278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23136534606143347, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.169072121457426, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2381365147707664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.6590278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 8.369930236266711, "y": -0.030801322357739913, "z": null, "yaw": 3.1730665638141184, "pitch": null, "roll": null}, "v": 2.2431292810164605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3624727537643573, "steering_wheel_angle": -0.24974602436744323, "front_wheel_angle": -0.01150716115829012, "heading_rate": -0.010083277146356697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.6790278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23136534606143347, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.169072121457426, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.234818767965261, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.6790278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 8.369930236266711, "y": -0.030801322357739913, "z": null, "yaw": 3.1730665638141184, "pitch": null, "roll": null}, "v": 2.2431292810164605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3624727537643573, "steering_wheel_angle": -0.24974602436744323, "front_wheel_angle": -0.01150716115829012, "heading_rate": -0.010083277146356697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.6990278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23136534606143347, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.169072121457426, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2315073028567576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.6990278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 8.369930236266711, "y": -0.030801322357739913, "z": null, "yaw": 3.1730665638141184, "pitch": null, "roll": null}, "v": 2.2431292810164605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3624727537643573, "steering_wheel_angle": -0.24974602436744323, "front_wheel_angle": -0.01150716115829012, "heading_rate": -0.010083277146356697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.7190278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23136534606143347, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.169072121457426, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.22820210316748, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.7190278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.7390277, "x": 12.124222647036099, "y": 4.961528514318324, "z": null, "yaw": 3.1724462380719687, "pitch": null, "roll": null}, "v": 2.2249031526753407, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36074709802161375, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013295663926268008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.7390277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22412769742350022, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.145798734520616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2228036627840932, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.7390277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.124222647036099, "y": -0.03847148568167569, "z": null, "yaw": 3.1724462380719687, "pitch": null, "roll": null}, "v": 2.2249031526753407, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36074709802161375, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013295663926268008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.7590277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22630318126207555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.145798734520616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2207061564293413, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.7590277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.124222647036099, "y": -0.03847148568167569, "z": null, "yaw": 3.1724462380719687, "pitch": null, "roll": null}, "v": 2.2249031526753407, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36074709802161375, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013295663926268008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.7790277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22630318126207555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.145798734520616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2167888904793887, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.7790277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.124222647036099, "y": -0.03847148568167569, "z": null, "yaw": 3.1724462380719687, "pitch": null, "roll": null}, "v": 2.2249031526753407, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36074709802161375, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013295663926268008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.7990277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22630318126207555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.145798734520616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.212879013343746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.7990277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.124222647036099, "y": -0.03847148568167569, "z": null, "yaw": 3.1724462380719687, "pitch": null, "roll": null}, "v": 2.2249031526753407, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36074709802161375, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013295663926268008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.8190277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22630318126207555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.145798734520616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.208976504973528, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.8190277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.124222647036099, "y": -0.03847148568167569, "z": null, "yaw": 3.1724462380719687, "pitch": null, "roll": null}, "v": 2.2249031526753407, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36074709802161375, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013295663926268008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.8390276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22630318126207555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.145798734520616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2011935146952455, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.8390276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.8490276, "x": 11.88069964354294, "y": 4.954085273339442, "z": null, "yaw": 3.1717888957377065, "pitch": null, "roll": null}, "v": 2.2031365151744025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3586949308036682, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013165589996232274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.8590276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23240140018056316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.221501052107196, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2011935146952455, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.8590276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 7.88069964354294, "y": -0.04591472666055818, "z": null, "yaw": 3.1717888957377065, "pitch": null, "roll": null}, "v": 2.2031365151744025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3586949308036682, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013165589996232274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.8790276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2303930970908924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.221501052107196, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.194711248480954, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37257675831235476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.8790276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 7.88069964354294, "y": -0.04591472666055818, "z": null, "yaw": 3.1717888957377065, "pitch": null, "roll": null}, "v": 2.2031365151744025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3586949308036682, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013165589996232274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.9090276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2303930970908924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.221501052107196, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1913538995125155, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37257675831235476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.9090276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 7.88069964354294, "y": -0.04591472666055818, "z": null, "yaw": 3.1717888957377065, "pitch": null, "roll": null}, "v": 2.2031365151744025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3586949308036682, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013165589996232274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.9290276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2303930970908924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.221501052107196, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.189677587939649, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37257675831235476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.9290276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 7.88069964354294, "y": -0.04591472666055818, "z": null, "yaw": 3.1717888957377065, "pitch": null, "roll": null}, "v": 2.2031365151744025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3586949308036682, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013165589996232274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.9490275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2303930970908924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.221501052107196, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1863296804169803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37257675831235476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.9490275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.9590275, "x": 11.639391987222988, "y": 4.946874378714652, "z": null, "yaw": 3.171064820715189, "pitch": null, "roll": null}, "v": 2.1846580803978055, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35696021330236455, "steering_wheel_angle": -0.37257675831235476, "front_wheel_angle": -0.017194628352752483, "heading_rate": -0.014675033688994648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.9690275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23574758655143574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.302668567695428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1829880468329628, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37257675831235476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.9690275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 7.639391987222988, "y": -0.053125621285348146, "z": null, "yaw": 3.171064820715189, "pitch": null, "roll": null}, "v": 2.1846580803978055, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35696021330236455, "steering_wheel_angle": -0.37257675831235476, "front_wheel_angle": -0.017194628352752483, "heading_rate": -0.014675033688994648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.9890275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233987571565995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.302668567695428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1789903518783187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.9890275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 7.639391987222988, "y": -0.053125621285348146, "z": null, "yaw": 3.171064820715189, "pitch": null, "roll": null}, "v": 2.1846580803978055, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35696021330236455, "steering_wheel_angle": -0.37257675831235476, "front_wheel_angle": -0.017194628352752483, "heading_rate": -0.014675033688994648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.0090275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233987571565995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.302668567695428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1775502800298963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.0090275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 7.639391987222988, "y": -0.053125621285348146, "z": null, "yaw": 3.171064820715189, "pitch": null, "roll": null}, "v": 2.1846580803978055, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35696021330236455, "steering_wheel_angle": -0.37257675831235476, "front_wheel_angle": -0.017194628352752483, "heading_rate": -0.014675033688994648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.0290275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233987571565995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.302668567695428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.173238142242263, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.0290275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 7.639391987222988, "y": -0.053125621285348146, "z": null, "yaw": 3.171064820715189, "pitch": null, "roll": null}, "v": 2.1846580803978055, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35696021330236455, "steering_wheel_angle": -0.37257675831235476, "front_wheel_angle": -0.017194628352752483, "heading_rate": -0.014675033688994648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.0490274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233987571565995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.302668567695428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1718034499917267, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.0490274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.0690274, "x": 11.399969757476075, "y": 4.939906764345411, "z": null, "yaw": 3.1701995659764735, "pitch": null, "roll": null}, "v": 2.168938086004275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35548982850941263, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.017793512983675954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.0690274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22952009105251656, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2488438836485292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.168938086004275, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.0690274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 7.399969757476075, "y": -0.06009323565458935, "z": null, "yaw": 3.1701995659764735, "pitch": null, "roll": null}, "v": 2.168938086004275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35548982850941263, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.017793512983675954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.0890274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23084266034047496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2488438836485292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1655198971998093, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.0890274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 7.399969757476075, "y": -0.06009323565458935, "z": null, "yaw": 3.1701995659764735, "pitch": null, "roll": null}, "v": 2.168938086004275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35548982850941263, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.017793512983675954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.1090274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23084266034047496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2488438836485292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1622733296958025, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.1090274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 7.399969757476075, "y": -0.06009323565458935, "z": null, "yaw": 3.1701995659764735, "pitch": null, "roll": null}, "v": 2.168938086004275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35548982850941263, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.017793512983675954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.1290274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23084266034047496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2488438836485292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.157414822570737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.1290274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 7.399969757476075, "y": -0.06009323565458935, "z": null, "yaw": 3.1701995659764735, "pitch": null, "roll": null}, "v": 2.168938086004275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35548982850941263, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.017793512983675954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.1490273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23084266034047496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2488438836485292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1557983375590664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.1490273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 7.399969757476075, "y": -0.06009323565458935, "z": null, "yaw": 3.1701995659764735, "pitch": null, "roll": null}, "v": 2.168938086004275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35548982850941263, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.017793512983675954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.1690273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23084266034047496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2488438836485292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1525698820126222, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.1690273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.1790273, "x": 11.162389176817541, "y": 4.933205847405813, "z": null, "yaw": 3.1692971490560304, "pitch": null, "roll": null}, "v": 2.1509579076332006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353814094585758, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.01764600737281552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.1890273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23688484428240392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3283018599302332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1481160925710374, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49543302361709274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.1890273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 7.162389176817541, "y": -0.06679415259418686, "z": null, "yaw": 3.1692971490560304, "pitch": null, "roll": null}, "v": 2.1509579076332006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353814094585758, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.01764600737281552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.2090273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2349128738114438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3283018599302332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.146885897017686, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49543302361709274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.2090273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 7.162389176817541, "y": -0.06679415259418686, "z": null, "yaw": 3.1692971490560304, "pitch": null, "roll": null}, "v": 2.1509579076332006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353814094585758, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.01764600737281552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.2290273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2349128738114438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3283018599302332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1401369466378144, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49543302361709274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.2290273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 7.162389176817541, "y": -0.06679415259418686, "z": null, "yaw": 3.1692971490560304, "pitch": null, "roll": null}, "v": 2.1509579076332006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353814094585758, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.01764600737281552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.2590272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2349128738114438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3283018599302332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.138790914162674, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49543302361709274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.2590272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 7.162389176817541, "y": -0.06679415259418686, "z": null, "yaw": 3.1692971490560304, "pitch": null, "roll": null}, "v": 2.1509579076332006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353814094585758, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.01764600737281552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.2790272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2349128738114438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3283018599302332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1347603044995314, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49543302361709274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.2790272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.2890272, "x": 10.92661973719601, "y": 4.926774699273058, "z": null, "yaw": 3.168327784703925, "pitch": null, "roll": null}, "v": 2.136102594613094, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524344726777826, "steering_wheel_angle": -0.49543302361709274, "front_wheel_angle": -0.02290198050117497, "heading_rate": -0.019113099529194457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.3090272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23790994103254842, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3557651308706298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.13341925880473, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49543302361709274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.3090272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 6.92661973719601, "y": -0.07322530072694189, "z": null, "yaw": 3.168327784703925, "pitch": null, "roll": null}, "v": 2.136102594613094, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524344726777826, "steering_wheel_angle": -0.49543302361709274, "front_wheel_angle": -0.02290198050117497, "heading_rate": -0.019113099529194457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.3290272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690437577125448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3557651308706298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131115354485651, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5363464105353289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.3290272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 6.92661973719601, "y": -0.07322530072694189, "z": null, "yaw": 3.168327784703925, "pitch": null, "roll": null}, "v": 2.136102594613094, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524344726777826, "steering_wheel_angle": -0.49543302361709274, "front_wheel_angle": -0.02290198050117497, "heading_rate": -0.019113099529194457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.3490272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690437577125448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3557651308706298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1262692925988245, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5363464105353289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.3490272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 6.92661973719601, "y": -0.07322530072694189, "z": null, "yaw": 3.168327784703925, "pitch": null, "roll": null}, "v": 2.136102594613094, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524344726777826, "steering_wheel_angle": -0.49543302361709274, "front_wheel_angle": -0.02290198050117497, "heading_rate": -0.019113099529194457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.3690271} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690437577125448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3557651308706298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1262692925988245, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5363464105353289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.3690271} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 6.92661973719601, "y": -0.07322530072694189, "z": null, "yaw": 3.168327784703925, "pitch": null, "roll": null}, "v": 2.136102594613094, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524344726777826, "steering_wheel_angle": -0.49543302361709274, "front_wheel_angle": -0.02290198050117497, "heading_rate": -0.019113099529194457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.389027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690437577125448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3557651308706298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1226465061209043, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5363464105353289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.389027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.399027, "x": 10.6924113970766, "y": 4.920620785175707, "z": null, "yaw": 3.167283983101646, "pitch": null, "roll": null}, "v": 2.1226465061209043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35118860720551803, "steering_wheel_angle": -0.5363464105353289, "front_wheel_angle": -0.024806816979371784, "heading_rate": -0.020573010620095547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.409027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24208335947694745, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4426151603240256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1214411435345526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5363464105353289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.409027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 6.692411397076601, "y": -0.07937921482429289, "z": null, "yaw": 3.167283983101646, "pitch": null, "roll": null}, "v": 2.1226465061209043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35118860720551803, "steering_wheel_angle": -0.5363464105353289, "front_wheel_angle": -0.024806816979371784, "heading_rate": -0.020573010620095547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.429027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24040263269333484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4426151603240256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1196808336359605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.429027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 6.692411397076601, "y": -0.07937921482429289, "z": null, "yaw": 3.167283983101646, "pitch": null, "roll": null}, "v": 2.1226465061209043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35118860720551803, "steering_wheel_angle": -0.5363464105353289, "front_wheel_angle": -0.024806816979371784, "heading_rate": -0.020573010620095547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.449027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24040263269333484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4426151603240256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117713781560097, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.449027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 6.692411397076601, "y": -0.07937921482429289, "z": null, "yaw": 3.167283983101646, "pitch": null, "roll": null}, "v": 2.1226465061209043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35118860720551803, "steering_wheel_angle": -0.5363464105353289, "front_wheel_angle": -0.024806816979371784, "heading_rate": -0.020573010620095547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.469027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24040263269333484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4426151603240256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1157503615066156, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.469027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 6.692411397076601, "y": -0.07937921482429289, "z": null, "yaw": 3.167283983101646, "pitch": null, "roll": null}, "v": 2.1226465061209043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35118860720551803, "steering_wheel_angle": -0.5363464105353289, "front_wheel_angle": -0.024806816979371784, "heading_rate": -0.020573010620095547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.489027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24040263269333484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4426151603240256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1137905652279483, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.489027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.509027, "x": 10.459539216885268, "y": 4.914759600345582, "z": null, "yaw": 3.16609095250424, "pitch": null, "roll": null}, "v": 2.1118343845002836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501901639005911, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.02362092228394411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.509027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23006533261553183, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3408132138135824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1118343845002836, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.509027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 6.459539216885268, "y": -0.08524039965441776, "z": null, "yaw": 3.16609095250424, "pitch": null, "roll": null}, "v": 2.1118343845002836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501901639005911, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.02362092228394411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.529027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23324581880988818, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3408132138135824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1085902443697533, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.529027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 6.459539216885268, "y": -0.08524039965441776, "z": null, "yaw": 3.16609095250424, "pitch": null, "roll": null}, "v": 2.1118343845002836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501901639005911, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.02362092228394411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.549027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23324581880988818, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3408132138135824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1057494605153697, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.549027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 6.459539216885268, "y": -0.08524039965441776, "z": null, "yaw": 3.16609095250424, "pitch": null, "roll": null}, "v": 2.1118343845002836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501901639005911, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.02362092228394411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.569027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23324581880988818, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3408132138135824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102913908632648, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.569027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 6.459539216885268, "y": -0.08524039965441776, "z": null, "yaw": 3.16609095250424, "pitch": null, "roll": null}, "v": 2.1118343845002836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501901639005911, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.02362092228394411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.589027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23324581880988818, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3408132138135824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0972584494213167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.589027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 6.459539216885268, "y": -0.08524039965441776, "z": null, "yaw": 3.16609095250424, "pitch": null, "roll": null}, "v": 2.1118343845002836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501901639005911, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.02362092228394411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.609027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23324581880988818, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3408132138135824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095847834571857, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.609027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.619027, "x": 10.228122458662758, "y": 4.909218467439057, "z": null, "yaw": 3.1648605996554053, "pitch": null, "roll": null}, "v": 2.095847834571857, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487181731853883, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023442112308967256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.629027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23959158724840462, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4208338460346415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0924166211373163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.629027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 6.228122458662758, "y": -0.09078153256094268, "z": null, "yaw": 3.1648605996554053, "pitch": null, "roll": null}, "v": 2.095847834571857, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487181731853883, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023442112308967256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.6490269} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23753493372716097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4208338460346415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0924166211373163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.6490269} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 6.228122458662758, "y": -0.09078153256094268, "z": null, "yaw": 3.1648605996554053, "pitch": null, "roll": null}, "v": 2.095847834571857, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487181731853883, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023442112308967256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.6790268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23753493372716097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4208338460346415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087870504682112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.6790268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 6.228122458662758, "y": -0.09078153256094268, "z": null, "yaw": 3.1648605996554053, "pitch": null, "roll": null}, "v": 2.095847834571857, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487181731853883, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023442112308967256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.6990268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23753493372716097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4208338460346415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0867365824632866, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.6990268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 6.228122458662758, "y": -0.09078153256094268, "z": null, "yaw": 3.1648605996554053, "pitch": null, "roll": null}, "v": 2.095847834571857, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487181731853883, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023442112308967256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.7190268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23753493372716097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4208338460346415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0844718578016197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.7190268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.7290268, "x": 9.998269372888142, "y": 4.9039977681080105, "z": null, "yaw": 3.1636302468065707, "pitch": null, "roll": null}, "v": 2.08334105293807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475701520754746, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023302223632486664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.7390268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429591543090333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5081422370560649, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0822112847752625, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.7390268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 5.998269372888142, "y": -0.09600223189198953, "z": null, "yaw": 3.1636302468065707, "pitch": null, "roll": null}, "v": 2.08334105293807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475701520754746, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023302223632486664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.7690268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2412066831726929, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5081422370560649, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.079056748115772, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7001009318693607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.7690268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 5.998269372888142, "y": -0.09600223189198953, "z": null, "yaw": 3.1636302468065707, "pitch": null, "roll": null}, "v": 2.08334105293807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475701520754746, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023302223632486664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.7890267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2412066831726929, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5081422370560649, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0763701345322776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7001009318693607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.7890267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 5.998269372888142, "y": -0.09600223189198953, "z": null, "yaw": 3.1636302468065707, "pitch": null, "roll": null}, "v": 2.08334105293807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475701520754746, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023302223632486664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.8090267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2412066831726929, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5081422370560649, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0763701345322776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7001009318693607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.8090267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.8390267, "x": 9.76963830264216, "y": 4.899096233894086, "z": null, "yaw": 3.162272736161935, "pitch": null, "roll": null}, "v": 2.0736908918833667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3466864837449687, "steering_wheel_angle": -0.7001009318693607, "front_wheel_angle": -0.03245197622124179, "heading_rate": -0.02629648479552359, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.8390267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24611675388711673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6002629697488995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0736908918833667, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7001009318693607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.8390267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 5.769638302642161, "y": -0.10090376610591356, "z": null, "yaw": 3.162272736161935, "pitch": null, "roll": null}, "v": 2.0736908918833667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3466864837449687, "steering_wheel_angle": -0.7001009318693607, "front_wheel_angle": -0.03245197622124179, "heading_rate": -0.02629648479552359, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.8590267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453817233733527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6002629697488995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0725222911365955, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.8590267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 5.769638302642161, "y": -0.10090376610591356, "z": null, "yaw": 3.162272736161935, "pitch": null, "roll": null}, "v": 2.0736908918833667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3466864837449687, "steering_wheel_angle": -0.7001009318693607, "front_wheel_angle": -0.03245197622124179, "heading_rate": -0.02629648479552359, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.8790267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453817233733527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6002629697488995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0711585944502198, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.8790267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 5.769638302642161, "y": -0.10090376610591356, "z": null, "yaw": 3.162272736161935, "pitch": null, "roll": null}, "v": 2.0736908918833667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3466864837449687, "steering_wheel_angle": -0.7001009318693607, "front_wheel_angle": -0.03245197622124179, "heading_rate": -0.02629648479552359, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.8990266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453817233733527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6002629697488995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0697973902794526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.8990266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 5.769638302642161, "y": -0.10090376610591356, "z": null, "yaw": 3.162272736161935, "pitch": null, "roll": null}, "v": 2.0736908918833667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3466864837449687, "steering_wheel_angle": -0.7001009318693607, "front_wheel_angle": -0.03245197622124179, "heading_rate": -0.02629648479552359, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.9190266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453817233733527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6002629697488995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0684386733277518, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.9190266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 5.769638302642161, "y": -0.10090376610591356, "z": null, "yaw": 3.162272736161935, "pitch": null, "roll": null}, "v": 2.0736908918833667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3466864837449687, "steering_wheel_angle": -0.7001009318693607, "front_wheel_angle": -0.03245197622124179, "heading_rate": -0.02629648479552359, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.9390266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453817233733527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6002629697488995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0670824383123136, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.9390266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.9490266, "x": 9.541933909912263, "y": 4.894543532283016, "z": null, "yaw": 3.160735299162871, "pitch": null, "roll": null}, "v": 2.0664052498835632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3460205690616417, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02930428921632393, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.9590266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24723613403301442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5642606126905148, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0657286799640304, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.9590266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 5.541933909912263, "y": -0.10545646771698358, "z": null, "yaw": 3.160735299162871, "pitch": null, "roll": null}, "v": 2.0664052498835632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3460205690616417, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02930428921632393, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.9790266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2463597246943296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5642606126905148, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0647144842823435, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.9790266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 5.541933909912263, "y": -0.10545646771698358, "z": null, "yaw": 3.160735299162871, "pitch": null, "roll": null}, "v": 2.0664052498835632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3460205690616417, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02930428921632393, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.9990265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2463597246943296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5642606126905148, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0635926384974566, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.9990265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 5.541933909912263, "y": -0.10545646771698358, "z": null, "yaw": 3.160735299162871, "pitch": null, "roll": null}, "v": 2.0664052498835632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3460205690616417, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02930428921632393, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.0190265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2463597246943296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5642606126905148, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0624728397626724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.0190265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 5.541933909912263, "y": -0.10545646771698358, "z": null, "yaw": 3.160735299162871, "pitch": null, "roll": null}, "v": 2.0664052498835632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3460205690616417, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02930428921632393, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.0390265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2463597246943296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5642606126905148, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0613550838413555, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.0390265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.0590265, "x": 9.3149786312174, "y": 4.890359373205331, "z": null, "yaw": 3.1591753574167, "pitch": null, "roll": null}, "v": 2.0602393665073415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34545783079843284, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029216849044682327, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.0590265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24876009238625021, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.506624136695576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0602393665073415, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.0590265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.3149786312174, "y": -0.10964062679466924, "z": null, "yaw": 3.1591753574167, "pitch": null, "roll": null}, "v": 2.0602393665073415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34545783079843284, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029216849044682327, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.0790265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2479818400591026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.506624136695576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.059425592692722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.0790265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.3149786312174, "y": -0.10964062679466924, "z": null, "yaw": 3.1591753574167, "pitch": null, "roll": null}, "v": 2.0602393665073415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34545783079843284, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029216849044682327, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.0990264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2479818400591026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.506624136695576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.058516065213789, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.0990264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.3149786312174, "y": -0.10964062679466924, "z": null, "yaw": 3.1591753574167, "pitch": null, "roll": null}, "v": 2.0602393665073415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34545783079843284, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029216849044682327, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.1190264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2479818400591026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.506624136695576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0576081954997902, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.1190264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.3149786312174, "y": -0.10964062679466924, "z": null, "yaw": 3.1591753574167, "pitch": null, "roll": null}, "v": 2.0602393665073415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34545783079843284, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029216849044682327, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.1390264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2479818400591026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.506624136695576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.056701980199633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.1390264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.3149786312174, "y": -0.10964062679466924, "z": null, "yaw": 3.1591753574167, "pitch": null, "roll": null}, "v": 2.0602393665073415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34545783079843284, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029216849044682327, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.1590264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2479818400591026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.506624136695576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0557974159701327, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.1590264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.1690264, "x": 9.088625304328671, "y": 4.886539536408867, "z": null, "yaw": 3.157615415670529, "pitch": null, "roll": null}, "v": 2.0553457519642904, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3450117491993911, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029147451284542655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.1790264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503329968032518, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4483131087366197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0548944994759903, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.1790264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 5.088625304328671, "y": -0.11346046359113338, "z": null, "yaw": 3.157615415670529, "pitch": null, "roll": null}, "v": 2.0553457519642904, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3450117491993911, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029147451284542655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.1990263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24957595574439825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4483131087366197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.054286988127994, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.1990263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 5.088625304328671, "y": -0.11346046359113338, "z": null, "yaw": 3.157615415670529, "pitch": null, "roll": null}, "v": 2.0553457519642904, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3450117491993911, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029147451284542655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.2190263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24957595574439825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4483131087366197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0535859959870972, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.2190263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 5.088625304328671, "y": -0.11346046359113338, "z": null, "yaw": 3.157615415670529, "pitch": null, "roll": null}, "v": 2.0553457519642904, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3450117491993911, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029147451284542655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.2390263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24957595574439825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4483131087366197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0528862801251084, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.2390263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 5.088625304328671, "y": -0.11346046359113338, "z": null, "yaw": 3.157615415670529, "pitch": null, "roll": null}, "v": 2.0553457519642904, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3450117491993911, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029147451284542655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.2590263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24957595574439825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4483131087366197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0521878380225864, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.2590263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.2790263, "x": 8.862758551748229, "y": 4.883080356919626, "z": null, "yaw": 3.156055473924358, "pitch": null, "roll": null}, "v": 2.0514906671657465, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3446606729329689, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029092781214431117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.2790263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25348470513479293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5161842336067324, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0514906671657465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.2790263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 4.862758551748229, "y": -0.11691964308037406, "z": null, "yaw": 3.156055473924358, "pitch": null, "roll": null}, "v": 2.0514906671657465, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3446606729329689, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029092781214431117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.2990263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25224566632459633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5161842336067324, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0512831363483275, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.2990263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 4.862758551748229, "y": -0.11691964308037406, "z": null, "yaw": 3.156055473924358, "pitch": null, "roll": null}, "v": 2.0514906671657465, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3446606729329689, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029092781214431117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.3190262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25224566632459633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5161842336067324, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0509211738125908, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.3190262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 4.862758551748229, "y": -0.11691964308037406, "z": null, "yaw": 3.156055473924358, "pitch": null, "roll": null}, "v": 2.0514906671657465, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3446606729329689, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029092781214431117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.3390262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25224566632459633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5161842336067324, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0505598698952743, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.3390262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 4.862758551748229, "y": -0.11691964308037406, "z": null, "yaw": 3.156055473924358, "pitch": null, "roll": null}, "v": 2.0514906671657465, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3446606729329689, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029092781214431117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.3590262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25224566632459633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5161842336067324, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0501992233457793, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.3590262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 4.862758551748229, "y": -0.11691964308037406, "z": null, "yaw": 3.156055473924358, "pitch": null, "roll": null}, "v": 2.0514906671657465, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3446606729329689, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029092781214431117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.3790262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25224566632459633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5161842336067324, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.049839232916067, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.3790262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.3890262, "x": 8.63720069758525, "y": 4.879977866978146, "z": null, "yaw": 3.1544955321781867, "pitch": null, "roll": null}, "v": 2.049659483356816, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34449401414498615, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029066812668354217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.3990262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538427412395817, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.416703979074443, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0494798973606536, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.3990262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 4.63720069758525, "y": -0.1200221330218536, "z": null, "yaw": 3.1544955321781867, "pitch": null, "roll": null}, "v": 2.049659483356816, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34449401414498615, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029066812668354217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.4190261} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333532205655973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.416703979074443, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.049320758980309, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.4190261} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 4.63720069758525, "y": -0.1200221330218536, "z": null, "yaw": 3.1544955321781867, "pitch": null, "roll": null}, "v": 2.049659483356816, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34449401414498615, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029066812668354217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.439026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333532205655973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.416703979074443, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0490985115160427, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.439026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 4.63720069758525, "y": -0.1200221330218536, "z": null, "yaw": 3.1544955321781867, "pitch": null, "roll": null}, "v": 2.049659483356816, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34449401414498615, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029066812668354217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.459026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333532205655973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.416703979074443, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.048876668282987, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.459026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 4.63720069758525, "y": -0.1200221330218536, "z": null, "yaw": 3.1544955321781867, "pitch": null, "roll": null}, "v": 2.049659483356816, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34449401414498615, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029066812668354217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.479026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333532205655973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.416703979074443, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0486552285262354, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.479026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.499026, "x": 8.411817492289305, "y": 4.8772294329797, "z": null, "yaw": 3.1529355904320155, "pitch": null, "roll": null}, "v": 2.0484341914923623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3443825359433678, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02904943645080329, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.499026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25668406662421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4822462986418603, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0484341914923623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.499026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.411817492289305, "y": -0.12277056702030009, "z": null, "yaw": 3.1529355904320155, "pitch": null, "roll": null}, "v": 2.0484341914923623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3443825359433678, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02904943645080329, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.519026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25563200934695585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4822462986418603, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.048631959106311, "gear": 1, "accelerator_pedal_position": 0.25668406662421, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.519026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.411817492289305, "y": -0.12277056702030009, "z": null, "yaw": 3.1529355904320155, "pitch": null, "roll": null}, "v": 2.0484341914923623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3443825359433678, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02904943645080329, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.539026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25563200934695585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4822462986418603, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.048697919717983, "gear": 1, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.539026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.411817492289305, "y": -0.12277056702030009, "z": null, "yaw": 3.1529355904320155, "pitch": null, "roll": null}, "v": 2.0484341914923623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3443825359433678, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02904943645080329, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.559026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25563200934695585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4822462986418603, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0487637603707216, "gear": 1, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.559026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.411817492289305, "y": -0.12277056702030009, "z": null, "yaw": 3.1529355904320155, "pitch": null, "roll": null}, "v": 2.0484341914923623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3443825359433678, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02904943645080329, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.579026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25563200934695585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4822462986418603, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.048829481280956, "gear": 1, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.579026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.411817492289305, "y": -0.12277056702030009, "z": null, "yaw": 3.1529355904320155, "pitch": null, "roll": null}, "v": 2.0484341914923623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3443825359433678, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02904943645080329, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.599026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25563200934695585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4822462986418603, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0488950826647323, "gear": 1, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.599026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.609026, "x": 8.186471853868161, "y": 4.874833052327029, "z": null, "yaw": 3.1513756486858444, "pitch": null, "roll": null}, "v": 2.048927838601608, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "acceleration": 0.0032726136104269665, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029056437002926816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.619026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25701814895908626, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3614222017331137, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0489605647377123, "gear": 1, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.619026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 4.186471853868161, "y": -0.12516694767297132, "z": null, "yaw": 3.1513756486858444, "pitch": null, "roll": null}, "v": 2.048927838601608, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "acceleration": 0.0032726136104269665, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029056437002926816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.639026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25658722549099405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3614222017331137, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0491991163466934, "gear": 1, "accelerator_pedal_position": 0.25701814895908626, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.639026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 4.186471853868161, "y": -0.12516694767297132, "z": null, "yaw": 3.1513756486858444, "pitch": null, "roll": null}, "v": 2.048927838601608, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "acceleration": 0.0032726136104269665, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029056437002926816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.659026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25658722549099405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3614222017331137, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.049383393142846, "gear": 1, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.659026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 4.186471853868161, "y": -0.12516694767297132, "z": null, "yaw": 3.1513756486858444, "pitch": null, "roll": null}, "v": 2.048927838601608, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "acceleration": 0.0032726136104269665, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029056437002926816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.679026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25658722549099405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3614222017331137, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0495673347566328, "gear": 1, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.679026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 4.186471853868161, "y": -0.12516694767297132, "z": null, "yaw": 3.1513756486858444, "pitch": null, "roll": null}, "v": 2.048927838601608, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "acceleration": 0.0032726136104269665, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029056437002926816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.6990259} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25658722549099405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3614222017331137, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0497509417841915, "gear": 1, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.6990259} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.7190259, "x": 7.961049781053775, "y": 4.872787546667662, "z": null, "yaw": 3.1498157069396733, "pitch": null, "roll": null}, "v": 2.049934214820649, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "acceleration": 0.009151145726756793, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029070708714530758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.7190259} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2594578340220016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.418183865205936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.049934214820649, "gear": 1, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.7190259} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 3.9610497810537746, "y": -0.127212453332338, "z": null, "yaw": 3.1498157069396733, "pitch": null, "roll": null}, "v": 2.049934214820649, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "acceleration": 0.009151145726756793, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029070708714530758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.7390258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585653467100969, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.418183865205936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.050690468409536, "gear": 1, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.7390258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 3.9610497810537746, "y": -0.127212453332338, "z": null, "yaw": 3.1498157069396733, "pitch": null, "roll": null}, "v": 2.049934214820649, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "acceleration": 0.009151145726756793, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029070708714530758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.7490258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585653467100969, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.418183865205936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.050690468409536, "gear": 1, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.7490258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 3.9610497810537746, "y": -0.127212453332338, "z": null, "yaw": 3.1498157069396733, "pitch": null, "roll": null}, "v": 2.049934214820649, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "acceleration": 0.009151145726756793, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029070708714530758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.7790258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585653467100969, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.418183865205936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0513332503974007, "gear": 1, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.7790258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 3.9610497810537746, "y": -0.127212453332338, "z": null, "yaw": 3.1498157069396733, "pitch": null, "roll": null}, "v": 2.049934214820649, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "acceleration": 0.009151145726756793, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029070708714530758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.7990258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585653467100969, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.418183865205936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.051760797180958, "gear": 1, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.7990258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 3.9610497810537746, "y": -0.127212453332338, "z": null, "yaw": 3.1498157069396733, "pitch": null, "roll": null}, "v": 2.049934214820649, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "acceleration": 0.009151145726756793, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029070708714530758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.8190258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585653467100969, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.418183865205936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0521875659008364, "gear": 1, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.8190258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.8290257, "x": 7.735434845122841, "y": 4.871092281151316, "z": null, "yaw": 3.148255765193502, "pitch": null, "roll": null}, "v": 2.0524006589067034, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "acceleration": 0.021289899345963648, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02910568606993464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.8390257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26005827962308226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.299408979343113, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.052919571355848, "gear": 1, "accelerator_pedal_position": 0.26005827962308226, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.8390257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 3.7354348451228407, "y": -0.12890771884868357, "z": null, "yaw": 3.148255765193502, "pitch": null, "roll": null}, "v": 2.0524006589067034, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "acceleration": 0.021289899345963648, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02910568606993464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.8590257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596029629892548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.299408979343113, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0532253061699675, "gear": 1, "accelerator_pedal_position": 0.26005827962308226, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.8590257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 3.7354348451228407, "y": -0.12890771884868357, "z": null, "yaw": 3.148255765193502, "pitch": null, "roll": null}, "v": 2.0524006589067034, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "acceleration": 0.021289899345963648, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02910568606993464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.8790257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596029629892548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.299408979343113, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.053779052150323, "gear": 1, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.8790257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 3.7354348451228407, "y": -0.12890771884868357, "z": null, "yaw": 3.148255765193502, "pitch": null, "roll": null}, "v": 2.0524006589067034, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "acceleration": 0.021289899345963648, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02910568606993464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.8990257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596029629892548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.299408979343113, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0543317899659095, "gear": 1, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.8990257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 3.7354348451228407, "y": -0.12890771884868357, "z": null, "yaw": 3.148255765193502, "pitch": null, "roll": null}, "v": 2.0524006589067034, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "acceleration": 0.021289899345963648, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02910568606993464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.9190257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596029629892548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.299408979343113, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0548835213300656, "gear": 1, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.9190257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.9390256, "x": 7.509524090968997, "y": 4.869747225509921, "z": null, "yaw": 3.146695823447331, "pitch": null, "roll": null}, "v": 2.0554342479536793, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "acceleration": 0.027498706808549267, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02914870627170826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.9390256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26151274760661714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2243319182604433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0554342479536793, "gear": 1, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.9390256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5095240909689966, "y": -0.13025277449007877, "z": null, "yaw": 3.146695823447331, "pitch": null, "roll": null}, "v": 2.0554342479536793, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "acceleration": 0.027498706808549267, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02914870627170826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.9590256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609297542455587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2243319182604433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.05622258586564, "gear": 1, "accelerator_pedal_position": 0.26151274760661714, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.9590256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5095240909689966, "y": -0.13025277449007877, "z": null, "yaw": 3.146695823447331, "pitch": null, "roll": null}, "v": 2.0554342479536793, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "acceleration": 0.027498706808549267, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02914870627170826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.9790256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609297542455587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2243319182604433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0569366467928267, "gear": 1, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.9790256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5095240909689966, "y": -0.13025277449007877, "z": null, "yaw": 3.146695823447331, "pitch": null, "roll": null}, "v": 2.0554342479536793, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "acceleration": 0.027498706808549267, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02914870627170826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.9990256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609297542455587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2243319182604433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.057649406791934, "gear": 1, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.9990256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5095240909689966, "y": -0.13025277449007877, "z": null, "yaw": 3.146695823447331, "pitch": null, "roll": null}, "v": 2.0554342479536793, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "acceleration": 0.027498706808549267, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02914870627170826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.0190256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609297542455587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2243319182604433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0583608680299688, "gear": 1, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.0190256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5095240909689966, "y": -0.13025277449007877, "z": null, "yaw": 3.146695823447331, "pitch": null, "roll": null}, "v": 2.0554342479536793, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "acceleration": 0.027498706808549267, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02914870627170826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.0390255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609297542455587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2243319182604433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0590710326710995, "gear": 1, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.0390255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.0490255, "x": 7.283225320551954, "y": 4.86875289477284, "z": null, "yaw": 3.14513588170116, "pitch": null, "roll": null}, "v": 2.0594256294433526, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "acceleration": 0.03542734333049269, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029205309204532136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.0590255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26327425505324137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669337560076297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0597799028766577, "gear": 1, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.0590255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": 3.2832253205519537, "y": -0.13124710522716043, "z": null, "yaw": 3.14513588170116, "pitch": null, "roll": null}, "v": 2.0594256294433526, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "acceleration": 0.03542734333049269, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029205309204532136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.0790255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625597885238976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669337560076297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.060780409763482, "gear": 1, "accelerator_pedal_position": 0.26327425505324137, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.0790255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": 3.2832253205519537, "y": -0.13124710522716043, "z": null, "yaw": 3.14513588170116, "pitch": null, "roll": null}, "v": 2.0594256294433526, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "acceleration": 0.03542734333049269, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029205309204532136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.0990255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625597885238976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669337560076297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.061689824765585, "gear": 1, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.0990255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": 3.2832253205519537, "y": -0.13124710522716043, "z": null, "yaw": 3.14513588170116, "pitch": null, "roll": null}, "v": 2.0594256294433526, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "acceleration": 0.03542734333049269, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029205309204532136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.1190255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625597885238976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669337560076297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0625975812196504, "gear": 1, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.1190255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": 3.2832253205519537, "y": -0.13124710522716043, "z": null, "yaw": 3.14513588170116, "pitch": null, "roll": null}, "v": 2.0594256294433526, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "acceleration": 0.03542734333049269, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029205309204532136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.1390254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625597885238976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669337560076297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.063503681821001, "gear": 1, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.1390254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.1590254, "x": 7.056441817977197, "y": 4.868110222961941, "z": null, "yaw": 3.1435759399549887, "pitch": null, "roll": null}, "v": 2.0644081292618455, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "acceleration": 0.04516046256964379, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029275967472415277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.1590254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26438805311620167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1851661774740831, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0644081292618455, "gear": 1, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.1590254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.0564418179771966, "y": -0.13188977703805893, "z": null, "yaw": 3.1435759399549887, "pitch": null, "roll": null}, "v": 2.0644081292618455, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "acceleration": 0.04516046256964379, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029275967472415277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.1790254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26383944982143764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1851661774740831, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.065539354981868, "gear": 1, "accelerator_pedal_position": 0.26438805311620167, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.1790254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.0564418179771966, "y": -0.13188977703805893, "z": null, "yaw": 3.1435759399549887, "pitch": null, "roll": null}, "v": 2.0644081292618455, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "acceleration": 0.04516046256964379, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029275967472415277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.1990254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26383944982143764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1851661774740831, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.066599971811044, "gear": 1, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.1990254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.0564418179771966, "y": -0.13188977703805893, "z": null, "yaw": 3.1435759399549887, "pitch": null, "roll": null}, "v": 2.0644081292618455, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "acceleration": 0.04516046256964379, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029275967472415277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.2190254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26383944982143764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1851661774740831, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.067658652272264, "gear": 1, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.2190254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.0564418179771966, "y": -0.13188977703805893, "z": null, "yaw": 3.1435759399549887, "pitch": null, "roll": null}, "v": 2.0644081292618455, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "acceleration": 0.04516046256964379, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029275967472415277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.2390254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26383944982143764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1851661774740831, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.068715399452637, "gear": 1, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.2390254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.0564418179771966, "y": -0.13188977703805893, "z": null, "yaw": 3.1435759399549887, "pitch": null, "roll": null}, "v": 2.0644081292618455, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "acceleration": 0.04516046256964379, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029275967472415277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.2590253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26383944982143764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1851661774740831, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.069770216436089, "gear": 1, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.2590253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.2690253, "x": 6.829059070324234, "y": 4.867820569976216, "z": null, "yaw": 3.1420159982088176, "pitch": null, "roll": null}, "v": 2.0702969020668265, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "acceleration": 0.05262042365356889, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029359477859071576, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.2790253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2657667631807842, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1815199681884194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.070823106303362, "gear": 1, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.2790253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": 2.8290590703242344, "y": -0.1321794300237844, "z": null, "yaw": 3.1420159982088176, "pitch": null, "roll": null}, "v": 2.0702969020668265, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "acceleration": 0.05262042365356889, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029359477859071576, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.2990253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26519137348001853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1815199681884194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0721148761702017, "gear": 1, "accelerator_pedal_position": 0.2657667631807842, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.2990253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": 2.8290590703242344, "y": -0.1321794300237844, "z": null, "yaw": 3.1420159982088176, "pitch": null, "roll": null}, "v": 2.0702969020668265, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "acceleration": 0.05262042365356889, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029359477859071576, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.3190253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26519137348001853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1815199681884194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.073332394012142, "gear": 1, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.3190253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": 2.8290590703242344, "y": -0.1321794300237844, "z": null, "yaw": 3.1420159982088176, "pitch": null, "roll": null}, "v": 2.0702969020668265, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "acceleration": 0.05262042365356889, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029359477859071576, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.3390253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26519137348001853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1815199681884194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0745476857753284, "gear": 1, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.3390253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": 2.8290590703242344, "y": -0.1321794300237844, "z": null, "yaw": 3.1420159982088176, "pitch": null, "roll": null}, "v": 2.0702969020668265, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "acceleration": 0.05262042365356889, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029359477859071576, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.3590252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26519137348001853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1815199681884194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0757607549393624, "gear": 1, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.3590252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.3790252, "x": 6.600993800668712, "y": 4.867885828093091, "z": null, "yaw": 3.1404560564626465, "pitch": null, "roll": null}, "v": 2.076971604980723, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "acceleration": 0.060459393522117544, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029454133747423047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.3790252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26723570072053715, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9627700895276374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.076971604980723, "gear": 1, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.3790252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.6009938006687117, "y": -0.13211417190690877, "z": null, "yaw": 3.1404560564626465, "pitch": null, "roll": null}, "v": 2.076971604980723, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "acceleration": 0.060459393522117544, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029454133747423047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.3990252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666273757089052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9627700895276374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.078435663300393, "gear": 1, "accelerator_pedal_position": 0.26723570072053715, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.3990252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.6009938006687117, "y": -0.13211417190690877, "z": null, "yaw": 3.1404560564626465, "pitch": null, "roll": null}, "v": 2.076971604980723, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "acceleration": 0.060459393522117544, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029454133747423047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.4190252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666273757089052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9627700895276374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0798210360168414, "gear": 1, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.4190252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.6009938006687117, "y": -0.13211417190690877, "z": null, "yaw": 3.1404560564626465, "pitch": null, "roll": null}, "v": 2.076971604980723, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "acceleration": 0.060459393522117544, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029454133747423047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.4390252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666273757089052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9627700895276374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0812038721837984, "gear": 1, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.4390252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.6009938006687117, "y": -0.13211417190690877, "z": null, "yaw": 3.1404560564626465, "pitch": null, "roll": null}, "v": 2.076971604980723, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "acceleration": 0.060459393522117544, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029454133747423047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.4590251} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666273757089052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9627700895276374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.082584175681017, "gear": 1, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.4590251} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.6009938006687117, "y": -0.13211417190690877, "z": null, "yaw": 3.1404560564626465, "pitch": null, "roll": null}, "v": 2.076971604980723, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "acceleration": 0.060459393522117544, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029454133747423047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.4790251} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666273757089052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9627700895276374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083961950385346, "gear": 1, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.4790251} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.489025, "x": 6.372139299384786, "y": 4.868308325141296, "z": null, "yaw": 3.1388961147164753, "pitch": null, "roll": null}, "v": 2.0846498906508946, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "acceleration": 0.06873095198220491, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02956302173247677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.499025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26907047419084246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8124476433374687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0853372001707164, "gear": 1, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.499025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": 2.372139299384786, "y": -0.13169167485870403, "z": null, "yaw": 3.1388961147164753, "pitch": null, "roll": null}, "v": 2.0846498906508946, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "acceleration": 0.06873095198220491, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02956302173247677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.519025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683421782112517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8124476433374687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0870151761646945, "gear": 1, "accelerator_pedal_position": 0.26907047419084246, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.519025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": 2.372139299384786, "y": -0.13169167485870403, "z": null, "yaw": 3.1388961147164753, "pitch": null, "roll": null}, "v": 2.0846498906508946, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "acceleration": 0.06873095198220491, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02956302173247677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.539025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683421782112517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8124476433374687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0885990798605762, "gear": 1, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.539025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": 2.372139299384786, "y": -0.13169167485870403, "z": null, "yaw": 3.1388961147164753, "pitch": null, "roll": null}, "v": 2.0846498906508946, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "acceleration": 0.06873095198220491, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02956302173247677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.559025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683421782112517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8124476433374687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09018007798158, "gear": 1, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.559025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": 2.372139299384786, "y": -0.13169167485870403, "z": null, "yaw": 3.1388961147164753, "pitch": null, "roll": null}, "v": 2.0846498906508946, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "acceleration": 0.06873095198220491, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02956302173247677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.579025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683421782112517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8124476433374687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.091758174858443, "gear": 1, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.579025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.599025, "x": 6.142396362894166, "y": 4.869090865494373, "z": null, "yaw": 3.137336172970304, "pitch": null, "roll": null}, "v": 2.093333374819455, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "acceleration": 0.07865149889802037, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029686164727537975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.599025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27025174838096877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8219326687541522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093333374819455, "gear": 1, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.599025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 2.142396362894166, "y": -0.13090913450562702, "z": null, "yaw": 3.137336172970304, "pitch": null, "roll": null}, "v": 2.093333374819455, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "acceleration": 0.07865149889802037, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029686164727537975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.619025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2696948557739975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8219326687541522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095144268800307, "gear": 1, "accelerator_pedal_position": 0.27025174838096877, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.619025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 2.142396362894166, "y": -0.13090913450562702, "z": null, "yaw": 3.137336172970304, "pitch": null, "roll": null}, "v": 2.093333374819455, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "acceleration": 0.07865149889802037, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029686164727537975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.639025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2696948557739975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8219326687541522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09775005236647, "gear": 1, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.639025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 2.142396362894166, "y": -0.13090913450562702, "z": null, "yaw": 3.137336172970304, "pitch": null, "roll": null}, "v": 2.093333374819455, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "acceleration": 0.07865149889802037, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029686164727537975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.659025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2696948557739975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8219326687541522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098617050297941, "gear": 1, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.659025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 2.142396362894166, "y": -0.13090913450562702, "z": null, "yaw": 3.137336172970304, "pitch": null, "roll": null}, "v": 2.093333374819455, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "acceleration": 0.07865149889802037, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029686164727537975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.679025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2696948557739975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8219326687541522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1003486547746246, "gear": 1, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.679025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 2.142396362894166, "y": -0.13090913450562702, "z": null, "yaw": 3.137336172970304, "pitch": null, "roll": null}, "v": 2.093333374819455, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "acceleration": 0.07865149889802037, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029686164727537975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.699025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2696948557739975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8219326687541522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102077074623138, "gear": 1, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.699025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.709025, "x": 5.911648210080921, "y": 4.870236801262151, "z": null, "yaw": 3.135776231224133, "pitch": null, "roll": null}, "v": 2.1029400917689354, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "acceleration": 0.08622227370334612, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02982240035311181, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.719025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2717660064841811, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7765949610215995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1038023145059688, "gear": 1, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.719025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.11993789672852, "x": 1.9116482100809211, "y": -0.12976319873784892, "z": null, "yaw": 3.135776231224133, "pitch": null, "roll": null}, "v": 2.1029400917689354, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "acceleration": 0.08622227370334612, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02982240035311181, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.7390249} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711629444899422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7765949610215995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.10578315370881, "gear": 1, "accelerator_pedal_position": 0.2717660064841811, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.7390249} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.11993789672852, "x": 1.9116482100809211, "y": -0.12976319873784892, "z": null, "yaw": 3.135776231224133, "pitch": null, "roll": null}, "v": 2.1029400917689354, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "acceleration": 0.08622227370334612, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02982240035311181, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.7590249} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711629444899422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7765949610215995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107684997636004, "gear": 1, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.7590249} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.11993789672852, "x": 1.9116482100809211, "y": -0.12976319873784892, "z": null, "yaw": 3.135776231224133, "pitch": null, "roll": null}, "v": 2.1029400917689354, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "acceleration": 0.08622227370334612, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02982240035311181, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.7790248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711629444899422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7765949610215995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110531196476091, "gear": 1, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.7790248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.11993789672852, "x": 1.9116482100809211, "y": -0.12976319873784892, "z": null, "yaw": 3.135776231224133, "pitch": null, "roll": null}, "v": 2.1029400917689354, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "acceleration": 0.08622227370334612, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02982240035311181, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.7990248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711629444899422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7765949610215995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1114781807153444, "gear": 1, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.7990248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.8190248, "x": 5.679809271786361, "y": 4.871749833344935, "z": null, "yaw": 3.134216289477962, "pitch": null, "roll": null}, "v": 2.1133695298908504, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "acceleration": 0.09443661886888549, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029970303225070525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.8190248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726857510299599, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7817214222221757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1133695298908504, "gear": 1, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.8190248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.22993779182434, "x": 1.679809271786361, "y": -0.12825016665506528, "z": null, "yaw": 3.134216289477962, "pitch": null, "roll": null}, "v": 2.1133695298908504, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "acceleration": 0.09443661886888549, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029970303225070525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.8390248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27225793417116156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7817214222221757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1154476538197593, "gear": 1, "accelerator_pedal_position": 0.2726857510299599, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.8390248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.22993779182434, "x": 1.679809271786361, "y": -0.12825016665506528, "z": null, "yaw": 3.134216289477962, "pitch": null, "roll": null}, "v": 2.1133695298908504, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "acceleration": 0.09443661886888549, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029970303225070525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.8690248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27225793417116156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7817214222221757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118477510301621, "gear": 1, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.8690248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27225793417116156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7817214222221757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1204927539029312, "gear": 1, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.8790247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.22993779182434, "x": 1.679809271786361, "y": -0.12825016665506528, "z": null, "yaw": 3.134216289477962, "pitch": null, "roll": null}, "v": 2.1133695298908504, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "acceleration": 0.09443661886888549, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029970303225070525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.8990247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27225793417116156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7817214222221757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121498979459742, "gear": 1, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.8990247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.22993779182434, "x": 1.679809271786361, "y": -0.12825016665506528, "z": null, "yaw": 3.134216289477962, "pitch": null, "roll": null}, "v": 2.1133695298908504, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "acceleration": 0.09443661886888549, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029970303225070525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.9190247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27225793417116156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7817214222221757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.123508641372124, "gear": 1, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.9190247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.9290247, "x": 5.446785703132062, "y": 4.873634127681411, "z": null, "yaw": 3.132656347731791, "pitch": null, "roll": null}, "v": 2.1245120790421375, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "acceleration": 0.10025096887769336, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.0301283189303417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.9390247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27356373840500936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7868144310045057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1255145887309146, "gear": 1, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.9390247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.33993768692017, "x": 1.4467857031320621, "y": -0.12636587231858876, "z": null, "yaw": 3.132656347731791, "pitch": null, "roll": null}, "v": 2.1245120790421375, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "acceleration": 0.10025096887769336, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.0301283189303417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.9590247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2732071411230692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7868144310045057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127679976805122, "gear": 1, "accelerator_pedal_position": 0.27356373840500936, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.9590247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.33993768692017, "x": 1.4467857031320621, "y": -0.12636587231858876, "z": null, "yaw": 3.132656347731791, "pitch": null, "roll": null}, "v": 2.1245120790421375, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "acceleration": 0.10025096887769336, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.0301283189303417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.9790246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2732071411230692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7868144310045057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.129796804885952, "gear": 1, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.9790246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.33993768692017, "x": 1.4467857031320621, "y": -0.12636587231858876, "z": null, "yaw": 3.132656347731791, "pitch": null, "roll": null}, "v": 2.1245120790421375, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "acceleration": 0.10025096887769336, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.0301283189303417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.9990246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2732071411230692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7868144310045057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1319097150360857, "gear": 1, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.9990246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.33993768692017, "x": 1.4467857031320621, "y": -0.12636587231858876, "z": null, "yaw": 3.132656347731791, "pitch": null, "roll": null}, "v": 2.1245120790421375, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "acceleration": 0.10025096887769336, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.0301283189303417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.0190246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2732071411230692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7868144310045057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134018712722095, "gear": 1, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.0190246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502704.0390246, "x": 5.2125200385432535, "y": 4.875893942042104, "z": null, "yaw": 3.1310964059856197, "pitch": null, "roll": null}, "v": 2.136123803410344, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "acceleration": 0.10510819281370254, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03029298814476871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.0390246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2770130571065915, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6087644269773461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.136123803410344, "gear": 1, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.0390246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 1.2125200385432535, "y": -0.12410605795789564, "z": null, "yaw": 3.1310964059856197, "pitch": null, "roll": null}, "v": 2.136123803410344, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "acceleration": 0.10510819281370254, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03029298814476871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.0590246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2758774735928649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6087644269773461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.138700511450508, "gear": 1, "accelerator_pedal_position": 0.2770130571065915, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.0590246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 1.2125200385432535, "y": -0.12410605795789564, "z": null, "yaw": 3.1310964059856197, "pitch": null, "roll": null}, "v": 2.136123803410344, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "acceleration": 0.10510819281370254, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03029298814476871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.0790246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2758774735928649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6087644269773461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1423438920780025, "gear": 1, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.0790246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 1.2125200385432535, "y": -0.12410605795789564, "z": null, "yaw": 3.1310964059856197, "pitch": null, "roll": null}, "v": 2.136123803410344, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "acceleration": 0.10510819281370254, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03029298814476871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.0990245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2758774735928649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6087644269773461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.143556098496325, "gear": 1, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.0990245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 1.2125200385432535, "y": -0.12410605795789564, "z": null, "yaw": 3.1310964059856197, "pitch": null, "roll": null}, "v": 2.136123803410344, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "acceleration": 0.10510819281370254, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03029298814476871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.1190245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2758774735928649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6087644269773461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.145977135156481, "gear": 1, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.1190245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 1.2125200385432535, "y": -0.12410605795789564, "z": null, "yaw": 3.1310964059856197, "pitch": null, "roll": null}, "v": 2.136123803410344, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "acceleration": 0.10510819281370254, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03029298814476871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.1390245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2758774735928649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6087644269773461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1496002609839864, "gear": 1, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.1390245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502704.1490245, "x": 4.976879781771614, "y": 4.878534665770392, "z": null, "yaw": 3.1295364642394485, "pitch": null, "roll": null}, "v": 2.1496002609839864, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "acceleration": 0.120546384085982, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03048410167894686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.1490245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2769084232668313, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6044164409441537, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1496002609839864, "gear": 1, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.1490245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.55993747711182, "x": 0.9768797817716139, "y": -0.12146533422960815, "z": null, "yaw": 3.1295364642394485, "pitch": null, "roll": null}, "v": 2.1496002609839864, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "acceleration": 0.120546384085982, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03048410167894686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.1790245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27664882065670526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6044164409441537, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.154656545318069, "gear": 1, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.1790245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.55993747711182, "x": 0.9768797817716139, "y": -0.12146533422960815, "z": null, "yaw": 3.1295364642394485, "pitch": null, "roll": null}, "v": 2.1496002609839864, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "acceleration": 0.120546384085982, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03048410167894686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.1990244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27664882065670526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6044164409441537, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.155905513853626, "gear": 1, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.1990244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.55993747711182, "x": 0.9768797817716139, "y": -0.12146533422960815, "z": null, "yaw": 3.1295364642394485, "pitch": null, "roll": null}, "v": 2.1496002609839864, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "acceleration": 0.120546384085982, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03048410167894686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.2190244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27664882065670526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6044164409441537, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.158399963116161, "gear": 1, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.2190244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.55993747711182, "x": 0.9768797817716139, "y": -0.12146533422960815, "z": null, "yaw": 3.1295364642394485, "pitch": null, "roll": null}, "v": 2.1496002609839864, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "acceleration": 0.120546384085982, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03048410167894686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.2390244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27664882065670526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6044164409441537, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1608897671089426, "gear": 1, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.2390244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502704.2590244, "x": 4.739751137751708, "y": 4.881562032875863, "z": null, "yaw": 3.1279765224932774, "pitch": null, "roll": null}, "v": 2.1633749320040963, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "acceleration": 0.12408447153996571, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.030679444264074224, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.2590244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27753772708048907, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1633749320040963, "gear": 1, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.2590244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.66993737220764, "x": 0.7397511377517079, "y": -0.11843796712413734, "z": null, "yaw": 3.1279765224932774, "pitch": null, "roll": null}, "v": 2.1633749320040963, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "acceleration": 0.12408447153996571, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.030679444264074224, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.2790244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27732408526773306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1659665254486757, "gear": 1, "accelerator_pedal_position": 0.27753772708048907, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.2790244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.66993737220764, "x": 0.7397511377517079, "y": -0.11843796712413734, "z": null, "yaw": 3.1279765224932774, "pitch": null, "roll": null}, "v": 2.1633749320040963, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "acceleration": 0.12408447153996571, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.030679444264074224, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.2990243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27732408526773306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1685265921435737, "gear": 1, "accelerator_pedal_position": 0.27732408526773306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.2990243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.66993737220764, "x": 0.7397511377517079, "y": -0.11843796712413734, "z": null, "yaw": 3.1279765224932774, "pitch": null, "roll": null}, "v": 2.1633749320040963, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "acceleration": 0.12408447153996571, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.030679444264074224, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.3190243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27732408526773306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.171081881029663, "gear": 1, "accelerator_pedal_position": 0.27732408526773306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.3190243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.66993737220764, "x": 0.7397511377517079, "y": -0.11843796712413734, "z": null, "yaw": 3.1279765224932774, "pitch": null, "roll": null}, "v": 2.1633749320040963, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "acceleration": 0.12408447153996571, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.030679444264074224, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.3390243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27732408526773306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.173632398413105, "gear": 1, "accelerator_pedal_position": 0.27732408526773306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.3390243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1761781506029076, "gear": 1, "accelerator_pedal_position": 0.27732408526773306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.3590243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.156178150602908, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.3790243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1361781506029085, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.3990242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.116178150602909, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.4190242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0961781506029094, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.4390242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0761781506029098, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.4590242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.05617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.4790242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0361781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.4990242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.016178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.5190241} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9961781506029113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.539024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9761781506029112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.559024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9561781506029112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.579024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9361781506029112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.599024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9161781506029112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.619024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8961781506029112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.639024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8761781506029112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.659024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8561781506029111, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.679024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8361781506029111, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.699024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.816178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.719024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.796178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.739024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.776178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.759024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.756178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.779024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.736178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.7990239} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.716178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.8190238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.696178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.8390238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.676178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.8590238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.656178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.8790238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.636178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.8990238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.616178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.9190238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.596178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.9390237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5761781506029109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.9590237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5561781506029109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.9790237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5361781506029109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.9990237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5161781506029108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.0190237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4961781506029108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.0390236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4761781506029108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.0590236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4461781506029108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.0790236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4361781506029108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.0990236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4161781506029107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.1190236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3961781506029107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.1390235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3761781506029107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.1590235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3561781506029107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.1790235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3361781506029107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.1990235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3161781506029107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.2190235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2961781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.2390234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2761781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.2590234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2561781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.2790234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2361781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.2990234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2161781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.3190234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1961781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.3390234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1761781506029105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.3590233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1561781506029105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.3790233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1361781506029105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.3990233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1161781506029105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.4190233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0961781506029105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.4390233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0761781506029104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.4590232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0561781506029104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.4790232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0361781506029104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.4990232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0161781506029104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.5190232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9961781506029104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.5390232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9761781506029104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.5590231} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9561781506029103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.5790231} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9361781506029103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.599023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9161781506029103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.619023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8961781506029103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.639023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8761781506029103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.659023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8561781506029102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.679023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8361781506029102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.699023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8161781506029102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.719023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7961781506029102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.739023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7761781506029102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.759023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7561781506029102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.779023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7361781506029101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.799023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7161781506029101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.819023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6961781506029101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.8390229} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6761781506029101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.8590229} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6561781506029101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.8790228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.63617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.8990228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.61617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.9190228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.59617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.9390228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.57617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.9590228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.55617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.9790227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.53617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.9990227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.51617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.0190227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.49617815060290993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.0390227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4761781506029099, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.0590227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4561781506029099, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.0790226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4361781506029099, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.0990226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.41617815060290986, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.1190226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.39617815060290984, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.1390226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3761781506029098, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.1590226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3561781506029098, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.1790226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3361781506029098, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.1990225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.31617815060290977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.2190225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.29617815060290975, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.2390225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.27617815060290973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.2590225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2561781506029097, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.2790225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2361781506029097, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.2990224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.21617815060290968, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.3190224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19617815060290966, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.3390224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17617815060290964, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.3590224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15617815060290963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.3790224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1361781506029096, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.3990223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1161781506029096, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.4190223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09617815060290962, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.4390223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07617815060290963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.4590223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05617815060290963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.4790223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.036178150602909624, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.4990222} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01617815060290962, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.5190222} diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/meta.yaml b/tuning logs/2025-02-13_21-10-39 (fine tuning)/meta.yaml new file mode 100644 index 000000000..0ead3dc69 --- /dev/null +++ b/tuning logs/2025-02-13_21-10-39 (fine tuning)/meta.yaml @@ -0,0 +1,19 @@ +events: +- description: Ctrl+C pressed, switching to recovery mode + time: 1739502705.4840224 + vehicle_time: 1739502704.3390243 +- description: Mission execution ended + time: 1739502707.669565 + vehicle_time: 1739502706.5190222 +exit_reason: normal exit +git_branch: A1_control +git_commit_id: b5cb190b3f6c6cf17344817eca71aa0a5d350394 +pipelines: +- name: drive + time: 1739502639.5759368 + vehicle_time: 1739502638.629087 +- name: recovery + time: 1739502705.4858768 + vehicle_time: 1739502704.3390243 +start_time: 1739502639.3786135 +start_time_human_readable: '2025-02-13 21:10:39' diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/accel.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/accel.png new file mode 100644 index 0000000000000000000000000000000000000000..03e7e6dfe591e02f9edbf45f51a97432eb0b62eb GIT binary patch literal 256695 zcmeFa_dnPBA3m-$l_WDlX%IySQ7Ee=Bcn3Q2ocKOm1L7>$O_pZM7D-qW@KbW_TI_( zUe9_T=bRtDpU>wHIBvJ|KIQOwJztN<{c*ov*LA<{kGF@s>}hf`1~L*767sWWBrlSX zP~eYSPHx(Oe?=eqDvp1xGZ#Orvvyi%M zp=f&D!ur~6J(8Q(EX<5eEsPDdcU$S*Ha9di;p5`r;ytw6z{0{zn4A0W|ITH4Tc3Ns zSHw9IlHDX{B~K~YgbcTxH*WZm^RDY{-HXR+3e-xHTQtY-Df950E8b08Pj7j3-wxJh zkG(p1QXZr}(x)!qSH{wqZ-AU;G{hb~E zJA^w99 zf7anY2=Tvz@gIcvvk?D5i2nt|e-Pr&Laagvvk)a^WvR1g&jw$*aN&Zr-)0ft>I)?E zzc{(MP3LCv3JMBxOV<&aS<7RN2+k~VqJvMyE|)Y>+9>=_JVOwUsjBf z85plNW2;bBRc&dbIR5)-EVle1(kCfq`of({@@%Js^PI-o^HZCY462{!%j z$NVzPx<16Eq>R;vT}i)gS$p)apCDP3`or35B$zII&ebmVY|67Wr;{Ol=kY2!djGj| z=UVd4oj;#zFY~|OI3w}DpC`TfE%We`!)jJa_WIRf8a;-qFL~_IAHx1(<8u*vD{3;= zsFvgURUyYL`sMxE*8cTlo!ox}ggeYJ^6W(+Lgv19E6EzU+U1Y-Oa0>$?A`oFL$G@m zeg0|5?8rC20dIT+8bgM^UWjBl;D7Ju79?ce%M(7)Za-E$R=A>h-;m_RuZH@1$q0Fa zsf2`t!BL(yyL+obzl|EH@Fer-lvo&qF&($E_<88?;loVNqp@{u=@p+o`TgkHNWA); z?sNb9urBot4aJdCUcNs=NH=aPYRxwHIzqYn04rzz`mwy9y}`Aut*yP!1LQ=75)u=? zi5Pu-b)}eL%U?fyXYc<+5xa-JlDXEcw@#l}9RE0ytd?ta^Oa_P4!zE*WMa1NuT4(9 zUio~!H`ugA!@9$9uDHm9N@u+D{Ydi6rN0FhPr1J~@^gq#dKlQy-(beBt{wrok52?OkpB--gGMckDs-vQ!BJR~IW9#ZySJHhA1^)hV4MS@}RU;ue z*%&Njem&Pn+J}MWlBVsC!liHZ@rvE4rOZa=9cg->w13Tx+-kS&WBTIV7LV`~xYa}!-!9+JV^H&A zlsR96ZPGC@CB@H&QLqFts*M+^t*J4aF9>y*EU%4~3uou%_M55}6XW3E`0mM>>|Wsb z%WAI4nX|I8GWFWW2Tf^u=Z)KP_?>=@yfwIS!?UEMq`x8YQi$DPd~J$WA-#a{WhEu0 zBE6>?v@RPdMn_ZS&RAMn62CdW{A*07I!q+hw4vkX)18EA8yMP#4ko=XA5B`BIUwG zdCWTB#l^+BQ|^^6ihioefM;kE5eS{`_7f|Kxe%;9^fhVXBZb(m<(%7{@9uuAo_cZ0 zWt&*_Q!OXkz$Xi12i|pP85tQltSrqbsHriky*2R(cUm||yazTyRZWe;+0?R1s83Q# zN=n^fqL_HZQD#PBqx(-SO8?gNI@i6`DfOM7@AmtqVcny(vh=B^JV2-AjbUwF-K5qW z4VmjR>dC>C&Z@5z>gZT9-d7`T2{njf}`x zPOsFnd98+t>~u}wNZCx1*-9Um+5q~R1^QvH@|Jw~jC zH=`ieC_Vtr?C=LeA=R0gnN)+?$jfQEXHk7D7KSR~W5XC4HSKS<+6^WBUPFXE-32>` zH*ek);lNSi$$u}+8$-q6mJH6>u@07Bb7Ou_o;>-O`U~-^^WpyHiRmwL)^klESDlt- z8t2D9QgjEK7I>HzE(zQ)GKz|b*n^Z#mz0!5#Okq;H($Qr+rs5;l#(xyT)4bIf85G= zdaxm}KmAQ+rZlm;su>)}r&L3YDSjgMvyu`L62y6t75WiKWCP+%mih118E#5d(9mGg z4|lYx)gK_s$jBfHwosqAKzb2_gy?oj8 z?E1(JtgbIkkWlaEAgbfmqlXrLB9iS|t-js7g@aVul&a(94-Z}*hheD`3}t_VC>i`R(^{q_W9YaUDZO+EegkBYd21YxeJ#b_)WvghMx zNT&5)ztWDho^shxOiFQLJB7%!e2CM+fYkA~hl_2zo$-z~-9Ccflis#_W*9YE4bJ-Y z{^X=4n`qV#FBV(*Sv}tqAg5jVoWB-HB%V(=^3|(Dqxo~~HskL%b|)kzb1eL%qyz%- z5bSVBKVLQKO@vz*vf#Fq>iO(!!!I$=w&mS(@zHZ@%i}k%ZYUqp%*$%C#P@8T7VC0eO2$FBUi7`#tNYzuQYoSImoN93C4y~YFfpa%G>aoOIXO8~!IE!?BWr(|kxtP{L03H@ z+wY^~$Zx!t{R&SxIXS6Qkc1P#!|XU+E6_+(^oj3Y+{=xAEGKM^^j3$nq~y=460sM$ zylmQE6EWfEyhvd`x0AM^A!E(_PCJ^^yXz?*8Vq~xu$O$5TBI4tYH+kfP?{<#X6Jd& z=a;oTA5buQiX0G-l%!&$9VXv0d+!eGJyyr6xsRXn${BwQAME>lM0C#bC!1(`W6Q@Q z`bS=+e;fx4iV$}t6Be1ZtqKux86P)WTo_6@bKye6K&pz0ia|$#NQoZ{_pc>Gvi0lN zyL)t}`RMJp?zdQ2V)$c_f<5N?7Ejf~_U(WvSt6yc>h8e2mrKP9W$`6Oj zh6?AK`5-Tqi!$G#rlX7fUS$yw5^{)~Q9vdwJ)Nq>i)Xq1)fL6(eEPnDPoI|N4-Ay} zFxIJ==I_6vrpB4WVrpt?*j?h|Ir<}r_ONQ%Y`STOsIr~^zOxloRZm1$7R}?8;xBrN zmR40&)qM`)i(XuGD4x?TGhgg{Pdb2L_Uq~Fd@-kK`E!9u#7=3UKgw?(H#c`ff%BR( z3_j9>9fgG!GlR-HA|uW_j~YBou(z!Z=Pq2l7+X*|V9&?Tugt)!>;8Sr@$TKbb;#Aq z&59QkGM zi(`+PLnd-=ZdqPlmQG3Z0}n{9bxSVy5&zhhO6*kQHIKx|1=8S^q17nf}2 z)6ULLI#E$!Vbui1Sl{+vhfHpsXI*%nZ8`KLUTw)MI5^n2aOcjQ(((MJ?I)U5QBfVc zx}S1unY^jK16ce7C!Q@nF78Z9zIvXG0>hE3cV5;Sc-P4RPDL{cn)LswXHZs9@TX>G zPM+_(iJER$AEzK~??}1&C8D#Qb@eOlvh(7^Mu71H!HmKd{aaR&?dL|t+4dd2k|r73 zUN5htbRP+vHYIP8?8%`k+HV4?B-OLb)^wNpomN$S&N`&F(0;u-%ttlj#x+!Pb`Fk< zFRSrMP^KA z+-TsygOZA^Eb`qpH>XLNLy?a{F$QMH)MN`{5P!7ql}0Y@%wWSulxpRq3&m=w+UqqP zXOv%EP8FY+E4Y7u-BF{jTM<h|s1_kuuiIKAWjwR@$EQ2w_7;z`HKhMN7Fy&09n$iTo6eD>VA9m2&*XXE4J z-FS9%Pero#r=04~-hD03=@xgcPo@IudoEfZMTni)Cx`Dsu=#1T1Wv%^;u-%4=D z_w?vmjJEFFvuBU=udVarT@rb7?e_gmsZmv8)r-jaaey)?cBE$?VJp?uccBov_4gY@ zy^2jyjFpW53$p18wWeOl)4+ykIsIJEZ}hbY<&-8#YW1{o(`_T6THWOiG8UTa@$4a@x=$*0rpxtR`M;|9&>My~mEx2OPNY0sDEO%~#>dWcz4Gp`S0) zac$J|vZ^YTj9F~|g98_y@8;oAXvn$2dFW8l{6u$clA2&^)-8#K7F08-t55rUD9jj!M3%iO$`ixi4lXWOK9knz9sV6~e zN?S*#HtUwou488J*oQ3pYt}sGy!50}N?MvBI;o>yfAZm@jAFj;?K_1(;&Zn{6>VbLNbEhRKZ^961&P_fiU% zRU7`!rn=e3NMu$wOE-d9)FIMEul+AC0Q>ZoQ9wW-FI~j8t&<iZXqGNT!seD>yl&}H72uPN)AyNOwuZ3t_&6|of&HMNedIry!q{c z)ksTFG5I~QhAU$5*O8{-b961sKS(0+FKl$qJ<1UB1*;zx5T&I_A&CIK~qLvEk2i ze4ffWIf;T!_y9X8zP*RYdI3=-%Wfv&?5~IWHb+E6B!t)fEN2V9TI$P`@b#!GqKDy2 z%mqG6#t>N8~bvvl2Y5}PNW=~p7e3!BqYiB}gz8KwJ9>At$LzRMUvKVfnMAlc1 zetPfT+G!wrfM(^quj%1Dv|Q?OHis!YoL58u@vaUEtipk~`{_KEq^sd9`EslOHFYg5 ztvANa7Y*{Uq%vVAvYS3nbeG;5tUp+vqNQbUK?k6Bld$#ZtH#Zy&|eH7Dm@o8-RA7< ztdyuiZen6$cKf#YwQGBB-@g6u`EyU?%n&hWX2?nJ?~-mLQmH|P>UygwImAC`*Ist^ zP1p=!kz^=Y{q^xwYe`8J-kNCG*xE+O1o4_#SV*2awT73E@7B_SWyrBxYn_*WvPDKk zxw?rlpRl=utVp$a^JX(^>qdRG>-%xoP#Qh}3|QKQczJDU$uM$5Fh=3r#i=AQoH%h} zS(twjA1BLp>HwA$#6r`!HH#8#Pu$2TLv<^Q=q{iDgSwX~aR(=((P*ptP z(qMp`a2g!6tEXpO=YU}aa$J^K*FEjnb3o#ePD=|0tyw%bzP|E+PO_ecQ{}#!+eUSD zbpQpDBo!|=3YPD9tTS?QrP#7tJ!O=;ge^AFajDnDw`2EfUtQtDrfT>v)fDlp}+dHwU4pC>e9{^6r3S^`zZ$ zdjIW(6f6+p$k;3ifOGf0eUg3ErZ~*vZrhk@P!9+kp{c29W@+i_;zCM9Q&^ZU7{YGk zw$#+rrgVKjGanqDJx7mHBX7D$N7d@9*?p?0AWHUq**ygC!^;sL8c^fo`}b?)!cM&Z z=tgl12dG%?=KfEQgMvID<7`=ar5Jy4zfy`O(~nP2-SB3-yu3u{BI6BMh-?fiV1Y)# zjL)@H>g+$AV-+A!UI~HTbe=?a1*b*IrV>2+Jg~D> z3y^jm2k7a`h8va%GxHNVhNG?77hTC{?hm1GS9XdlYoM&^8jXH?TOG&0|Lmg;%W2z@FEu2&^?6V{sV2t1xH6 z1?Cj}#eNM*JQ8kQs!r*BBP6wh2M$QzsE_lPwRCWBc)5{+nf^^7C|t8Js9PNbQSyYS zL@=Ou_3Ybe`Hu5lZW|hfZ+*WntEF@L^l3vVAay^d`Ye;NwucRY${vM=hMMI=AE(bN z)&KteyYA5XjT_ISRu*4Z*U%vLl6XT1ha8#L0pj0S3|x%A5G-&p*J{K&lg|9W?VIbo zr}*xsW@TrW&j$PZUkg+Pu@6Y%w;I0OT-}wVn(+u#)YFl9%a$$C2=22e{sF@yBd&#G z1TPvM9xnVE1iGL46PtMs@bb|%7STgA)YN&e!-EA)&xtM1NA--2rF{9d1f=Ob*(z3z zo`A(*@wabk&yQOtYc_@>j6wWmKV;x#qw$A>uZ>m;L4*0Y~8Xi;p>!y=S*f zJjoM0`{*UJh~1_!&fU9DqI$-?=LenNP0oDca+ZmbQs8_3aGv6aT{s%td6y_CC=Bsp z8yXKCIuuy2G^!+oq zSrkydLr20pQ_Fu%C$#f(fWVHU9nCE*=YVMg0ohZ`N2aGO2HLDUXxiUm`z_{1HKIn^ zc2QGPpMkVb>9h?x)83oN3}bdk&UFw!*&N78h!5EGLPXSIUcTRc5NaJyoNqF~%kDQT z$PJ82YwmQ9-;e(&zKOb!kV+=qzV;#>&vTK6@!Gv+SlUAuO@1RdJ>qvH@BRDRgL zvSa0_N$X{fLx+xjF!A^+F8cNU#d6ty{`?8m<56XXaq|vf58))H9XnWq&!VUTOj@Wm z%6B+Sk^AlvVhzklPnVFCT$gFwd=DjWXNKS8k57cU39QCJ%dNQ;(uGUoo1Xk6_3RxW z+|(6LIFM*~ZC|@~?bhU>(NSNNZ~`%l|3p6Ps*O6mp^@JefTbI2LsC&aF+}tgF zoJw(b2vTl6+WHT+X(gBk6n`}YKUd3)FAJ`j~0T)%GJ3zN2-4GlZRoKBdu zX6*?!H#2)z@t89e0A12Ub&A+L2&^ zn>!d<8H6q3s*L6azHCH>NXy=T{z-pcW&xLGo;!LA=h%mahrQ9f>>PR9q4I`JO-*ep zqrg^Rm3wY(ZtX*tC)?}3eBnWIju=Ke?udTXuBN7@evL6(NPd0@6cqvMm1W1z;bI+e z84bMJMVlh_e8hV15fD&G>B{;3#_-Dq9v+_885xf&Wy4N1$7NVX)Ec}-RdASTxFqcy znqP*tk{R?gnP*4V0H!C@6MZ6r^ES6aIB>oFG8|lH4{8egHxMF1VF1WGdTs>bEWMWV zQil92P$og&6$S?rad<(KkJudBK~mzq)5Wylr!;#m-t5dHU9$`3W@GIl4nKc96>sKH zPPmHvAf4-R#?0&p0o;?_vC0zh+OqQUCY$e0%YZA&{sI4bA!X zZ)@x`^YcYAO*?$ww%dJrVYl)L7!Er{%fR60<5Rr6^vg$8i;id*;<s@axRXul7t>WCFTfcz)EsQZxJZdeH9=c$bwKYl0?(iP+0WpQFjQUlX?c?Os3s z*QOPfBYG9oD9};@mk_E1LG~Aqix<7`DSc!4+tE-{l9@a&2WEGD2yHfsi zRo%F8V?;pC@>AeK1nd6bZ>c&PO*#sarWO|FhtsR&QO$zWGct-%;l?5GCe}14T3K0r zkl?P?DYp;iH+oX@Vxhk_iU;K+f2b_z$hEaO)?-}3!N;w+pt;cuNo+=Y^drEVo;g0+ zdq8q(Mu(fVk?XHlg&Yk2mSIG*_B+od>$$%!pdqlLA-g6m4!I&d55B<=)+7sN9D!8?m+VAq0zG`9lB zC^PO*e%?RxslA;UaW4)^$LuJPJ*{J;6h@QEu&|{7BwuJCjrr zE5@6^9nm!25HSp_vz?myrP=8c>=|D2J<+HS24!GECD~Z~3vG({;dhGC(i`v~u{PW# z)5UaJW!F!Lh@|R$qD3-2*z(DZ#mQZ;-9|!y4mz&^OZAt;OWbJk$kDEN^NX6fV}lP#&EJ?Uo>jM|8`! zH@6}p{DXrNt(g>9!(EBy7_VMMzlIKyFHZc!$_t^wG?2Kyw5vMyBM`W3h0;Kf)gwNC5Aki zO`ABXf|h4wWQt&eP#SPs&3uPQH{MxAYVL>b?>l=r(>Tbu>dO}@CSi-3T;Io!X*N(W z9}3RB{euihD$1Hkh=N6wTG+n2&pvZyI|}1ThEwGgyS>Jt zDpWD}M?{-jaUQPf>&IF%X?V0M{Q%Rr6cG@6?kU${3l28_N7BB#;+r=YK#o9`imvXy$*C!?%B-9m?S<)q4UIc~3=bcgZcX^fd}cNH z_p|(K^@~u<%zjkRG`GSMvXyy~9#}+Pw){)}*Ay*3Q0C@VAkr?-waYB$UiajWG^LWl zki+%+lp%AeNBf3BV)+2}qhT!lXrHp1;>-*h91&U^;U{dL0q$qtup_ zb!;CC3lfOR8s2zd4^u4S$fs*6H` z(m~}Llp=nQA3u%^7rJ@#CeiHaTEvcDH8M)PEcX8W`?R2h15Z-7wl#XOQ z;lcsk`-|_1s@T}yMMAIhpGCrTJ5weNQ~P0A9|r#I^z`h(-(FuM1 z%cni-FFo2nb`uJ4S`gs_2@4D3u$Yo#Eqt|H%HkYX<8h6EH=x_vd}u2|V)Hu3v~&q- zmfpr~^>)7Y0ND0}>Cr}z15%yCpFB~~md)qd3^CyTZJZb1521^fItm|QQz0!I?w~H5JiEpL_%T94 zLOd%0h4*l9oEu{(ZqB^P2zbF3Otn*q%ePEF0bq+!NkXf4I_L&emxTH~cK*;}K2}%D z)iPiKc2t1HYD4kzoZYc~`|jV}wjAmFGSuAr58N+IFkg-kUys&IY}03SU;V?vk}sZK zjbx>|f2HxYx_Wv@iR5Y7(31#8Asv5^_sn8XITg-U3H!`47dN+@0ew6gCvh6NnYBZl z<&WkzkO2Fp1wn<4uPHA?(^cK-*bFcMhh>zQe_s~LGO(;tM6ff0{1KCIzSEL0L_X>< zsSzs5N`F5;KjYrTpHmzbledXZgmDZGCREFKvbGa?`uc8Iich_env`u1zX9$Si=w4ik z-@D|#)iG#LXhYaG)lWhwo{=I3M;XvmIj9=7k6k$-&^Trv#mVOZkiI&>`_i((Q%^?K z#?{n1dlazj5_P!TC3^?0qJx^GGIZnofI987vgLsP`~bg=$7@$OxT%278U;awWd)GF`xhg zO>;=9+#1b{8#Ks`o|VUr9lHu=;D!dupE7zCM)_bM=s|c^vO6YiyaOQ4q3IHL45=o; zfg68QVUI02!aF{#FD&#Rgv5As>~8P))V9A+G3AwQ|7=A+MgujJN;v-&@MxTT#61Ng zuP}DwVZ}RA4|Jhb5%eJHtFp`fu?szcQNZlVuCkgkJx}{!t4tDSTcEUE0-t@?(V^vP z5>~w{tQ!TKJ*OZwIwpp&HNqeufL4Jkl+``EcayZYx1*=y77##XY;63Z*1%$c51^&F zWp1qF(lxgyV<2PV*>JjDAXW{0Ee=Lp<54tHJm(^N`A_z&8_vr+K_kplKpeDf5o=>? z^Vgh28rCC%8UBX4+y~N8lnWuy>25?hg+4v3b|BamajyV#k;~xa5Bdq%9<-J@S|rZq zwg>!(zmk67RZ9t z>#3}~oX0>u8O%e-^VP4kY^#yyzq{(t(NL32StWQ;q%XbMXm4*HK}G6Q+|Zyb5H)7@ zDBdHl{Z6clVGQ!zr%#{w=GRTu)W{ngeXh+10|i``>8C8iAX9tSTs1K;ha3JK z!t^QA*P{oZ;WvBNbyJQe{N)9R4d9Tnh$~ZyeeadmPV&($%E8gG7B=N(bzR+;STjnY zrMEyyaCPOMvV`_CffCo;3g6oWyL>U^8)Lt7nqyELP1EL-BK7MTvS=KWf)&LUGmWt#0{_ zsQQ3?o1s7YS1Ko~H?z;w>z3P-7Ci_)zt&uo@^N+QGcp!8Un^eLd=+l)AxRR zV}thRFWN1`k_j}Zl5ps)<`5jg!q(Q5Dq9CRnOZ}9PJA~xXLif z^8VQ{h+9XHGT3UZDo~NbMkp?Z0!4t`s?NP2-=TmI$dac zpzv&p+lW#4oi10Pldp!lI<wio8umC?&|uHMX!BlV@%$&qCH=6T}J3t zFB)ipRLyP$TbVpxuI%_J{P?iiSKaFD=P7RiH{LflXE(_xC{V(vvNeHX8AP?h86jyCxaO<_J*y#2`}v%$Z^{Ga-f!sf>zA>MEoG>3p`K-h^f z;ASN)f!Gf(Z1(#MNoR$x4Gj&QsyEVm@&QePbJj=I-pGhC>2f{v!&YTMNZ{!j5VTDe zu+a#bwjZ_ReEAwGe6#mKw+2Zg^UKk?okJtx8L%)MCY0NwalU2U5S$(WY|txhd>vvW z@?vZ4M54|+J~L}7;kK<9-r_xH>$dR0P12NO$w>&Wd85esgpS{=j>A>WPDItMSpoc^1S@P`Pkni^$IH2A2!PS#| zKHcfuzUTihV4k57$$I?wxB8p(lGE$D`yh^-LdRa$Jd(}$IY54J zRMcKHjP%Sw{#7CvKm9;*3+^&E7Dk;p4a22zGH4Q6u+9I`+slgPsH@5Hg`SxW?jsU(h`zL-XV2)n#)^?4 zFe7nMfNsZ*wVa&YOE(^rWiWTngt;H0`agXR2r9^JE+c3bVQ|k*42y7H!2IW=UVfwC zevlQ|RQ34!s>3fuP<<-yYsyQ44k^$LKLuPmAFHZlC!B1ApWAUjo(ax&TFRO9$$N*T z(d7e|l4jE0_ro0}`AdGUq^9Yec~MEoLK}gKi?5Sy+2Z=ZZq05qRr+HNp%o!M1m8 zqN7LFw)hQeqQ?hfqYy#GyTQMaardm{rF&;IAfuzAGG-)0T89*}HyH9mP>mgHHZmts zvhfi(VBD**ycZttUbe$yF^_ayEWo2ie1`NzJLEZUueY8E_ z3tl(kz`|RKYRQSm?A;1imU4dyug8f}lI<)kDQ0Zbg&=b;8g6)126AgLBaJJ?M?JFV zyZZ>{D^>Aqbh+7E%L`#4*pyETI+P?XsJpdy5$qZLr%%@j01LP5bj$DPLFf9DsNnw) z=CEpsD4q(Gq3k+LhAC%mva%}fSh95+yStikbPxUu_J|Y4&|*)T7?Y0%#PcH>^O+eT zP6VPq@>Fvu7{biqBS+)~q8e@xHZYo;R2f!~wZ)%(;bhk0D?`vm(t-d*5bM~XhmRk- zqD>AlNj^nWBqHSCgDKdFJP2hiq@THL8iI@bZ#H&N(-hVEn8W;QW7+sdwM3Pq&b~f2 zqSzjq9cz4b#pSo!BP%Q0-t@&|Hhs0z?wFhE>zg_@C( zGtj8%b;O6zhddq*`7ncc!#W#ZQ|V0jAmU;!rU)Vu2^(fBN*#J!;~xsO5Q)PKC}Izw zhj5K-rur$P4C^y!GRMVm_p(56TrfI6f(qxX<}}uewEv38O|{pWVcTv>2oufBf zlmy+w@pdmK|%3TzfW1BdUjgP9k^K-CtzBl5l)kV+w@5#G&EA! z>lGsy?WA=(lQ3t2d|M9zUMX=s$=9!6({`R`KJ(S!sKJ*QpWoD9T=3VC7?>tC1iF#n zEi~AsD5j_EWD8IY~A%?Jvz;0UpJGJ zH^hqULFbp+PD>+I+f^Hlry$R=>f_)?2#<>qjH?NRRqvltSlqfZXjRF`cpE3uM*E4Z?eYQtK6(H>{WO`DpV<7+5)dX){4Z$DoC^)e*t)Z0JKHN$7=RWsnbKsZbo9{PHFJB&Kh*;Yv! z^MI=&I^;dQy@Sdhl>mRxk)o<_oNKcdCk>c3g|7Sn z_}|zBQE<$0;SCuRB}v4bgrlrvBjI;=7#f;%E~(HQT3{vA#`qc!Lr_Yo*?I*M!c&cL ziI?K1-=Xi#9!QnVvp(o4#va}`HeM2V3lc+ghh2T|!2P@>)T|B2C1OrS!abylk%`F% z!*na%g&46Rnw_F5J%QIGJe)K`1a3Z$blgrEpM;ZV(3l)*Jc=G$Li=Uc)f0YZ^FQ?{ zjx~~Qx>B-j%IC9h|ER%RG-H0b@8QFTFQyitl!>z?!o;Hk$A)l<={fjlkrz9E3yH++ z13b_dBldpM(a~|il-y~7Sh(=fZ$I zR$wphuFDr~?d_vrXiUon?n~f(bsG&Ax-hc^Yk*67%&2@{dN|?Xz*T=E14Cpv-}6x- zHaEh4tB}R`0&e59u}>IFS`kjQf%`cNy|7fjF9t`6PQ-hW3j7#lPNs3w>otIMDtRod zto%!TVk^+e7Y1TsX!ZZlwkow#9(4OBl)TOb;7-S_8CaP=S;4t!>sF~b z9POo;8JkX_I^1v(5_R)ufCQ!fA`3~kwT1KFw-n1sEW`ftyJ3%l;8im&5EPCS7olhn z6&Xog*uIRZk1UIUN5;txKPUTJv(qEh2UP(8djWAf6vE>Z4=O2fY za(}Q|`gL*$+7_CHSp7J)x5>uP#wn0)xfEO|5EtkPMM5S|%O)J*nA#*9;Srplz5~vk zkQ9Zx;7_rW#9WZ4aW6mw(Sp?$A=*knWGBdEUELK}s?bTAl1UO;ql zT%vg4GE_%mVkBZ1vm`V_E`dM#`u=F;Z&VLIAZL64<|(y+A%qVYsN@KAgx%yCx-Mr} zR?h3%%tD>V(L74Bn~#qQ4eO&7IVF>D5PU2zKPzAjv-j3r$F{q=x^h@ZNxnS6$;l}b zDy+=TNJCQ`%)Git3LeG(oCV-}0v!U-d9z;SEs`eiEDZ2Gs?@uFT^p4SX9a@|#5e~# ztZVn7Qgx%5FWktp9OE-A{WN0c3I5}Uj~+#uUE+=bG(d_|meuEv0sDG^vjx#jy@am*7yO-StVc!Jz2xWyYqu@3)%9XRCzH30KwlN4=O-ubd|ET~6rQ&pu zky{F2Knp{592PHg;k?=MLsCw7SqrI00zJ(8X;>IZ2r5)U;eYsV%$dm zh3LiuBS(N19W(2^GdR<55gICCuoQS}KWFkeSg<-S10n8%t=$U_6gM=;K>$2rD)Bey zHj&ZC&W)o^RV~AIBc14o8r{`+51S9p>8%nhLyW3@AdOd0P>>dx_=)g9AApn4GXqyJ zcH7z8d;QGJa2@1ZY;s~Wt48I^}XC+ZB2UVeS`ZcX_F8um@EuOX)jzfnyhYg=k;PS+<0FI03I z+(x00A+Q?pj~)J5D0p=uB~l|@0%NvQQ{P8QDDSnx=f~R*D(^jUVizP<@#ej!eRo4q zC)(he89ivEc4Gwh0iNah=Vx~j%r0LcB`slWXnbOVvO+W0ik$EifomI?Y51!`?00?p zRuHD>Tg!{KQbPv`*R^=88R} z5Dq4@Hh7ImQPW|MPm_1TP%`1HcyC!gU9hrjk1jcx9t3q_yr16T;~hBQqu@ruRSqfg z1?V=-Lw6ugi1$O z@dv1f;8W~@)c~w7&jyTRKpH^vLtJbSvB_eK&ym;}VGdl>~oq>$Z0z|3nix<0_ThR@cFLZJw-W(>#ixGS? z$lMqDTQ-q^KheWOib2*pXw8Qj>FMfTh53L0z~g3xh(^@=c=N-&a%eA?pcCXeg#&BQ z^m-5agqF$5n0CXh7n?CuQbbtue-B+CLZD<&!^^o=hwWyE3FS7TR6XC02Kk`~ z7>FPfkthSiunxo@SLSe}UUVHh(NsgaB?0X=O_g{+A|E5O6Tm5wFo0gTKw~GPqC!j9 zqdq_5Aubq_LJg<^TflRv&91xDIq=#FePuj?8)OmUiAw!g=$0AOIOOEyyyWF-arxqPC^;lRUcv`}==k9g?lK%5(ly6U`ng^7brA;OmDY~lpr z)<(b;Gn(ezMGkvo)VK|%*y>7JT3X_|n#*rZm@pwTfre360s2)FLn(!1;i7W;KVn}g zSy=qw=GyWj;L#&u=<+C<^eEOR5yzcBe$0GW1X_P>_~ii7UN^?igl7b-N7aeRQp|Kc zLn_tV_(s!WuWKP@wd2Og)dGpZ|1SLC@8$|iI@AbU4MRty9b(V1(~)Nb4iG)pnr=l! zMIsRslW<5KO@+>daU&iK~UHcU+_z=#ag0QcKqJGdr*K~w8c!t zAb8xu00m@8R+!T9DunIb)aK-BKuVYX3sm8bj{7jfZ_-0$e`O~4z^LZMn!);b!Yxi4 zoNGBm3qJ}$Qt}67o*&(e0$dC$g{2)qS&rCF>SBa&C-?)AqVn?dyLx*!u(7d$Z?eL> zg;Wfluno3@&1WA?4=QK@v=R+WWIx>4Lr=}wvgbWQ z7zFS;$~3`~&z&Q~I9p(gXY=I5#3@Mm$R97hEW`4;!f;??*tQLJ_VynkrJ_TzJT%=4 zYzqJ1Iy?b>`8}9{*21+8x**hG^bOe-Ez2q^i=kk@Mw^UKJ5fl8jzDW$8z8LL@UU@f zzC9h3No2;mHP4|c!uz%pQvuh@RHo~2n}EY?v%WC-rt5loU2y6PH^ies-Aq9ObEFP9 zsX=pE^!U&zOuM4m5NZy3%Uwf5Tab()ufNCKA9QoV9feE4*5ffH`@*2gL$$vTRby!J zGOsgksoBD%Rp5=wtu~4E0)N|p`>r7Y>=Q?xlFu~00xQ7cOhNdwXY7m1Q-#vr^mj3= zEtgWta2}=(K$!<97Ws`ee+U|7ZXIz66fr?hI7)>@Mu~6)9G^h8S!-h#8i#va;9Vt# zAMqJ5kg^-ImKYby0@;8whA>1HVXoAo7Z4O89?^foz<2#XDtI4kqa-BoR}!m_os?=$ z)9dQ*--KHYuzjp}9cVzOv3FYGg!CO;cNA#H;#Muilu|l8>cNAX2@!ej1@-y%Z@3PISRUl%ODPfj zodXX$QOa&X>DX(nzjF}R)L=;o1dy(Oh#M*pqiu- zTS}w~n3^^;SX)|3$;fPl*Ill~0mG#W_}_P^7&S&dI4bIe zPE6?V3!0d(9&|~&G~R!X|4y5pe{zVjVrI1MR|?g!$~GhncrSF#Ve_v0MV+lrAVxqu z)O*G^zCvj|`S}wijP8DZrx9{8ZJx!z@*iOmt%*KQr}%dA;!sTlDS^-$hH|p9t^zTk zMn?>0tR!Db(L5kF@g;#Ij@=RXJOXA;4#H1FO(YhKA_UA5cSY$S zDZEbO_0zhtiJY8&pxfsrk`Q5Tg7hlWMn>tMKtKz~yo7_gzk}uPAo?6?yV!B`Z;@@` zJZ@McMiJ8X4+M(h#t~dupepe6=~FiV3I=sk_}FNV%iJipCo&!3pa6#ss+8Y8J}sF~ zbloBDV-kKBaUTW&G*D(@O!`tqa!2Yw6(aD=+FO0fDg>IFiOQ= zl&eB=GZ|9<*BS(p#|o+r;br(ZR|5!QX2|LPB(caM6ZwGL-1+d}aI3SzNs`y-rsM(_#c) zFIZkMf`??M-US6TT2Z(ajScF5_rUH0E_{bk_5h3O1Ofpk;}#65zb`Aur~l@>JjJqa z|Nd*B4+oesxfElzwmZ&g>^fny9hZfqmoFS~1z01l9%9!j$cwaGm>uyVmPRw*&hu-n zE3CwXt=_oh&1QhM7?aXNM1hAjnwY4QhiRvH2%_gTfRJO>qr09THH@?o;pN6k5he9C z2q1Bf&Ex0bYNda;Rm?e&-#&;G;u-_FnQHAw6sHMXmZS|O@qly6O;8h9(dk~keEAM7 z;+Of`Yd=K*UjXZ~#>j?}p#>N)1E<0rKw=_^;}i&9VOc#{O85JI$%Y)e7Wf?E6mew~QI&}+hX|95!dFL1%q|cW6_eE%2@8pgEm56p zC;5HZ2_ynyj&6FiO)Vo}t)qj(I6kH}UN+0&CvS{Q&{`H27Udg>l~XItxxYFSKJl4$ zUfQu^_nt|v?bIF-)HDa9wG&TflCrNYHY}C$%Df?^7SeW;$=Z^sq%r4fQeyR&B)OYO zO+gJUhK56uDyd)ZWvZsrO5Ip9v3?)N3swfrN85J`RkO$qrEBo-dAL|L7Bcno^SE1| zdiL1ZE#7RuXJgrJ6n>b0Dgth%@0c$U+>!eOmGV9A2U(mi=60e)9``yvnzdJSDyVv2 znsv+P(Bp!ryL14Y!?R-(Akrl%PBV#6u?_v6dQ&t6>4)v)&Y!-xIIJ(`1z?dw!^?_m z4d@{pc^f5X$DHfN3n%EFx^@uYx{y=h37nGG)4wvUklTQmM~@!05Y7dyGim!(w%5-a z5S0fri@PX9=dU7=jxysY;EqG#SC%UmO`h=^seFFU&q>^GW6YuN_^mG&1dA~( z8HL{@7R$%Sr!CD1oDAyMelRakkk9UNPLlx&N=o&Ijrv@W@k@Y|zE^OjcoTby{}fK# zYC~a|1d9aj0SuwUoVX{(vbX62{j(79ARL0nRor&)^rgVSz#_~?{=WL{sGwl!7dbH| zbVWP~`iADr?~Bl&W3%BJNg}{&ai+V2(ryCGPE?vY@g@I%?7e4H6p`$>1IyO|&|p2OMs_5Y^3r;{x7A3Oy1A_1Uq#l#e&b8NS_$R zAq$0nzct-j{St}eOyE2gY=ReZuKBvjE>LX0e{G{DoP^lR1r*PEoB5RwIPCzND2v^2 z?1;_9>4IZh9?R6;T?x+&;T@tOwg*A2tpeN25gB^%%q@R^ySxe%A(a#B-`keb-;we} z69BNprK12^1J1)-$hN32(J}PCa^;F+ciP~6V3@oc6!ZX6w18mo!ONFhF=-zK0peZR z01~NBZ1A}T5Y{Z%`MerGsI-EVB5=^gfcMM`HzIJu10=C?>U@nHMm26OAY;f>3ejdC z$oJ0zx5^lTSX%($BMZ~efKS9_4BMqwk(C3UR|9xYr0WC* zLNmbozzhv$1YDWFbcx#X3#MMnq}BnOVnc%v-O;(8GtAxBrNd;KgUJQy*9i$~E-o$# zy;+<{30Veo5s;3s2Ap(mU?xP`PSE1lAOlUd?ePO+h#hPJKq^2N_XY!1oJaL-jh7%! z_ksMet-ZZ=lUfG2F-Yh)==RM&AV3XPHb65s_$UsP@k#uyj`wVVY#2TzXUBL$)@_Xt zqv@@(Dah`2qmRON+8h`}wk%t=%osv`-2uI$KUz7txw%Oy&zKk=c+nkMYh&cs1K&NM zGa&P~3Wypg^nH-%{UA}0wQo}zQr7iC$UzOxY+wnf?c2A{bZcM>__q)r7KJQ$F34x{ z0A9hz@H`V=MQK2U3c+Ez7o3Ql8f_wM-vRw19wmB0@*9#~AiNCGA&tR>c z{OkYy%j8)6-|=A{i~mnY+oT2NS{PP+B*st&LcZ8D2v;j0i+K7ujy_PVmIHJz7%AwGm1+{$h9d@ z}nzwNfF_+P*Q=8F~Q5CQgqokA{+g>9jf z{W^VUd%4d6t1F9y&_NP%Ooc-(h;aK~R%PnJ!%wJ~F)1Lk0fMydz*Z$O&x6=~mvyrr zCqT?Nb@Z%vI=AjKlzSZHDt`#{GdPqwXexl6_`ccMv!idzA*Pz0kTKqw2t?(JoDApc zf{_4jUDvu^@Pv*+0G($ElkocOQ|dUlj`)7aI-ZTNH3iGp3)WK>I5rj=j<@NgM2wBr zhJf2^4ZJB1at`n_7vjFjc9u-7hMC?xH&bODcwig4z>MRv3I-Ppx$aGz^nnG|8hmUA z*`nfNE(jQR#!`#O_3+}&E=}tVJ;1g}f?|J=kA*E zOSy1FjqcvD-7{2_&esrrGny9=d#tAXqGBQc^)F7PAA zefB00l-6ILnMa5?@R*CnG7$u;$acsXO#1dcl#j)<=VlUg4I3Mqs|CP4A$o5$oSioU9YdfPr(8vq|Brk(aukXRwU z{9?M;0K z@zxUNXNC79CUb~6LN}~CUzgg;9s*YqsB-p;X<0y+_G}ec77#9S-AYPJ|1M9tS;gQ0 zF>`JWb^-v0omStF85_bmYi@}ppz^aw>;D1=Th3!`IvMZn1(@GU3yvh_bH#zbj(Sio zc&)g&H)>{0F|Do&IO&H&7*QlbKBvaC*a_n8X>ww8D=I4+U>EBJE~A62L;1;ooj8e6 z=XFJHdceuE9MIq_!O8{k4FYl9F5ONZjn&}wUsbAsB@Bbp(L25;5@_3fovQ}fiR$dB zYvaGwlGORY)rakXEa=Za?5gcbvmrWM^YsHxbE%$<#@0(q4jwzU6v8Clock5FpqrX2 z=%5Fg24ZkjETkr2t%^+KaG+5S97p7)+I6(DHmBQlFa=cE_;204aTGj6pZW*7@>0t=e~!7rc; zyyLieyl1NT0Aja_@%9jG8v|lQCyaoEXCpYYjfLaxMG6KW{4kXT+l7hm*Qb+DQew{s)hf@*RQrv%AP$>ios5wZ z&AbfggLQ%8pcsAm9~d-&gHQQjIGgeS5f;7mUwIfD-4zLI3APKJFnhj0LY7jLBs5kx zi7`yF0DW8Yjc-7ZMZjCGY0QV(qQ3xs|zV5b`a#LZME%+ue7+fZ)4JGxb3N7 zhHFSoC{TZf9hfZB0yojBU?DX|Sh|f?VqC~h&f(1hnJmbW3{|;5HdtQZ8vmx*5PTui zKkya*U5&EfxOF=Zrqp^rjY)n|l(ar3Q8*@Tpkl@n?kjMXX-68e)c!BJb0R1L_*NgB z2ZN;cm=tus+HJeKC%U@pZ|hp@S)uh6I9Y8YB_J=zzF-#hE^D}}2E_*Rs;<8?l?zU3 zxqq#Gpb{L3!(Ur~-aAqP3WdyBO})(=Up6#c;I`aw_`S~kw6wH0N$m4@varGcIIMHl ztQP<>+>m^%Sa6AIR>{%4fNQufUw#wBw&a3G$C{Oe2CHoLbMcOTD&+*Bk_%~t70ODr z*XM(H1pJDYUue883q>^K(~jAL;p}}CHogH}r2{Yj=>wvBd$}U0S~BCte3Qh)5)I~Ru#a|Bl`JPT~M3E7cv$kfhYIQfvpzl!{0PdLEP0}g<_3qRbWyZ|3ao> z$nL^8Vw+W$iO}fLv2QXN9uNc(x#a}`wRNsz4MGmGIAj>rx{q(g8jyOyJSO6?4(0n+w@R5Z{Uv=}Ht*is&%c#MaY>)c&A!krmL*x%>kL7~p zF)jsq!x~5;L~nHz0^8>{uu*bjHc)g!==%t`vKSq*HLP2R9NSyKIWsdeYq5%fgS?5a zLK7>mQ#>kSScQdecQp8pIL-~1c@0{uEMP|n$CaL7&NRi2U3?9O7m}D7p1sO%`y|{W zG|_YQj^ycsSjZ(L9|+h>wm^V>c^-B8EMfYzD**I`{s&OV6@9IOIA6U?#;^uZnMvO> zP5KHabG`r*QUjN1EZ1#J4f1g!b-%bk)Uo~wzlA&4kZdqQ@*!cHPi!A+P@XVJ=vcr! zItRpX)0lbn7??_M`(RUo1!`Pe#((>0e-(X5$Rpq^e=3i$KKO4xSr-RG&?t;>#)Rc! zwDg>j=m04Ux*@r#BpX*%+Reg}W{|kW&T&zo>Z)^Lq&{0a#7`Xx#;is|M2t z)0S&~FP->iIUy1`H`5KO-7LX)y8_e<;oyKd|D#xPzana{fg%>RS}sWhA-wi1vSKmk-ZS9^qMHUa@rg4r87^ogV}NJ3#!FfE&6`(4gcOw z{=ZQYHUSEsAsYxI(P+`Gj{~)4L%SjUB1E3oTYr=)RRx@gXd8g%tWJCw*ZH|2R6@8<-z+;e-=n%rAAnPYk+6p5HW+Prz`j&3_-j!>hpP2R(pH6 zPkG$#ZwDvUb2UXg>$_c~ANk5}wHWzli0@N|W&KiSKkKbeJ-)N+Zm6jn&!(d>*j?Cls7#GUC4BY*nDigN*Ho{4E&xJF-`=(b^_ zyy!Q^i(W3Fbcs*`MM|vLm+Z`DHGRuA^3tlQ{asAT%fn|6&st`OIyZ$3eeIUcag||V z9@a*P@Dj8Qt!)c3IXG&Mr?1Q(Q_k?^t*xqNqc~!_*%;q*nay73?#>(E>3OaD7`M~$ zMYcA=lS4repTQ4;W-e@+S(o8BUVVG0^r~S?4rL?s@G=U_?OXl=HM+60zMKQ`SC^se zLRN^AEpN24Abi}*(gsz|)qE<}IL-W?-4F|hc5kaK=wS?M}G;-~ocej<$N5@fF%@S@IsI*JR-z6E7|>vk|^{`8(tC!SL! z)6b1D_!kT-|HntBI(e7g7(5V%Lx9P~6Mo?F!6G*;tr@?Xwkw4n{xNxd_aR3v*!Dx_ z8-q90UBa*$Iq*5Y9d2c36Db0^f=)K`UE)`NE&Ds&ITiSd$?NA+f2>>UbLh$5g=f8` z$C*7GS}L~CZ|5mraqr*K7NuoZcFi=Jyqoy?E4KB#@gBUxGyZ4GADxMobZ2< zsej2?S>Kl%XE%JdQUZs2@*3WSJz(GKDSSrFHtj>@x9MK9_~%1AFk{Q_K8{3MuLsd*jS`ayj(RtW$q<>JR4I{G`Z7er{rYF^_r^Io+PN z{U47xO_hY7&$EN)F^eiaAkE3w|J6ob#fc9e+TH90%5GT{_rw zaMkR+YzLp{{TVR#{_b0z=T_6)?_Hv~m(S&4NpfHN=sM4R$1=|YUgk;cX0PL{F6yRj zFe^PSVKY(I@k)_@MDtWl;IVG`_P#x1P%tvT`|lMJTZRWfoaDTrr0j|vo^~@cr76Q~ zyBrFps$3}^ZTLW)(EL@nru;6-5CP_tWz{0f3KKJbZShh<=iGFkL=EPas~n@Oo5IsG zV49a6jHAeg(Oax1Y`Qy*#VSdd`Xov69Z~Yc7do>cv=v~qww%5zo7!9-Mst&82J4S823a-eN{S&g(a>+l3 znyamf(2JT&k){8G=~1WuS8^A6QFwtdpf4zm{C7aLC~e%_h$V-&KCBTs<^P0HS@`ET zgco7$Uif4|CfgLT_&L!0gbu!F@)A`0w{z=t*eRcc>>@w8EcZVp<_k#7|J$d*geLq> z*&fdHC1-T+{}kmEmPEa%U597PpKLWzsKppBuMv|P&k0_pPr@HC#^7l4%sO{^87uQ$ zD$R>Y0ljyLNIb|*T{lZefsp+E%ep~Xc#89u=s z}%L(!<)_T!ln@huHk&{5kUq5ANS;Oq(5cB7f4ShInJy6Qce|IZ$ z6No<<0&tm&pSDWamHtoLxB0C9y__I2!#T(y+j0_KF?p#>kTRI%D>3;uf{+wJr7*n= z|13fM^XorlIE%9A335*BbC)tda~UTprwYp3|6KuoTZ!dTsZY24$$Z0RGx9Mv26B(R zuDC_#$as-GTMv!u9VCg8 zGPC_Xk$BwuaRo&N{mznYIGyAB>ZN!lbHkHF7?SoLh2bRC7dfv%&hX{mXH3!ejd#h_ zbGNraoiapzmW-}SpJ20!xG_PQCO!qmXOb(4jXG3g@K%EC?5(?tiA6_Qm}mUoc5kQi zk5C*I=bth>hutdaxCVVCbC>2XBOfQZiipw1!J51-FgpADm@Gf8$;sVGRkzMt#v3znnP4i8mrUs1rXUtK#z6EfO*r}|3d zJjeA^9l&U3;sO^sV*>17o zam}CA-+w;xr{J#VZeK*pgMLq5G(A#ukFH{|idYA0Z}R%N45XG2i>4dd`RjSw{^!H^ zY3rwbOVsrRnbS`7v!feS(-v5jQ*`0aw&|tm(x_rJOfH;6X^$i0;! zWzK(YKYJ$IbdA&dM1A>696~?q2syU8^M|RTMT(BsQyC(?ua>_2thA;1C(3>^j#Nku zdoPc$!qzoPW=v_hOBX%Ph;q($oK$Dl{kY>iT3X3#n0{94*-`qgc_Pe$5bjUPkIuOs z-pX&$Y}Vy$*Mj7kbrK;?D%!-DUGwVP9mldudUw^Ta7MCBP9zat!g$68$q9>yWwApg z-XHmyXPS1KlmWf98Y}`F>z!)OeWo0I#r=r_*Wh{C7G&hO`LrJ)^{C$fOK}_HkG@0tizGb|Fd)`_$qw!5lFHwnMw0C{y%(^Gk2JdH#9~VUx&tFTvdOi2& znVA~PnBz&bc+$nvTMHqHm((YbT^EcwK4nRJkR$xrqUSaIGI^~qBwsA!_p(lde=)O# zC^TTaTxVTW&GRGFu3sR%wZu4nnmBcIdC5^ce9)pteA-c5A6fH1CS(DvpAuvrX1wAO zyyH+hbE2J!6RCqXnrG@x(SwXh4*+4HxT-(9sG|uBmMe3z>u`AeUpI0BeGduR%z2dB5~BoRE|!t?=Av5#EkYF#qYC8JY}I(bi3 z+@FK${jRT{P{)!XMdNuxA&1fo@r#pJqbJ!u`Ym%~h-gvBq!#bDO_wi`j`6&ut6y-x; zEmV=Ov6e6C_nBtUw;fu?(u)uB9Xn_g~h6zI*5AM&qno-d9)prjho*l zd|B|?FUJU-C)8WWac@+QT|pVW7E|(uC>s_l?RC+C%!5b!(z2|Bg?M`#l1;@80Jeeo zj(`DM`=sOyf&=gn38*bS0mZOjz}+C#-F{g>wGE!Kf@qOhZOU z60S7XoBIGL4SGWWsEsLRKYskkf}&kZ+~Aq?+E;i2il>~AEoxowA-YSav~WbH9`c6k zfzH7vY`o)?6y0g;6p~ipIcHY}ePZanPWlo&A+>aA*WKbeHpHVjZ|s$EY4?w26U$bruIys=9x>TA~bdSw%w~ zjh)Ba4SnHsU#8Orm~I7l4V|r>+YW^xa7eP#=90q^H=^qPZ<8yLAk5~lZ1&reG5pc8 zUQ~H_52T96M-M8&fqC!OMQ*Z~c@$q$xeyZ_;6OVUb6##&Z?UXN9eS&#v;J_R6`9g&S%59XagMMTYjl!?b+{X7emDVVt7<6(gxGIz40{PI#-YvQ;zV} zQnkl`^l%JPzkGlYG7DJE&W2`myv(Z)|8t=yrfw}=wa63UYbZWh5|_8HOdlzEj+`AP z0s8hAD*F(C0%;@2abXQryK?ap;LG#~8_r}~lm(Pb^_ZRgWcX6T(^qtF&nfoP^G`)W zMbRGe9T5eG2hzPzUMmNRfbgpc+7;VpXK-*hb;PQD2vw9vC>xXzvj5muaz-j&X|$uI zwRMmDNVp@swgJX#pF$DT#YGfZmDQUC-F);32O$3N!Ny}o9?%gStuN2pn6d$QP>z*; zP%+Qm4g&qFu|0nRn0Bt|TBb>1Qbpp|EBy749i!2I0nn^ol@=-D0KE&_8Ku2fAqA#0 z@!Q?A2dia{ZcJ*t(bCyj{jG2Ny~UUW9&G!0kDc4V+Q{G~8L%*y6kvu3ek)m-fA^7R zHta8coufxU+_Sa|lGYpn`Bo1IrRpw?jLLS%Bk_XSDOQky{5FJ29qP7t4J-&bo7{%; zvLtZfAjD}wt#w;eWDc+ZEGek6E7eDcla%wU9(!;~r`W7(1mD|-kin^l>-^|T(>(}; zkV^RRhy+6bRx{A?5oiHuMdy^w9rU$1pJX5$%wNYKa3mCx!q!1{XvW88n2Z=m z)Gr<+=n?tsnOaAFv7T=qV%7{huij#PeSPz!ZqR!%N%}*;D|0Sy!^anpTZCDh^?{hz zx&`=IiygfAwg|^0)_Z12K-T)HXSxX+`}H&3#7dG_9EU4p>dOxgR~R!#+&13=KSkIW zbw5x6h=vZo5t>-+zc)gIGr|T0Le0>yRywR3q)LkJ+D?KjAbB=^IQ9ASO(+_Vs%P!c zzn2f;DC3IY+y+rM$0YV5X1!B*j@5{k5Db~^9tA)!#s>&%%Oc6vv3lN&-OjFGj-ASe zqDFV^4WT*&BK=C#GY8gxsio(rL@cArb(aqf29!#>tzdrQ-Mx^peH)=3QU$4F=LZr_ zK?bNa=FVqHAY8GiJGws*ErFUx{0D|bEN2ix1Ksx^8BME|oozTTzNRN5mI=KA&+m*2h{OG$7anJ+c-qPa+e4d`( z&j{B%kt{~*86UXurReFoEv;+%W^2Od9KVamD>hrz|8MH+5!;5 zSg<}>5?7aBG|TH!?s)NLNf;CckR2Hv)wNfi&mD1VJ?&}9ndu$|Ip(L%?6Stx!)T~Z(b>4qMa=CA5t{q1p1uXP=L?R@39L-AdX$I;sA zyhLe*J@bmltb1?&Zf2nf0;SJhi3%Gjj;xT>XaGBOd&n8q$+_YA00h;kw_(}*FyK6k z)h((X41_KDmDKY|0sx!7P#*~Gl?B~gDXG-}$}@1t87#ec*u5`;uYaF$X8ofLwDnY9 zTOD?wJ8B?dZy7jknhFx&{2&f9NaPIGrsE9DXxHyPGd%xw*JG(w2Xxok5ziY92gtZetgc7fMlX;mact4=6A(HfbnOIl91FH?YvWu?bM=|UaIhH9jSdhC9-!~ z9}G*TQIz&NYh0a>vA3k)BVep+#=9I6PCu~)6iC>R9x;}WDftM@(RD2VtjiA{w=__D zfJ-m?KKkwvWUQM{^qY^{#GX6m_C!8_KHeQ`_4RC&5*y9=bmQnuqOECkCe6Obg-u0% zD4iu-(7BcITMitNhwDjVQiKLe9^{T2-UkhrIUn>JIeMQeG zVY@J62Vpj=R)&cCvzwo&_j|*0U3*WerC@ z2h^9D_?j1Ke_Tmixpxmj)-gwdBq$;H=#_BSEdaCTLRC{^z~y)}F9g0afYrMeK8m^< zd8Alxo&RyA9ntdOh31{2X$HKczor}%t!S8$nd$clh)RHV! zUw(^v?c!i$6y79JoNNO5_TphIa{5!EK0degJXvhrfpKE!!zm?Bz@CLIDd>FhW??Uw z^lTuotdu-vW9Q(Y=H^D14og@?XeKKQZ(Vw%8&a#SGg)TEjfG<7DiDQ?#Ag_6;4uN+ zd}esu^pK@xx4cF7MxJY1Annw_`P2}-#n(NDK3FAn?r2Bcp@E5n*(&Xl-(A>alroI&Oopiv4_oQW z(gTU1e2{K?BCmT}PbM2Os#uP;qhs>GS1Gw^@TLavFL(hcA+7Vd=(tVq`-bPLsXYU3 zx8qB@8V20qONn0xS>A^20wE1IfFILH(Tdu!6AOr;2Pj*hA4?z1X8( zP{6p^8XQ;{{x4Ev_t3(x6md%Bq5Du3J6&25h zrZnBwt&c0xJo`p9S_({7R&(cU+SzI?xHD< zF5vu+m`O zS&?a{UEQTwB1(q9MF756%*ny$P&^4$rsE^j5^PPjzXYSeOYn1Ar1;|iI+9u&12_v@ zV6FL}yl8E(@5&f~wB9hZ0ri2fVR_v#0kooWy~DVoIYrdX(6;`F+~7FnU?4s}x{kK; z#KhQeFCZ19!KiZ<2m%bs8l5^Q!yP2TuYeeS&M;*#PvR*lUrv?YT~MafI`xeGB^)I+ zegWh?53(^J)~&Y+F;74=<;Kt^f7>-)R})ck0}6-Z_JgocK(M}?%N$rL21g`$Yh`9L zJ6wgwS&dc%ptp8M+WdGb*bk3pA7GepY`J$8alGbt&-G{kc(`{MTi4Rwes&}cA^lJr zL!tKr7=y|mPAA0fN?Jr}ck5C@9)9NVWQR}~L|H&?BAX6FbKU`$0yy(tYTP{e=Bm<< zd!WP3b1wnj0U1ah)sBLa7oAxy-<@iMJ8jZoTsxYvzGRg9S25N*mg;B?YQH~j#K!}|6^gx8PBnd@jxcA& zu$;~onU+h!E5WJyM>=c}0!Fa?DUBP&wZ+HBSN5$Bm#B|i+hcI`Rh`Y>KP>CkmzVxw zF=btyhQaRx4`*qvfQ>rlOZQg6K9dtLM(#i*@c;%NG_@xXC$0%i0>+qn*v9X7DFt@1 z1_Zb$^u2!WA`T&dwiFtDtMk#dT|@O8y|H`x>6d1mgkbIDrGnZ-T^I7kk&?v#Xo|9I zpn`%gIOHN0X&?Upf?QaMyT=L~GDfQ(RoNjA%AGAHuw#LmLiw@{UMNySKA3C`K(yF-id|@IMlj0)F=J9NJ$pZ?5Uj-df{6ljPJ$tom@`|a&C=2`(hU1C<-a`z7SZt z|1GJ&rOO7f2Ior4e+OShvHmYkO|v}xj|bNI*8`~CeUWR=pHRj5wt1)%sJeQ1mls5; zwra|EB1y=Qd?=PsGy$gNEx>Mu0S3M*c^rM<@un%;YET{V_<{-lpP*i&ZB%)D&6MHQTI!1B^dku;F6*h!y#Sx0}*$l^JG}bDh z>Al#2|(Z0Cp}P@4Be5+>|HNdydhh>=U$OPa~BGnzewE zvuqax$^NE?08TI)@H{i=4mA4V!xvbrUQ(3eW;pz%{ej=dC{!7sS-NX$;3oo@5Oeoq z!n`i%=_|InOADEO*Kl6A?H>eGLYd6iMDRNiIB8xcD|Jrr%y5IAelt6qe!;$l>ADEMJaIJf!-UN7d6`UqCtl&X?a{>K_v>jl zDR#i<3m$aM3*aYYrsT+wN3ECh7SI+@+XV}UF#6h-Iw5m|;;H<6Qo_3pG=7Q(&3uL@ zQ#>(GzO&Xnq$s&Ncru*%&&h>EZhOkw(2HHgn{%04U5E$nMqj0q*sWBZf5R>kCXX93y& z5=E{|YM5Y{Y_*=g-6GndgVVkKA|K(CGlTN_bBxyquv3qFGk^Zwmq>g~)gAmG=(Nj~ z#no(e(?9AeOI;zwOaE~7=YY+vi$6SFv!v|?iNq~bt;l#y`#t&s$}x22&*6HK%$pfC z{llmW@i3msZP2TJvq=s{ZSwl}L2V~k689(yP-bxxV-^+Z-eyzQ`xUY$cZ(HkG^npB zX9!H|Bd65Lhs%Fan>b<`)$P?^sH%}M$X&LJ`qHK>Y)1Fxt8IN9oQ9ZB&k04cLsb@w z`eWFQCi_Fs7_(osrn%d8V%PfVBxXEwqVGXWvde=#)W#<<8t+t~1gK<3%Sg)>Hx{NR zet$|77xb5Ze4UbpeY8@~PRdFm8BNUplM$0(0Dx{-Xu z$yu2ql&3J(?shwasi|<}Bt0t>c|~YOQ#JEOMhDPZn@~TICO?ULH-D;@C)d^Gwhx9E z_Dr*QxSwq0ovP(YfjeS$b1Bh2%@mXE)tF9mz)RTcOs8v>_9@NjpA|T6DLJKC;6D&F z?k7)ES!Dw$!^qHRb4vm_GiOr9ks*591IM3JWqm0wf@cTxo47OS!~LZXwy-fL{cN5` zzUch|@DeSCqceOWL*=D1r6wmCkmD%w&kChkdXz(Dm(Fq0CcCjyX-_&lq*GrtRU_AWof~Ab=8kLTPdjS^C-VZ9zRJ2 zPlIZ6)G_Jd#dg72QxXz33z9->F1L}0oZ^dOCQ;_x5$UQ3~6>)K;zDw{60b4{5f$B`UDU3c=GzUv7@z{srH7^*pkD!>_$|D@b4>v zVJT5{!8&rR+sf!ySd1p$K+syz)*X2qlgypzO_is24 z0P&qM?p;R-86JwvilDVVdQYQTeA&&SsK8$x4THKUN+dpj&<*Kd! z)|qa!>t^hqq7un@^dA}K-&8qb zK1C^R#e4meJ68qd^atoCmgurk-daS;nYO-8Z~1;#x3LduN_WPkss0sXo?;c7gSj&X zdY?A1HK&WV>rZjDykH!{iPFxD741{37WoD)qeD&OE>w-Fj)|)WXz0cVt)>k39SrY; z6Ni5%&QS%H90=BPTiyECOe5p$k0p5j_oJw}fOl}>!ik^{hA!q$r+c~GH&&}@`%6*m`vtvY)K<&qcJ8WU$8*?en!4eb}Xc#XTgo9Hg{SR`$ z`gu4rr+5@UZ`wi#P`&Ka7DL+6S@3uuKjcQ5S@=#}!^9Oic7E%P$ui z{a~2$iBoh|BJ)b3IbZ^xSSHW7rK+kz|JZu#%5ImHp)SKEu9Q^gIziMkb6-RyY@n^G zFMgWRn-?}33AF#Y*O=Z3!5XrQ#g&=_-B-;wV{w7&N9vx44_7XG%VuKi(F0L~t_cdA zT>fr`%))-h(7-W*y5W%}v-w!so;VRz596o(3^x|V)GYQKOllKT5t=u}r01ZwC#JHA zg_`zi#Kq`<;#k|hDavj>`N@x1q6$ZT^4i6Ck`N0uXVQo?wX8olh{%WVs>zEFH*T;t zmb>;#QQftlPbzuCI_;y16=!5laf`fuBL_@lQO3v(YBWZR6psV_FQzVXMze}tW@J)5 zXvPgMT2D>^AZ(rq%2|b_tqU9}7=g))_VX2k2c~#lKZh3ge>bTslQFnIHWLC*px659*0XaY`()eFbwn}b2!9qQ<-b^BzSd^@~oaEeAy`~Nz zqor2EqXStrHu-HoymP4gGBHNy+t;Oc%jb9gSiqL~Z&UF94d^>^)$>{=-!B@SB4W7B z4_{nr=z7Ar?aH`rh9y2}@_Int+SujmBDRp8bvU+9Jg6gK4<%ic(eU5el0Em=yilGP z3$Xa$8boyr7*A=r(Pv+;mN8oYOlFFXWK8Pgpu9)rS-$!b9PbcR7DMZz3st-vjrpr&ZvKdV`%x7*6@7p|W zV?&bu*Q44~iKEmpU5HER-qz9D-BVl)Qnzd`ISl=PnVYe>f4LBU)ck69xo<$96 z$&d^1@X48g4htLkGvk_};`eN`XbQi;e9}94{E>&nN;ON!^=shJgACh5f)Y&kIb!)fV0?I3Q#T;$K}A|<%ZHx#+b~;4!V-NHvEoN2ELHL5`vWE?h9G*5z+$FtKYTcW zNSqSLSV<1R>((#yD^yRDkG!SCE`e2c%Iq+1IeeI^Ahwad#F?UPL|5x#=9kwnhA&x{ z&Oc>yJDU`-HXnAYGt@1_j-LYo8?-6Aj^D`UmOv2l2L(UyhP>lUQ7mDhOO=4ds7@|F zd1Apb#fjsCq%auHARiX1&y?WXd{SLM#s)`I_dJZZAGXsYEYvAmv7fhSe{OeG;P(|4I5m=U!7h|Bm z+UM6~-4n`Kr}U$<_I7{F9yUQ{&-s8XDr620>&}SgljAODf1PteSonU-lV?+{89675 zIfj4PIgpFW-F=Lh66@ZKGY2JMLQ3ho9#Ff2@=J4fM~|PPaWmasIncEZ^8WZIS6L#3 z_F@IAu;(qYrEB;85&kIg`>I1)PCij9tKT=TR%*TQd4qUfu9KETcduGau4JmdxI~`w zX04RR;dACr?DZSFBs{_DwNuOW&C7qfJ}9^qTjco)-U%rW38^k^58f6l(Kqg@Y*Or? z89C@m?E1la0q=TV?rg@2wH?o`7IS>8B!a03rSLk)MM&`j;%{K{^-v!Bx(KuE zcL5tDq>ipy;-Pxe7icNXAwlWxmgbDl%tFP zM*nQi%(^@wM=5FNgO#k5TxMInrtIYe4GV_IAOA6i2mjYXg~U=#C0OesdE5jd$7+*$ zBfAB7U6LJ6UyAx~g5Vc9VB#q3TD`=BOr`_YI70v)M3yzg9Rm!{x`Ej${6$`9f}eaT z$)aDdI#D&z|Mj|A*B<6)n1L?aTLUD#CQzgc85sGXY6~W}egbxQN623{hE#^^<%_~i zZ>dto@e{(0n)?C2OsGC)jSql_yfgFk(F9B&`$vNr+3FDB$bf_bisJLtzTItlh zNtYTm5CeLQ!f*PvpLTu%UQVdlYzlR)o|iQcak}pmqzN_E)Ocr?OO%}BmNIfWYA!T$ zJI$aiTv;$7BW)hF{=*99{s`*5EMo(<3+dII!`zv6QR=@w169Zbi`BX*4VuBwV%I-B zr+aH3r>MaLvl;8;{)Ph9L`~{PXmM}}1-{)xXhsyV-(?<@a1+LQ;J7f5p%w6wq8YPV|V*SV0V+)GGV3DHnI zPF&%E-ysn%U@xy3b2yyl6P*h3Q|JoyViF;*=E0LE>!AGC!47Nt%1y4l*Ny~2s#|S! zYabT900a|HhLZUqU^>28kT6ht?Ii#Ad5#IiUxriW7w&o;F$!tG0q`UG@9~+mFLkbL zDrc=SSi+?eYl&O&k0zW1Xg=U#6#k7G5K0|z1HZJRfPL8s>$fYfsv;96RM3fqZ1Y{f zKl#icO%C`%IgzYa0T5Q0TnOChGWMg(FayH2yGGFhurWMit1tIKjzsg1;kn`=nz>LR z=bF7s#Utafw6fG~!eP&^wyNjUo}?{laGE_`y9$?8SrU79$c5CN7b5nC5q#lnn15f7 zke5UI6{UQXCx%)8K6kUb6Ml9;Vu>{*?BrZmTfP(!XPT<2Sd`ToDUGof6bwvC>Njth z8b0LrRKK(No>3T^*|B#DzWYzj-O6mjRIUbCHnXVk`>TsIKqX-xqz3PWZ2fF3tc6LT zUxs9Y-Yim9z+4tbOa=mVm16e+GQNahUOy%;FC1CoG3LWdT}9yFgoh;8d#6v$K>W(h1tFh$y>iYTZ>pL0riwEQR_&~A3O0y4lEQpE%(+%_zOqFM+T zkymhojLICytTp({!)zXwW`j)Qs;|S#6)$E%7LTso?TqMhf!x~7^3QEHq>emnsmboX z!(w)};xnv(fxKUq0Ylt^==5!bEB6fILMx=G>p?p3v05n0%jpY+3)XAQkkq+PTyr|K zHba+LVpbS};{9$93Af$nQ@T6Kht0X!j~m=4*sb*C^l20uCkNTE#D#XKDvj&E-3iOo z9l1NxEN1(;ZjFd3Ij#VIru~7$*k4L{HyKpP{YiX`m-43%)M(?@ZSwNl1P^6LeAKh& zrNzZr@BP>7o?aHdZN$F&#^AQLxi5B71mOV~f&+`8L`_wb6I7sla9e1GS$t@4&x+j*b5PGAOrely>iq7NY^&OIa!dJ*SbfxAELWR2c ze^#p~ZCvhPWxLjLLPwR#qVXNL48m8OIdjH-I27Pb{}YO?vLWI*knGIp=` z>s6ty?}|_b!SeDRn)7%;!$Pl=iRQPz3sR%tZ$VSg{=hnB@M!SKGPp%p=AQV_Jm8@# zx-f4zG1)em{SkAsTaKbi&O*%Ov*$of!e{M@-*hmz;FW8lz`G0o2oL8 zVbLY5n1{6fUj`3rYh!X?@j3~X%O|O5c54`gitA8c06i!y(;>c$HDjp$8p@?3IN0{X zHJC^VzF3j*D?%KZm?p0S5GkVBLw)koh?;;Z0A7#=EDxX-ZNEN*zs01Fv?1aZVGSwH zbf_HL@Oj@R@wcxpeJKql5;uleT%xYC+vu3QkcTW)PRq3ZBbvEbiLbpK%Ds3(zNkd= zF-_U8f5`#?w2e{>-?#h_en@Hd#-w{NQ@oME=l3E8eW85Ei`^m)-3}_nB_-Kd&5gv6 zLV{z8ASZ$bv2+~TASEFdvHRz#BJK&{id%mf(nm@$C!P04FoKT}MBLl}Wr$*K%%QcH zz+#2rz|t}d9%?M%hGyndh8w*M5UuwCc>D-vqo19 zD%&9$HhOFVR+%j54IBF|?6?9v%vkJV!_gPvbhVT*pcjm3)UqWa0O zSk2PW)#cxmF?JqtD_E!k!6%SaoBibQ)4O)*P*frdGs*cR%?_Z4|F5_Iqq{aE^Cp}5 zCzxOp5C&=bc6lues+?)frpez?7vbEL+Or*tLSn5;$0mQB`|vP_9#}970SBouY;odi&@o|Up z<+%VQLY(%y(Tkb2cCDY+VD$-faf^$Kz!0IolB%o-ou;`*Ju`{hPBF)iE9B zBoa&t6#CT11`;y7kq-bt=p6D_k~Ff@KUUAsb4w2iNtg%*8g0zlb^`=GNtQleNJ$|b zVDUN74iivs7GLZxWwe7uRRD)I7CHgc3%tfyrT{fe-lhxzA(tOozr}ol6mndLuL_jp zNl5jl2Wr3N&x=z$c@jrx>Ux79to$oT(Z;=_@%vkAaW~*zCjIRr&o`d!@zMWyKM#3l zx~ygtR&Dkl?DNP1T<8QL>=}30fB$~pWeAFXaw3G^Q*l=f6aY9{NdF)e0Si+LYH#@a z`!6VnhQxc!iAT4q0YLn^ZyErJ?t^szK*%0I9h9ws>abZ@j;(J2W^)iI<%J48naKCh zfHMN{4LLATRrO&kV(BkMT(x#fucah0sMO5J?9BR^xbK0>7i*Kxh$FBE&XG%oyk0e^`idO(*~{6*I8MH+%HY*g zZus~(N+X-TTtY1QR?1aoF_Tn-{i0tOKxrjJ)bA{wCFE>124yFFArXI<$j#I4=h}Bv zj=YUm$}%4t8R)K_7*A4YJ1I{e$dzxakzv%lsQHnZt{X9QB@o&y~HH9JsE;JJwo8<1-(e98PIifh_7}S z9Rx=FT-VV~UL@TItE!AOe?VV+0#EG<7S#l4KG%ot8t}1aV})7Rt$={Oc=I~m*9*Kf zms?ds!%*fj5iCLjB*1$j4FfpPx-Z1D2^ITyrVyWU?@Zs=aXaCNg=croVCfzEud!MN z-yHHM7a}A(Z71}M5r%=7Ev&VKrDvagwT!QmxxO1KoSJ}PUf^2*6{)vC4Y)sM#G}SX zSO_BaujGOSda1#e`YQU3x8d2bF~p4krv4f

C#Ud+bz*|DYF<8RIX?sTFi)7iQgV zG!)8kwcj)L{QYn2p>vs96Yj!E1h{Lj<3=Z3&*q~PVic+uy78;M#-g6EU~&PPVGREB zCt&C22}*$6Z7d3r3;3ey9zD4bA1p`$dl_yle|IYMf{3(5RoP~nLtzoUN9wY#@#X@3 z!hNXd3d|kxSWWht3r6w+cdM%QVR%h>(+D1RPhNgN?llML67-;K3vz0Rtg7wYQSR;z zjQwElILW<}M852*0oXZy5lX)fUihkAUhYUl0?Z~nt+sM#FtOSe)<(bz6Ygaf=BJJ~ zJB_qPB9gKRSW7aP$x+41juHu!Pbi zivqwn-kkDq7g4qZzJRLpdE!{u0&9m^E6pI{Y=*C-1SLE&-l1WBiR$9P!JK&&h^-I@ zz3LBLdb4}R)ffHu&V?zt)Pq9u#-T8p=7P%1%Wc5#4kjFi3Z4U-5|MEnYW!wrbumBoC7*@ctrL)rYTwk$I#-Y*0s z*4$SbQ^eXLKpL?R%>uH~@Hjm?QUopw*3v}Rfuwzbi4eZ|u59LfLVOD2?iW#FBMaCb zEUb&14GN%e(Umjy)s_UF0TQi@s1A)hLtv2OQNIy0pEqKTAnhl}mCVi7EuP;(J0E?%5cX!K(c}kEBkJeV>Z@;2{gG{q1|+l2n3B5BxI^o5nea57 z)H+SYXPrL?!E>{1SY{BzHDsIxTp}o}A_A_RZwok^DA4GL^U2wo#pZeep~(7lz)^Mg zI168Qhw5ouCxnS`KkVA%1*4OIAVqKdHd*8i93F?^34^qY*${D9hGxA1L135XINZ{V zgxcN~SDQIKR5?IxK(K1#0CVJ&h*)#1gGI~>gZs!M1^OI4`dlbx0*j&JI~GbAs_u5> zg~F%j=L^b7Le0bDaRq+6S1(&msEl5x##&d1vewzx8A7R*2I!zS$guQZY2GFk`igD7 z$Do3_da&#kbXK9nxA;IVD^cNrDQA-x-oGRsTxr1iNz}te;u?T2&Ht%&FN+2$)z~*% z&_@J3=vG8H?v5;q9toVWohXcVre_s=bMet`cMX|*7*vb60FOHiC27I@{EmyZ@~@1_ z+_aR>L*w2%>cF_-g2lZMaO~9F5Mn3H-dtJO5(t9o`Zt_3{CBBnf*xs0sU5dafRKXx zx$bI%@pgHqbC#ovWuX!p?5q|eR|C+!#1EZlu)Y$CJ-$ zd;|ehzaWGRX7d_W_4MWcQ=3yDdh;Ehf}<6}sIi=7S?UFw4ZtU1;5Ob5g=)-Ye;;j# z_oW?*($<3$0iy9i$af z0`s|h^^#)^wE$kr!3spkl7aqr%~u6vlL9cJFcQoR0TUSC>({Rr#9B7={k}EOJTwF9 zTq3m#Qf?)5%wi`hyiB)pBxnfm7%G^C4b{+{)-*Rvi4GeQq6I z39i}DbNa~hA*cj|bWSh*zscVLyc2DO4$VMSo{!l8!c_;7my%PELzV<|WcQ#?EvwcSO52%m9F)PXL) zOOfi3qeL`9^UJ?A=k!_zY}6+ss1JPPo|HEW0d*5@F@Y^dsME^(qW7vgEPbYv{@ou5 z*IqrJL)^M8;F`PpPwicl^G3gUELI*^icx_+)~7Ku33$*MM7HP_hL%`~Lx-?NZ;4k%n(A1?qkrSTi2!7Hk|Ghi2;#n+I(I0J)uN~I> z?YYDEccQrnrv%6FbfSTY_bEsCOT)vPnx5d^^VrTL!aMg!i%vN$AlEuF$%QC|!HyCM z*RJW=Kq)M8uLiT2oHu(2_8i`L9)L#_Jb|!4`ER_dVypXAT?e=$tIt@HwY#o?0m+wj zO&?v-UZep@0Bq`&x`f_-ezi=b5QCU(7VOoJp9Ai)#Jiv9SAH=+0q%%Y3<_(1Q~CAH zRW%4iTr-dlR3~dT>lj=(X*!|R)3Jfo#~nB4h_ZEGq&)UwCoF!?2hX? zFGQ&pmiCd52B+Fl19UML#CGQk*Qp9~K;1`80k^SU+@Br^Swxr}`#5*1rPrHH+m{8( z{AE$|C`iEjo2t(3y0xB8-DxsVSZkGW?(D>gBm`o^RuAhOMk}o%3b)=!8qByy!5hBy zCK6Rw-;}2(to!68?tHnYcwXd~%Ed-~)F`uD&pbM)3W7TQ1S&hBCf zrY0#isuFs_7Y90$ikhE3eX4umhMQbxT#+$^jBxMeZYIY%(el6-HyJ1>_dm=bxHN5C zhj)(;g2OR+*#rDdwF5#{@-7qLdzv-viI=jdN`(E%F1U4-@LeBTDV*s5AImi$5xFO3 z!%AGf+0Ii(Jz*mS@)LN4Ar=L?zzxRnsQe3%1Jpx2#M1p1Oj9Z70i=O32BNo}ft-Yx zmjGm{Q4u=lg^7(EvjlAmrIkgOc)T^;+FNn1yTC6OzTZ0A5%^t@ z;}FOcL_N2P5`Gz`!jSe9O*!&LcUTpVsus9eq|O-vm3j@vg~#NfAkrQ579ZNb6ROXW zj{~{xZQA6v?a}@)103$LTTO|-9CzXlQ~1jKrJozm?pN&BZeQ^K(DfZ~HUHoL@7qFV zw3JANl*(u)g^Z%4iJ}zR3uUyfozf5)4MoyYNm@#UmQW#@x@m}pRNCu*&ij^6*Z23o zkMHC0#pmAlc#ZQq=Xsvzd7jQj1u0B)Au5LhUJp%s5#a0w9XrmWT13Rq@vlUvMtZs6 zf8$LMoj2jZr0a?77my8n)+mzY0!Tp-%HC0#=XrTO5++Yqd8Y?6c?pf(ezU3n*!1i8 zUMI^p<00iWXrUdlQv}?NeCRgoDR(i|t^m$RUVy%?mO)lPoZ&*gSmhb=#(WF3_j28zi?f_nFIB0Dwl(jpCRO-h@kE&&TwjSIi2Wn;TJaIL-hxaM>VOC zBq5_R5O%1xVzC7j@aC07Wy^4>WK4YC8TEB!dMNW0Oh~|md5WS~P7fnCXp{sP z4W^a3ZJr&h0in>QtE=vLL15Xn0EmQ9EAAG#j}}DPG^WP&v4&3flq1IAQg>2H6>YBg zX7;W7jc@`$u#z8-WElWJipd~U)e|x$L=O+K07Vfn0>cOf0J>%soCZSxP&|KM=4;*n zOS16hYTW~_4?_{2B26ynGc0Ffqb>}3*UR7BIA4zY*n(;6hw7pMPzUy)#~id*uETi3 ze9QK9f(8nPXyVNLGIl}A&l{1z9FX#oQ_J&RMyS>r+-ez`k-6cYBY`Xq zS5W`X{|~__09l*V&}QhyB6jc&LpWC>jxMRf>RpWapYlKqGMYtJGuR)?y%;7Q4}?iP zBKA+Dj%hkot%cWVY^ID{xu?j*2)H5P9GmTz&XB+n#0Ct6LTs#NtFv1TJ6!tjhx(Yj z|B+pG9{)yz)tHGZR@bbjIG$shz9%fBS@N)}v5ztnp}nPNE>-t`E-6q4=e!vhgo35a zgy?b^qu$xn4gW-;vOo-?HtvUwc@0%TBo63x>?NoRpGHZBRd)Zw)-sSKPH7`*1O2#> z7T~SSPL#iV*xP<(`h(RdLy`dHVG&~nDaUAt%LxJP8ph}o-dNxrsQN<7$@P$;I)Hbb zCl z+oz6yqXjLZZr)e$W=P=aOM+3zHP2OAp}Z5_%O>_Vt5c{tH+QdW9Nutc`?l7n#{|L| z*>i&8fb^e$^lBlXxBQSq(k#p+h2KCvS+eILp}KlRugkvs_o?j#ttzR8rA3UjG%yM2 z!s+#AZBXImx<-_Xm!~j5ziLb1?8j`HsJKmiA!vY{4X=)N-RSs|=YfO2q=LY0MwL>q z1NN&DbH|4>nge$Ug=uw3kH0^%9>GA={dr(hnOLxdi?G~L@;1<^?b}Gp$=w=^zIqUm zAwa5Uc#9`iEg!TSZKW`?TGe36XneI^q?!2G>gzWqP%VN`NOpMHZ>F|BoI?blRbO-}UA>ZbJt=i`f*)mE6P{p@xZ+Q_*{MzF54v(j~TFvmUpRYF-1ArQ>Yx%|{y-!g`BPdl1tU z%-gguXzd~afyk@f3(Tec_C~JTd%^nx(>m|jo0T%wtzlQY_F-m;kf_r6HFNd5u4I38 z*(z71|M}oal}cx=@cZG>Z4-6Q$G-0~@c;$C$xp>jqK>Lx&*D~f_)0~jk9dih^;hePr!nP8ju@^Q^T@?SHZx+Ro zIVj7%9fWi;H&pbWU(}Fo=R65#wjD-kX zbp>dXjC^)$5%^I~x35D!xP%WNJIS&41j|OC(vr#l?#2QPDt6vFIgizG=+yL1SOf&m z_NM3v6%BSbMLv8eA{6HjNiQI7y&$#CK|r$);;xLk}%lD~u0icW(v-ae=QdxcH+2OCBU@)twxE&X8p&NYUF$ z)Tz3|%JfBTRfMO#Vm2|A9!tR>1{;a{$gCs+h@U6P%K5`(x%}pj-b?*v=qNHboXDVH zdKM^Z%ljcE>lLHGv=jnjV@P`zKz}I9=HpPbAk^8VT$6(ggJ!wd_C0#jQFi~$sp z1-GkjMA0|P}RBzys8wd1DjP}|1h2A&?u$9YSy zAj)}V-fSSoEq}KD!%THrK*$L}&chGVP-2`>JAdRSE^qAsU@@55SL^WdTc91}MpaGra zv}bC5WOQ@3EF@MHCjm!buxw&<564K&%wREFN{5wiKTl+YH` z>{;_qoEoD+gsM)A(Ix}{dJKVBR@CbxBOgS2CsV^kdyjL~@&S>%!Zuy+l01LNJr zNGE+oScx2Az`!EWLrp9}Db1ca|MXbVC!P0Qie(Nr8GTDVGTM>CMZp+8z@mWg;r7N6 z+W$@&{)f5zz2c`+{<#=g1|oHLBl96fw>ZxF0Hk2*kWGS|HOz%#1_qkVL!j!K?^0`L z*zo~s&Z`sjeJsC73$)7}IeykNhcdl}PSsqPc+~K{EPNU2HDZjgQZty7U)DC}xC&5z zVKFX4{x$NeFs;)#haE`JDUW^*w%IEc{mFcL;;d&OV_+io5h9L4bFkV@P=v89-TrGM zvIa1d4{?Q1$a{mKYT(N54&S6~pV@Nj2e`4woAqybdt&xwf@=4A?^liE9!ZQovpx`4 z7QoiN3jI6|r`Tn4Ow<%B!DbR&{YJU&u8OAz3Jt<3d#%_Y?lf@NQYC&3;?bNd%`!Z0}_h&2JyG{3;O{6e*b+CP}nBaumlc4!SX9h0(;jGs!r0hMD;pn zgR;S2!n$TJy;D=qI&5dC2i4y8yoy;{WqiPMBE69o!j_4|h(i|hmu{5DR6d7^?WhFp zch=98xGck^EK-o@&{FQJKswix&xR%h9d@n@ugBr`9v2+7@0PO?7GOt)QTSxpH;dE5;KZAMY?a)9x^oA~*LO zq+*VwR3i@-7glQ~RH$e~r;P`fFsh=*#91ZJi1?)$DxX~F8h!7qb!qE(x4$Q*?F=tw z1?kW8giQES=$wJ4)V@ibQ?#TU6hjY(p)SLN&id~{6*jb1!wuApvRMX8e;-S!CKV+ydj%P1`~K&+Tv4AAvO)9XvZLK{KtWLs z$vsFyFYToe1=r)83F93Xrk~-`+CKqn`RWQhy!eaqE%!U`Us)R5dl%E*pa~jP!bU48 zs{&JsNA%}HXoIn1iIduHXb)W}I#%LYFm#9pf@b!ur+%)}!rxNlU$ojQT zS_Vk8Lbw7X>8+D)7Zo7!>H*|TjW$MtN;Cqe`uVv*6Be*|LA!A~M8TySnBajETcFpd zm+u$G6%R-FabR!zg4x)X|2?D+G-bj8A{EOu1h*J@`B1*m6IH5!4F1O{rE#YnS{54u zj|Vaj}jZz(+^Yy0`C(peUVKjQp&fL5Y9h z1z#6DaKaZHPW`W^E+)J=!l=~K0zOS0P<^bkE5Wjbmb!t4rSOe6YWcac{RVz+!O~U> zEkd2PCzQ6s(>$}Ql@*emf4LsSAw$7S^ZrNe<{26U$d2IDT7j|6TuvW=)IGjBPRUR+y}EiPjLaJ&x{xcjG;3J0U=Pk zOg)q!nP^#HPoj{6Z;z#*_+Kh*}6nG<u`UkQTqmAAw`#teJuk$y@rqXUH^0j3U->yC$|4%NH!C7#deUblc`7b*@Uu?^+z?3 z{3|q`dO!X6%xr9<1a?VhWV!GINPc`iWCC!IRx1qpCy|3AO!EIUw_=65UK}01E_d*B zQa2?%dv-F#re(P!M9jirrJWNG4?MHn+u3IZObsG<+%3-cca4eF^g!O*ea-_>QUq&Vmvc#iBd){PYkZs z5EJQF({W&ky8(08km=9)yaDM0-gYmmt!4j&K>|jhEFHSBAgL(+MJ1rwp=AJ`2}1z4 zp7Gp!ULcsaddARG_r?G&^pJ4Jmio2cIAR7EH)R?uQxhl)CIF6fR#q2z1ZD` zw^3w;Lo551Ly<}^+_yfuqkY1plM(l9o7%=cVFE%1Q^i+D_vhjLRvZ&0(3=Q2EgYWy7SN*;K9Kx7Y>dP*7TOjxDmMC ztz0Px@c~Ta0vX-+Hjf}rYZ#hqb;J$2oV7a36530C)(qr^xKD5FN9gfX?hCfR4s7BLP5y0pcwcYSCDhgh%7lF4m#_R z{(f-X*0DK6#Q5hwJGP}^^Sl2(zrk8<3A%YR|M$1oB%F8hM>#Sa)!aCS4aR{bu?uGl z^OOac#K+u6eVHeckfG`;ssAnq2e`LoBa6Xfdw62zKmNUmB{xWJz#2x{SqE8~@nwo(HF7EV1$ergKixx$WrWf!|m z4F0rQwxhamx4`bdh!+f9`ENLP0zfpm2#Yqw4HGf_L&#`U=1llrp$&?%jebuZ9AToJ z_-~jAf+cTmG0;uTKw~)>5Y0k>hImlQo2(W#rx1GAOQ46dTK+qK!$K-8n|osPr2e^8 z)5CqseQ*tJ*x}iKKJMyq9ZJpHJM_y(u8cC21p<0>IBvj*gdVYwl~2{&OqVRav{eSM*M1J4;VLU1)i zk^tT~^cpsMGT1d{K(r&o9Eijv%!c*zM#0xEKw|L3c-O>IXb(p=xp6|&9nL~;z-`?A~6rjC^NvvFo$-3 z+eRSDXsUQfKo7`5TguAm{)puroGrlNplC7C3raThs);2Wsov+nXGcdFo9ZE>ClWcV zZ&uvKvO9AKa<+}Q!8HRURf*6y4B$T%q#@-5-ADR;@o^AiL5gRcTkm_a%v7!KgM((J z+zaeZMe^w|WIX6nO)}bnJL0%z|I>#v!xs{kKiJDB7_Y3h2xei%($l8KK;v2mZKIHb z3hP1{0Y}R(kE;#L8*F8bRz3!H|aaveDS$Tp4y!{`Jl1Cq7Ul{?|FPDPR^r*a-+ zc4XwqT1HF)V@)Hp36E<6O0wKihn8S_70_&71(;56lq}(JHfeMij9C-#EPN&g{U^Mz z^yKWH9~>$Wia;)`UbM!7l}K~{$>jE$F;9tBSNId0CcN^FrlkD$&*<<%EXOc3ad$@I zhCY;{>*We$^z@aia|EXxLkT2?lk_xTy>CU*clV!9dy2qu@##N9q1x>M5~u}(FRXeV zR!1`Urf9P3z;tv&Y)+a|j7SSkGm{v=uXify(& zKo`Rwuo36*%dV-1L3`kC07146E8yoJ7?eWv*nH8tA_mWP zfPEhpHpo5r-kH}@39M`6Qeu|73TlBK0Mlt5m~~_$iPg^_r0stKbv1`UEl7POu@bye z4lHt@O^gpfOQ%;PdufNt@Lt$D357thH1fv{FbYk1u9=Lr86u&7N0v)xBg6y#aAXug zZPuY@WwVKjgp=cANh(XG8!wSy;*J;q3&<-2%9cq!xcB_vrO}XE53$1zy{oQoO|nvX zGkRR1>loQ6v$8%!11l@yB> z_~eKk6<{KBWk=ENR=8b5iGU^WuBBLtvat*@DgR2?ruK9YftwQx7Fdoxmnx?%D* z9xDx9j5~g`=XUNj=v24<gsD1(|e{dfLsLf!F0o+@!Uf~)x#Qw^7~r7lEn|jQ zD)AX(sBwma(3QsEBpjSUOjcs81=--?-MS(*pm?V7;?L5yu;h)0O!p#1?h<$Gwjfut zL_Fylmce0PTqu*mLPhK{ChKz!43tqEL0j80T`@`(>LRPZKePTU#x{TH5-d(ZKoaT0 zD$pVf@dOPmbi8^vFA18zWO05dr+HqIuh(vC2=h1=&E9<6C;}wLj~J?p|k|aVXhV?Vo33D z?mVZDl*}D@Jtos0Q}9hNP?p+?0Ay%{7A{u-fDz;O6pvprY=1Th*5d~_)-9`_MhWr~ zRdE0WtMEIjx}~{n&F&d*Jdo@8sY__u#RzpF0FSX69T8&dCYojv02vb4e+J8yp>OR{ zBz{`fXP+6HKbMfUv@??R*&#W4_S&6|a)|*w;hr`A-zPoGIs?Y^^ z+Ao3XMNFq!y203l_Vp#@XU#S!eC^=&CyI7EnSqsrXFAhH$Y3H2wKGbGtJ|UFcRGaH zWV1Ywuh{=?9fi96@n}}j?I;GD8@QVYC4f~L-{aacC|aBKi`LZee7E!CsW79Dt(7&OUHSDtko;Rh=lC{fsF*st7D7Rd62SU*te>?3c-J zWy0yl0G$YC!fq-D`bn`t%611(=-76LjoA4>uOjgu$c9{@s(>)WzZeG}jefz;F3gUP zf>jPpw?zS*0LB0ZBnMzN;GkB}@2rz5&KRJg$z9Zd#VFuxM>P(>3Wfbr53UN0UfwMfJ_Zy^w)tZ6)1wh5JO%}@IJhq6ZE**4oN04 z4=Eax+b2!A0>ERv`vIFUj+T5R)X0X*4B#Y|T=L)rIzeyLU|C&p-6+KzM#Ze15FOK!nsu0+{~euz2bpo7!i{8f0!IKSn2eE$0tUa8AKe&qGEs@_jfp*JDY~y zD8QL!0EBl#fVd5U08lVffZ$^hU@ZRg1Qa=4)gmY*NBAjbUICgoF>elk=uQ}QHTQbG8w>n zi3Fd*Sze;NyyYoHKIC5l4rqgY0NfA3ATXCRxGH7mo;z#=b(f*u<)?toMYgkp5lJqx zUI4Y{SZmOIBYgCT&$&Ohlh5|GVT;~I&?LGVV*h+KR#!tw7Hcr4b=U-%)AYpjIhZQtKCBCJhmsMDZN+Ncp&UZ5Bbo0Z7_@w-S>{4t zeskGDFh#IkL=J&he;VSFNN|Q(m6ur#epKLOOd1Hr!ghQHsm8%?^F4V{NQzr-lw16j zgu%&oY3*370o}5BT(7aAAtGy*VYGBXh7GX%NXT9yM`p!}70&%jBEG$8$^FH69>!ww zb~yETO9{3rYy{UIB8f%SwrMdT9_NO!tQe`9ZPMcsa^R?t)E+q7oyXTid@F9ry3FX> z=zw)P0-za!$lzBeEF3pTXU!Nrw9bS2N(q9#CZH(Pw6z~dw-{xS$J7m+1K1Aj%dlI7)0>w0UW`HS zLx8{YV3VTHN?Vg1yM%ceSeNb)+UQEyf%?}tzU^uUk(QvUba)a>&vCjww)+SRdJ)7I zRgE@K?XeI_7S5KIku{YdfrA<`DTS3AL2-su5CalrNbd>iWvTzk1>zw>ph?-iQg_9m z#KbAE;}~e&gZcpU(XOw$)P`MU@thzB1K_WMrO_`lI@4<7Y)9+$Fh&9?6s!6&pfMPc z{RSa*qVK8#1AryVNT{eUW8zD!Y0bqb;_pW=6L;BjIq0=VW?8eLRc!%y?)ka4pRlK{ ze9KMU{M^(hz_C6Juz1>FFm#E_6r9M-MbubR?(4IHO00MTUUl$53iYyh*z5Gtf6gjV zaQl!#rSXTKgR9oF3;6p0rtQDJlDVw}QD4l%b$b9s4s*Iu~(9WHEG}B0_7jZct$H8Az zUkB96&0`?IqQ}7!WAzqGCHI%zAo>o2bjS7gUzWUg$1okWq#DY`YASQMfrT5_?E#(w z7@XLKGFHCJ|Cev-Qezcuodnf8Irmmk+Fk=KG5z!e?1_XF3y02*T*!$y_uHD*-YPxJ z>UeCn=exf%3x9}M2To%iz*r#*X`-_S1t zhrZ*Zd5qkDK-*`PL%?92BxRiO1RtUXN&zsxVdVB6&Rk=QvaZkZmE2vB^{qv)+oEhn z+ClJ>oa&dYEU1eL=kb_cc}%qn1$TFzLUVw1Qdzi4E_p!!?$ddzWPzbvsKTy26JS2i zho597qK^V-(hbvAQQdpa&QS3R)9DWu?GI>Si_Gej!Yf{?O@G;1NmyoBP^0g$CrSrA zfF|%!#6GI29y|l?PTJ{QAQpT8+*{Gr0~8(6u+kcBP|8Trb<>khjn*e1l3><1?AslA z{ZrG8Ae-4r(+g?xWHAIm2MHR^nx?d)C;*6$@EjJ3NPGvezRv*QRtH))*mf>93gNH} zJ-&}HK3ov|ba1FDm&g8p24FejJCHXBIhYH$na|p}+J@+KNYrweZU^7QX0{_b9&`_1lpQ#F&XNt%V533(k!~)Rw63e*s4>_5%m;hQ~W^ zP%dGyg+#prAb(+HPf{&x?Y2iaX|#fTv0DDe&+WY`3>ifVaQ}*dSi*tXDoiHqEDKl_HCN3o4!WPZnaO8`SB+>I)&2d0`&l23 ztsmzdE_!u;Z&R`0r-I^#a~gfAf)`XJ&1X_}?|c<-Zu$K{jky*ym27p=&fHu#pRZ}KOpf72ya_4)xLqZu1jfFclAxfaxLDP;}`h0<8Kg*=3c zdnTfsX0XX(mBWXntH!gcGS=~MXdeCA^!3)QeNq#%wfA1=geMtp{{KAAR_G#}#X{(; z+;V*{Cdn}wfIMX{ui}>D92_6MeBq{zewRZD5%N?A($LELtiQ1mn;p}ub;mjE8x%9pRg6{9%zyDBQpHt8)ARwThbl9e>3M_KmA!cn)wyG;fLWWjP zkG79oA{-0<$gyVRnmW+T$5_wDt5@-Aq=0FSUP>(eF~s4Sm|Wih$_3po=X*S9D?0;% zQD)$Zg$R_j_F@JD*H#5k8M^-ba@({FT$7#mAGGm)*bhYXi4m#7Cy<)1h-urieg^Ng zr#-N~o=+{U7*?7bQE?s?pY_XuxvJ)GTYIf;6RIUF)D4d+Ozk9?GgIgAy*5or{rTL^ z&Q3q+J_mCi`a9TgTi>%3`2pa-)*UO_agCSb%97(dKSS^80|324J(EXD(}m7lpLK6( zey9JueEKUHiWUm5DHrO;2vKd{lnl%ze&Vw*u66Q(eBU3Niwpjmqr@D0MCMT()~9u3 zM8!$W4uV7Gd&_{<{@I3T+mpkjvY9=#)_=MQ64XETl6j6027|xdB$)Eh{#moIMZ2-e zE?+IOFmIZDQI)*|%K*w&){gP4H-$vV`a|r+RlPEDN zLvBL@JGV?SNGxsb1TO6x9UeaYEA^CFhu8At%6x&wBo|)3Om^Exbor<`lH}#UC!Mh| z7ees3N-)SBX|?v`<$~@I#-e%=^fQdg38t!2<@v_(TqW*;tPsVsVI#H5g@py-!Aoxx z&e;>INIqu7QhifyexlFJ=3C8*UAM^R+e+|0ja}&ag=gU+`T$T1bwx$GTf$X1TI)vt z9Qy`p5Hn1S`6rrsMw-6eu6(2|Kwe8b2?mVqI%Mx`@_Lai3xxwI)@3Fs$22i=V$QL! zkzu-^n+TU}@gzZXD%;7<$fW#(WjUJ~TxHWv72cg_f3uHPb0{*7ydw4NDq_xBFNES@ zIyW@9V!?ZAs|wKIVX6S@fOJHxb=izI!yG1I>Y}N~WlOoAAT0UZ{DbU^Q!TapO;-kT zjiIkReyH1*!xf8B#Dn=BKs812{T&HkU2Re+7l3eRN`6Q1!aaBAgSM9Kb>9b6dZOjx z_su2$y?iIW-(AQ`S?2YE-FNtWZw!S?@_LQp=kjKY1x)ygh)j)GkLC4q^*bj19OLZp zrcd5QVr^bTZ?eC;E&LkNanDjy^+z)k5)!Z+e9quK@U9;>f=_s1RvvjfRc`n8bSX}E zO(To@>_Ox|5x(0AUef@D-+9cirS}?bq<#Fj5Tm_*`^h2SEAvmk% zF~uwmYEvt0O_Ximf$~M<&=XtWO66Ae_I{vjcQ$Xp7{WL%&tH9&CMpd>=6(t*gF`~Z zu{(OR*m_Ep86As>NS1E#>AHTB^N$++c_^mT%|Ag8XUXr;(V3lxk5->F)>+p*>txv9lL_f6;f|_D_1RNnE$e*k1&EFB#7 zWIfbVMky`uEQ`QpM_5cNYe|d^<{40alsTsrrG$V*gXI6Tp&Zo7AZ6Qu5$KdR&4vDq}L(*^l>2YxMeNho$ zTjhGNLshT@d~zh`f|e=Sq#mozVU~>CXy}`Gjy5fWGR48|p^mR+VWQuImX3OqptVX$ z{DETIyul7AoG*~6G+qSPIO@)3>KL<|$Y8oeJ~vUJt*hIu9N4clIhd+M#^L616U&wA zfu{jI#Squq!J{|Csc^AHK33iG%Gn#2a2b>Vv5kx8;K{w9Gs(=+eY?Ry^7bO8(g4hv zV)26hpLR;nT8OMD3f}&JCA8ZJ0Uw#mJ!m_@tuc_>ESm#qI^+-OBtBVhkaS1@1h&f>v0fOdR2(0a24{1&&Ndm`f^tZbK!8ff89=dF zfDIH-{Vg#36h`GhL(u8z%WJriw3Emf#ZrCvROsYfl$j?0#~OZA)tWy^QqO6E%6jFq ztb5C=5@%(g4kOAeV*EImH)GQR%zvYjw^fkw)6&vXQv9=MnWr0>nr>1VCl!Ns28slV z{Or5ysu3sxbj~|EpUdTOzhE_8{CFq|`Xe?Fr!vEGP1G9upYei|b-vPf+-7AxbUDc# zr#*{&rgBRbYI_~nk|xyNip~yMD>*C9v=3O8gfc>~r=K;Yk8)NLUY1VlC22mqX z&PE8-uOWtsv_@18LB0{JLRvn6;yNQ6IXJM4lvJ_Bv^Ss(O^d<@)eu5PGMv3^r<~C6 z*gL3H*h;F{fCf>IjCrQu^c*dx&_PlK1@w&=YycH(D z(=#&_KoqbHS2UI}b0zUSHLE;$%GU&L4vxg0dTCApV^XT#=9NIkB;;k$8wS470}kt6!6lskYs3$zq6@+dbe2+h${9V_TPz zJdz4q7&T4cN&4Zym`?$LnLv92J`0u;bpfE{-3Ub>z9_-e{i4fV zN-}4#aUYODxT7bw+bUSrMny&ngA@cOkXhXd+B&3~tJ3{)y4v{<_<0RBuToizR)4v=Lx2|pV;J5e|Tqhvc2w`ftbj#MdY1{G-xm!4}5@k+Z%hCP9 z#ei7|mkCQkRddOUvV8gGu_(_Xp5`gX`;+bDoM}TmySa^d*`O-!w`5H0Vd@DxSPW#h zDjS6j8?819nYn}meaa%-D?r($GuY4y1T5bwX248nn*case7xh2yrsX>ii0L=Cusnd zYc*G}P?b6-ePA`U6E&>b2O&V8r~Id!#I?0W^Pwrm5|Hw+z~ln%$Ung!jeah0q|M3$ zi6CEpIH5@!3MWoCuUz7@-}8y`3>Q8bkwk@~6B*+lTAWJX@8NMyNTpLiR3ld(71(~| z5#5_xz?644u&fosK`hY2tTqRps-WW`jTzHll~ChgaNS}qq`%O>EE_7`(HOaG%+jq{ zc-d8mW#S)D%mG$yIi5NAhjOE-J$>Urd>`GM zmDhP`3zr!EH+;UhyJAIMUhFcPTs`HcJvhHge?16Og3t++I?ME=U~)Fht;C)#TgdTY z?^NIcK@_o5J(*%UMCZZ?&Q@f<^lTUXmTlC@TfBDt@8z^#&5NG$`#I26c=)h*)Iojr z5&CaF>S>&coaRMCwd{%^Hz$q;HJ~2h$5ML5GdV@g$xwN94Zl$W~mQ4F2!_r zZ>KJ}d$aXp=(n(xCch$N(#&GoO`na351bm7jwf#(rw0aWf6Rn{E5N(4F_(jN%JpE= z)i`C|nPtb7L|=ZE8_CN&sG5~0n>FcHYU;dVi!OVSCOQ7QF<4BG{zd79^kF?R{&xd? zyIE5&-}!u%+2`ReCESx=UU)oCRx4jfUIdNC%%S9HEkJw4% zLu_?)Zg=gr_y;d^FVNrfsRquu9_QT&i8EK+$f2S>yZMP`*)Ezt+u?DNDV@!$D$Ie? z!j);Zig-K8&YQb(bxLk>Pl9jI>d7&apByuIy5okEYolUcX6M|m^dT#jB%l7e+~mab zHV3X3&hFnqt`cg;Lh=>`T7=}jZ%pK)NZ;wHNHjO`HUxj@+KyQB2S~ z&&GB6xZSvJcTd}?cy0RQsvhMk+5J0s@(ik8fpzO*8h42$-K`6LS2~<|^t6C}QN68q zXVvG=F(v<2yoNqSB`gh+{-ZzNTiSI!o*YFYXjKk@$Gf=jEp8%9DT4O6iep*E}>6_s>>{LDX#C$J^Y4#1MRMo zc?AEY=YE&|=p|u<@soP`mW(;UN;yQ{FG6i{TwRE&^NY!UGIjhkj~vUXIT`Bd$(=GY z&PjEI!$LkG@|#nWV)C7(A^+9@`EROW;y0_y${DZF0@k2m^46zX(l-3rN`6-`D;UC> z;fnhDrPzFe^yd-|aN!w%Kmmy5S}WRh0Ru3$I)$Jf5SOAD|MD9me@c8d=x1qQ|4d)* z(n~3((1$WLRpu8278#I7YQmaf2zqxQDvxu*n@dl(Mz#{5{YTw7)mRUl7+0I#ng&z2&Zk;wJK0rti zs;RA&v*C>r$oZVdM13h0F4c85myQup&l>)^{OI{|@`nKjnerB60!bb!hq30VYhLLe zoPZd0tIrau z5-o4%5ImzN=_Ar+taI#qdR;qxA`4d#q01q6yB$@bl0kwOQW9Uk(Q;mzEILi09uOVi z+41uG3i>OBiF1}@9a5sNv!`&st>Z)C6AI|JYrZu3M5R!z#ZQ%S`KaU#~@_bCV;uc4q!_uVqLm6#0(RNi(_Ub-9+jc4e>u{ zyFz~z1DKsWVC*7c=Bw>-fDzi~F)usuZrwUyGa=Z(w}OdST(MX5rt^zQtDxP*a+*G7 zI{0IZSJeamu#dWoDNM!_s0Yy8J9JZ=m3aCvr4AxGRyw6$)m_|`>4^*d7(8+--+~PS z3eO*X1NUxF0gD{Ko^zKxDb!$_t~Cw?-mFsehkPNP9)4ediTq3TioUxPaQ{b-6+M46 zfvlrsAfQBPa}fc~u!pqPoSB^6dmMT6Ut7WQH3h=hS6xq6tqCNu(tc;BSIyR;ys zVGcr9!k`Qc{G&L|I0`YCQhIz9Vbo0@#)_=8S=HP8if!2Y^U%NDM+dvTvkRIug)4YdB z)Lu>>B7GegqRE|)J5d;=dn~Q3+s0ibZ~KU-oBgWGguLP{v!jHnL68b1W6LG_5B1bx zDjs$y(f{VF0Y7zt6*!3Unbn*PpeDQ`r!T=F3h#KdWzT=c+2Nlx()?<+)HRd@`0Cje z%rqK4F%*tc?a}*yV!BNr4A9h+{wZF%tGg)$atA_K=8 zEcbrhUn~vlrRa`P%yam8|5nmG!5NDuehE%*fcHi0l0OT$! z^0Xo^!`=;FL%yi$3pjepcfJEh0zTAtPqq1BkI}gRaKQ*PLs$}8DfY{5L$L{ zF=+*gK>mdn6%H{dL1sDfAe$g21fbsUW;`3gcH?JOPW0pUMdHWEN2MwnTs?Go%2pU+ z@W$Qb4W<-1DYS0_Ls+tj)Md`ZqJ5*9je-~fbJ&jPfP z&wim0b2e!X8IMjBY5G^IoQ`?Ox|TKmzem;DzT(kLx=HX|9qvM@FaT59*Os)mLWYu& zJ5briN*sCZp<9?=7pcOzHP~ljzjfxMMK2Rez8m|W%jH-&mou%CooT=gYEx^j&e(lb zX`+?J`NuNXIcs23AW+7golPMq>+uHY!cHLS{Wy&1*6S+6@z`gj0DY%V}+ufkgsO%Wj|JzLYMZWf! zP`eqw)aR6(vtF~ubn8P_M|A=zkxlOpi>Wx>@uDjBF3WX$ZU$HiegtcKtk6&3_z0rF$bd!O81%Stwz)@f2l1+c& zw&Kt8B@zaeQ~$I56e4Cec-nt`vQ@h(?PCU&7j2+NVS*{>M90h~!!Qy0zfl!+Y?I85 zEGLgv(&yCXIli|pju*Tu{6yT7)?ZF}%s+LMp~HNzm`jAAApPulfM^5+Oo$o_%#X9u_ zexUI5c=9a0`#IEwBK_#gmoHVIYxFEF4R|@&1r6Z@$Y$IWXD0aclXsc1b7#|^&iP?% z@q4ZGOH;cN;sfThz{hTaoR2$paUp9#5v0KG8d%6e8<-D#Ka`)jv1*SWYKNi#1LA@} zTKbaaNJM;V{u`q1%VA$cT{LYfWqScjD%3YTNVYpdR#9bUg3K-0mS#|bNh%~kW3T7_ zU69A_j@{!fwyF1SSv~;daXNBDc~#t#mGqSwaV%~~L@iW`qgT0Mo=G1K=kdd89Lm$o474Mn$sQq#^g`t?A0dhXAh zG0j=OVq2A6a~yylLZ+Kk#y+WRd&#Rp6hAYQE4V$G@oZDSF$K@F%0wR|QY#@eA-gI; zYoxE|>b!o){mzO~b+~=+llzS4k6K@h9J(Q*ZVYYB5hI2kz5JL*Erz`19JZl^(O*B_ z`VEi|tE#*@t&)C}tX%;93rfy6LN?)-%++*#?xH#b5Dfi*9lrx|Rlrb2 zeH4gkls?qdJgns3ye%-M32Q_1RRy^amcgzx<-&F! z726*tT=u*nauttsl*=0Y6RjcuiVVB({5}baPMqeEV&tgJ8)g(&9P6Hvw*3yX}ps*p3nip zDZWuZG`l-b&!?}u>yP4g6N!To^z)Ss8B@D%t+|SM-IO1^vW4OD2jHVD#8 zJeRgC7aCu0mo9G0&(ZA<74gWS^WHuBH5dz5F#3`QmbmLBs;d@7l9Rm~I?v^{rNX5n zaiY?uPK2GhTn68!nQ{x&``T5u!w!anauDTU9$4<{NnQO%*Ob3xCEp&E| z2sE=8>#J;n^i2GjgP>yQy@arhq@Q*XiBpSMFOYC#8wDdk>)2zX!64Z*+Bfj5 z0?6w;Z!hVyy4?3zfZ(m`**3oZAdqdswvZD}Xq2CNPj`M)70}@aw4kkTAkiud_f7|- z`K@kNyv1&iK>KY!#qLO}p-^AOS8ZFDl=F$NsLWOLka3@VkQm(pR=HgA_@aC>o;{uJ zxbR(smxBbcTZ*bCJQ9$iRieCQE7NZoOY*1(=0oQ{-ME=VOsY(Ae^!vTMD!@cVBS|@i9>9IFsY; zG`}sOy>Bhdeg@xSH>5wtlg_{xK+47H=xHO%IbfR0KYsM&JqCM1Ch^GIG`+Wg$y*!G zA_8u?Sq%Zzsj8}eaVu@yw#A!n*hF>yG8oQdfCD8K?E|NcjEsE6tDj1Iej0_t5?wJX z@8D98Gj=CWa*Is?cusK~UxMf+m~{QAkiPxn>h?KKAMXsAb%+Zg!m7+zNC-+~u4m3m z=)AP=Y1>zJefqR$hdyMVWjcw%A_BMpNo!+EJ>guzK>)LJVr=O$2>8iC&^b0PCnQvF zZ6!WIcRGm`F{Lb~lP*RvE)$f4bM0Io^0o!Il^LKl758++HaSq_DwK+(S61YTs0+bH zfvru(UJ@dz+zuy_mNi710wbUUyuVbb&G&BrtE zfbg(&DuqZ5l2V!AXEkc4kLzmnxBw!tP?>J&3I*X!fE#cEv`S8-JkmD&;R3l}Y{GZ{ zyR$M@c7W)*gKTG#_{@!P+bU>IXLE>$2=HT{L(H4XX-Isw)U|Y{4-8_i*hbPH9Z?omR(|0yaRS zm;6{lR%L$4vLO?|nX!fq=@!Zmbe6($w6wQR{LxFH4jY^sbR8}5vtQWJKxL@6IM-Y7qT4VBG+kl=+X9q73rCjwRz_6jG9OnJhQ-ed5dm;EMUnet=V4GrXnDS*-75l51KA3|EkQ}16&{L2 z#PycmmL1giI+|AneSg~pCy4^Q4WlPy>u2eJjan2cB!X}zCN_Q&rj{z&9EMw zQN$dUH0tHOc=cSlZ%*&_Kl7L!-p1#;p8R>n0}0^(&J=(u<$()(<`EU~ZmbLQro0=g z*b)}g1iI@10bs)%B~X0C5p@E^h(G*2ov~FvbB)-?`omVbAzuZnh>#faev=%b9p1x* z+}C}q^!@xWlFtsjcya_F8`A*tpZ3Ps?F$T9+F-*Bm5hR`xluJA)f%8!u?Reh#U%Y^ z@rFl2;m`-mHZvw4Fn3P+L8g7)`l56EI{nEo8V(FKwS1M)*D9kX{lAoVCqB3+IkPVA@>;Oq?F#EaojIoG%=F5=A6ydRoGrwuW@HoIL)Bl9%lGa*uEUbc}`ow?v;0I~d>$i??ZExr%z2+0Tu3;SBFU~$Z)ti5kz@5Rs)-$%x5 z)s8icxO=K#f7T2r`NEC3SCsSYT;|Fi??KHU>5xgkvgyzLK@cxp0_6p#-5QveS$>Du zcDKsPzK;fALKvPI&=itDmpU6Ey8W)0iDDi}}&vj5DbZnfL$P?7rDNKYG zl=6|+r+SE5IBLhH>><~pU@i;w=WT2aj4g6I))Um_Yc7pCaN3=xFV$d?kP{jb9^@}o z4{-$}m*?RMpBs~h*RZgUKKri8^TY(bjAs|k*ozu(cTD|0e{&T5$H530Sk3}G+9!&W zoqly*>YAQhp#t&?0h2%15}3pjHa`yCY;0(FnEbEBQn)M+Y)RJh961yMe}oV9nEK(^ z$Qj~{x0hBVcs5k+qc7<4Wz{DME%%+|_e}$ExFc3@>dqwodq5GNqwN2CiP@8<$NNBa zqN;|DlQfgbHi`QplL6)&v!i2Y$rqt=Vur1JVH)?RnMAZUJs!>@jwEY+>(C|d{onJ) zxn7fgK8cmhQB%0^EHUvF`IP{Z*D$=FUo;7H{ph_5;4MVt&i5pH1*8ew^9G-R>~i6m+fN>QLvJ z*Mc?QCx5t`I34gqVvdnb#HlA2t!LGu-H4f3QZThH4S_9aq`6t?^lDDp{k~4 z0duRQMz_3{w{|NMS5hY}kGKGJ##N2Ox6YmH6_|7X&dZNcyu?mJK1xHQ;9w$sGUjOR zzvwJ6wSi_4^A}oOGP`6$p&H1z_uLu$xgoxtPk8#$dXgA5dG(|%DYGLS0OGAQJka#4 zW;RhA?w{l8|Gen8GTqp~!^{&){X>7Z%qV6@A0+@}bbr=_e32)J{byQlI<0#gpk^VE zW$t}oa&9#P3pPg`o$~4=C=J}FAl68)z#lAD$d>T)EL+`~NzeMkV%iwDAZw!S#mEX3-6bW#Afv)sN{JdsPo|bv|WR*ZI_|HQ7Woc;$to|Loky zX?)Ci1%U_YcT+uabN$Zt1N3YvbriGj5l27YnV9?ESnPjPKFN?jP9k-;J{!bHP>j>2 zo?+qCR+dITg^>mBP>^3;xi(6Ql|`~ zh|dX)Fn7AgGXx&bA|y}?$1aGt3lyJE%y}qNm(&L@sG9S+ijbe8X&rkbLOh;9e-juf z$I_cwk7f1Q>tv1MD?wwz;C>;C#zMK7N6F`OYEE6@N=*vvSY^C;7_D)ofzf%Q9iKm?*HGud!QW}AcTyth;SFOKs~jK zB>FoGtzyOxP_b6RvdpzGYzYUXHKtJv@zO-WMLTm9xC8u5?zo#V;_pgXTcm}JM9fvh zVjzNb%pNH=EF3f(wY+|eP)gieKWm+-mA;qyCO7edA+ zK4q8624M@-pUJk`-G#jlNL4e_;~;A02AGLfcFHb$;P~cB*7N@xZu*zN^`Wbs!_q}`SX>pb~%(3X1zI>+I=!%2EgkG@loStTJ>VwWB6=1u<90;gC}#U2UYY6+Wh{mX7D884=M!|S0OW(M2U zjVL(h=>`$h*|>?;1Zt70W{;n4$jtO=F)5SH_ z1A5V5oLW=C7~)#NeEVos)R#^`uF2vOkRe@y+yHe;oO|Uuw_@rYGXcd(WBmx4uH)A- zD5s&9mqmSg=|o~D8|C7pZ5s)me?)VC28DLoLH2dNUg6&7C z7V`ZNv*&HPULE~BN1d8SD3O5edWT&kU&j*4zhSKTq6^BA&Iur6=MX_+Y?1`VE9{Bez!c;5YJ4m7@ zHtdfmn=2}wS)$JGI|A#-zp&k!wnQckq`G{XT3cE;0eDhcwoaBH4C+_fwn)bviL5!w zD9i#lvFT0`QDRbmL9k)UgL;aQzlku}hxwAE~m2C{nJ+ zOO9YK==)9$o9u0-8W9~JN&fG4ApA|Ll9eNxW*y1DLh`t3wvgRc(@go(6=capUG86r zAJ;Te&V5n_WqZ$RZ2pja?H#pgj_@-Gdb{x7-9xdgazMDDmF8gd5%Sj&32D11fBWV% zdBhtonA3N?+DQ!&*X)tJuJ&Po`rbaiy~0t_l?K>OUtgaWC_bJ@)BWmJgl!Pe3cNp( zp0F^42eZDocO~*=G&x3D_9w%Leey`X0^EWZ+Y1o6CfD7e&+FCe*RNkXKv%yUrr7tZ z))5&Y$qtT$Xv6e>LtsH~LLWu`E+x^m#3nHBEErc=0E&ne8Oevl-yy##>E2F;^F+xF z2}j@JeDh{fXXmGHQsn1U@>nd6HM$C55PnKFLM~&6L}Xvlygf_(kxP4}YZ?Zfy_ zZ4#s-yk^>+PNxVF2GrS3?AH=~+Ver5qk@sS@JEgemlOrStbwwwj3elmRe*xVrqn{l z5476}g2Dy(tC!tnYkRx%xcyJHprgIUgh_s9OS1g&4E9T^X$PXF=YjBxAG3Z%o(tb= z{!k-5-g{R#l9yasj?KN>B;6rWoMocS zXEU?KnB*IuJ>{EcyhS|8-;2Z4TVuS~U|c5f)Sy;mhKr^BPLUzqd&9{1H?{BF3uCjV z9SheG8(D6QoWthe3g*5-0WK5rFOwb~8XJ_p^f9LD%2Ud1Za4>zI&qhGVY_JIWUa#8 zV#Czw2AUkbimsv$C544L6&FEQ_FwCJGt<>PoUw&Ydf!GxPEq67trv1G8EXC(v7&CG zx%-luSJxcG{wZMCWb2n?C&Kd?he4|$HgCY`w;2H@aNFQVHQM27`^72VrGI%}8Hi$^ zTQ{^x1^}d44mv?(=NfEyp8p|tpH%tlCQ8vRO`cgk@VC=*nP*D<#UUAA#Wk>tbIM=R zHCXt5x4Xr-;B4Kz3KKi!!S;_QFB`Q07X&|~9jA$dC$Ni37r^Z7DBGj<46C4XQ38o9 zWl(i&7I`}lIzZLf0e^nm^h1fNIOjsREo{fZ)ZHp2cNa3MY)k>eiHL}}0j3od2x(!n zKBwX?V&6Z7c3*Ow=YBCRdKkfq!_O8=Vd^_mz-+*eeD1?TcD`m9&DwVzUO)2Dun2Q- zAnvuxA?b~P*+cN#jl3DMnk}$ON}(^=^`C%FFu*tn+{SLZ$a#ZyJ6b|nKe_Xqic|^t zO4R?k8%SJNM*)S_yV<36A%f28Es zO&MtG=fGx*T@!SKvhvIFR6zl1;$!0VoyxZzKTI6ljmn)i|8}JO+lhs|u`)4_v>gr^ z(3yn}?Laq4)UAfc}4F9DxakGB`8PxxvknCO?@Eo`a?c z=h--`nMXLBM}q)%IT~Zsc&|}rmMqvsL`^v?^3?HiQYYSp_^Gbi4BaL2Hyp2(bx3M0aDrn_`CHHi1UPm>f2~^sc-pH`JW?pS?vd@ z{o3R&0h~2!G4-+N%jf7HgxK8l%#^S&wBYT)200&7Y$cj{vYOa%*gA6!Np&l=!u_-3 z&&8~E%0M-zu|A@MwbZwHLF8#Ar0}Tn9Xuu{CpYM_41Jv6lZ*II;nF$dIaj9(?cjyK z017ziH*35Sb$;Don|R}2K7sT9JEQDOfcD9rTK!D?b*Cx6cCA#Hv~5amObRfLQV&AI zq^muR=+nv@P-Sb7lp^+Juvrch!qg+l%uM%v78hmM_$E1Q0hnpKM>W?mb zsQ@26WI8%yb0EtzFJBHXs%@|kdVXI14xO`tGQe{`Mj$%f<7BS=FO%PT)rk1968_vK zt~0@6&?zud&2a>%yML+!>d5-=C@!G8Eog)e1%s4Z7$vSzZNLNl{DD$u;cc>+SldL5IaaN52a5hqA5Q_q?*m@rZSv7`fu zbZ`I9Q8j_4y;Ns+D1$BXpvMPBg5(70X6`nu-55?CJBp2hanA05xTm;YBTV|@#FzEQ zHd0bk(gFUJ<+c_0Z?~O_CL-EBibZnrp~@dxeyiHG6K?-aUjz+{STB(DF5hVHD|L74~X{6sh%$N;u2H5t-n!Ip;A z|Ir)2t0G!^TC!|DVAU8&IFe0SV9=5SN|E^v%fka;@|Ak)G(5NezmF&O#<*#Uo+#2iN>d4N~8y&zcsepYsJK&wjY2Y?MdzXL$=$=$Sk#kPI145r} zR2{t5Q6R&Y_uz513~cXn@;s1m14hz7-BCY1bfC<_?T{16U_0K_+8;o4La2S`jQqBPl_^V!&7=vSnp(GUZa|4`bB*e>?*h7QmX_p^>@=+ov{^ibl& zz(49m!5?$+P^rd_4Y%8aMg16VXB2 zDNRd(-2Gp|(Fp)$S1{$ZX@Y~j4ahMlsr}a~9Od$sex6z4hp9FS0`K`E84$R!`IeDe z(V?+-)FIru+ID`>YXovj5bcJEYgFv1Ky2r2u{=%KjtF1Tq6C70PSH2*XiL;WDM^^c zK5mj75=a$5vcQJ9_4tBqR~GD?!8%44>U4oYaRVj&TPuFVSOsPqi0ZfxZ&@0aJq|2h z>!;Xehm zEMfFz@Cc9qc}`^bK;q6qzRud57AyUYIab`Q9`e8-=tepQ{Uqp)E9+k*I*mM+hOBN3 z{ZjPhRY>PsyhFYUsm)T4zANS{Wv@68N?i9RR}Id+KCV6V$rU==8V)qVydcv;pyGX^ z)RwlG<-7TGCwKmmqkAVdpJT)NdPNapADe)rBhhii&U~-vO!cv`p+qhXs#3!zp_M&F zcpcIE3HY<7pje0|_dKak!N~tTrtmi{pbQH9QuJZQ!bz2J4gDjtNY= zcG(3-#@Ue>sKdl|fn3;ja(@O8jk2BC)(~-T_WfA^JF-LL9|p%7L#phlOoE%q{9crN z+3Y0oEDs#$#4*6ZK3`j~P9Bpho{$6HbC!IUem{CS&(y~%u!H~92~1sZ#~9+JgAUao zSy|%5Q8v|Iy6HFFRT?OB`PTVuO2kZ!`>re0KK6ZVh+b~shJkSn2k{E*FRwtD2UTGq zj6=6~)5;JLY+4}eq=G{t{B`5dO&ZeSxa5w_B`jkt_rLAcqNGzl4db<1Cw6~rlQ_;K zR(iKO^;^t#@|8_avJksAp>7Xyn3+I!^~zIPV#AKTKRxN~IVtCRiNA_uiVRzjm&W=^ zwiQeb4%pi}tY9^deU+##MFDa+q{om*fG@T!=SCXzrIy3mLWv^_$LB;n;AWA8XiVBW z>N_jcYueVb{?wCbC-Ol_@&L5={u4Oe_uv3zx1i3UKs*lH`?w>B3Pz)W-m6_#aU|Ts^ORMSb{Bh5nTV^|!Fa z6T}8_>%DHS!@@0Wly9$3Enib|?xZDEG9}Phmgp_PD3&aH=!*TE;r6ws7*p2PPM~WC zZi=WU({3t1{%I$f6@YEt*uR0wynD6QDuu3>rN*NouXIgAvqes6T!?*JPkBUy6zEXE zpxaz={z9268dz`{Fuv&x(YNugQk)G`~JHF>>rMwZaI=s(#j6eP+%Dm<$9-7$M9RI*G`xb;7 zJ*XX9FcmUi z1W=w1v?daq-Jw;OF=f>N+Q}e=Zk~N90-UGart>?=UBiuFfdLlmewhDZ=Q6^67!kPp zpMw+~=I+DQ44dDaQy?4!-_*bXXHGrf?&v+;7WC$C&2@nlSd;g@B#e(VSjxZ_q8u=Y zo7AR++qd;0^9u(C7otK5)j+WDz($^#!p`|Zp6QOiS=nVU>n>pxzvEVK8LEh2Zih1K zh5p%aS{;NY>K-Jgft*gBr~mnJ+_InhD_;KcW!4|8aNQBUUZNDh#Q6Z+=us%u}O9(@I@hjT|Ubc0^ZH9@-wQ2jvZwMmy^*pon?DdLL(QJ)e;9iJLnA39yzJ#4l8gs?IN)h2HT z^xXDmQ7xuo3gmCffz%OtmSxg7P4^*$cAklIUn3WrBaZ>)O>hECqJ&Z2NXz{SILit@=;&<8170d%{MDpU#DsJm~_@U=-PS!Teb62fiTnn2bDhzk&$QrBD%$ zSj>YpA|@d6@&$A5_@;TJ3IGLBtU-pRFOolAkub(?PX8~|awr*e zDutb_8RUyPm*y#nCrXAO-*=PH-2o(lBuocDJq26i672kW6%{brI`1Bnng{ryz{)lw z%TE8cYsJswv zS>ibdX+YLDI&S+yV(7d@viBH#PBC#B?ZtK(^|APc%kz{E$YqS zsey~61+f>k@Pqh ziS-pQZ0Dz*!`5cDUz#Xv)k{(=kPBp#p$v^7JAExpPGISK*N3UDHbRtmI*=KICXg9M zVqrH((DXH~%Yj%HXj_~pY>lqY=oYX`XFUswYBtP6Ui8&|31wsoQSkP%tRf-ruvv8~ z0OY;M7plKXz`?-J^0<72jee-{g~ws?k4pjpO;rY#n)$*)uVMhuS&H=6g0?G|Cyafw z^^ib5$w5e}C>kK3-S0#t_*C32YPmrppH=wZjyE+Jv-u@{oe^?p=n+k@M1X0>Y)#fiTNAK}X2TgZ8(Ul3licp#>U1J*O@QoI8HUAJxO=Bcb3cy4Q8~HuC}k1;tn}r2+?QnM z{W3XFgT71aI3C$XYl*!hY01Eb(tC`Pnt0*EZ;Ia@h~Uk?XS z`_Rp~UvRQpo=gUmz@TgpNP6hGZLXl0d=-{xq0#j8u`}EezfQg?@)Jo-F&eJk{E0hK znmBN$nv39k-^)n&o$a6a-DKOSI1*ImYx;8_HqTH$JNK`4fO&|h->j{+k?SgxKYvCk zze0MSobBmP7s!j7pr{;O$a_=ZooSE4NuRgF0kG_tfyJVMYua#WUkK|CVdg?Mht2jF z%toaqjCtTp34m5d#4yn)7D=iYdM`i`+HZHHTY9J6*Dz_Za(`|vB#_=$JS7XPZo|6j zkSqX*z}DWPWg%mir}3oCz_Tpp8$Bh=lFjLv5@28(bm6cZfOd8)_^qZ~FF`k&zHWzvhd^(i4Bb!{26`CI~k4`mX_U-EGIs`g>Xsn15hJ1XN z(7XY%^fFxHC!kq0(#~U0ztaa>qJTL3tfiXfkGH$en3HeID>ga?nx{k57Gui;NgK}z zH%cGZxOnw-tt4fstflE{dj=5cJ5^FB@XB5TPmvxJ84p6xO4c+y^0G)X9-3vl$eMeY z9wEIFqv*-m7byS7q`2@0jsy9DP%e|OtEM{@3Uv0`xTbCVMe`3S;vOXwsJC=xP0Otk zH*=@#X?pcfSJ8bs8LuV(q5*p20%hkyV|7Pas<-BM-C-cBbRi-UFSpRz0H%6m3p+P( z1st7dhKQz=1DvVqf3NZKnkkh3a--vR*^kR+!^3V4RQTOeQuyAl#yczhKy)-FQ36v9 zx3VFI+~F`OSq*NmTpAThmz($A0u+S|Mxg zG_AcmZZ?ll!i*@XkD5O&YF@qfA%TJz)`SfOT_hZ~fGt(Syx)4lwmmNsr|Q?cSUM#4 z^uV_!C`=FAdddMGJa3J*b{JA2p}!??_7E;EfcJ7MrjESa2$Q?g%|ovac`}ajVr=Wt z&vKX6ftjKGSL~9S4GQhtbWZ8(17TM7qYt4M@PAFn<8hO>B!ut18Ts-3^`*9)ESsh; z`d?Vm;$v>Wu4ML*%e<1g#H6>=matd_%k-}P%c#+vN*xy%2|W$t2#4%z&9#BDt4Q;` zp;js081X@();K7E`!g1TL}qy(lFJ~F#z;i=LXX`;Tu~KMAlrmEU&QP}MhyNMAeSx% zus1Bb+s-PpSh+6uR{NLxTLnN^A^iV)(}f|>uJ}-Sx;eKsGm|U(Xq%IhT2BFR6un;e z78EYsAuI&{TTg9zH%8?Nzh8USMhW=gF1x6*EY8P(o&_$&sj?H@*0!$tXk@4z*$-7{ zGz&h=PIIgFeBAJ-MUC9>a{}afUvgIR&^>Ocd;IsLKCqn2g5G2NKvrTYmN@69P^TeCa%zu82krQPSl zSvL%P6YbGrh%Xr9O#%7W9-Y=Ue}Oim{%{;7R3mO~aaL041)Jp%QQ-3N_sqz`<+M!Q zFL8Y2+cAmT8gfKKI+Lj+{vj>-CmFK%y{-kmQ&$35db}h}gGQ84CKSo)OeXW1k9Diu7Ct{zh-0ybs{Q`RFt}p@S zer9^gp5>!wB5v)6cp+gLIt%tMcQSs8)RQA@Cnn5|eMja0B-;B@2jC5j=n4C}kn-&; z=Nyanl5h0q9b#Wi5bU+B=1%QU{Mb>)ImhXVexopB%=A8*On_{AVYN91149fnH=~pN zUyl_}b)KmJtj~uElPRCud#}biTELG#gSxf_xf+LPEv!+j3)m{c$ezM7F&u__vCj?^ zy^(&fXSp*i9ngLdmJ2fwQT~Pvv9NviPc4CG8#1$>e#^jBN>J0t6h>@(z}Trz>0l*TP7Lz6Ek@ zxeQASqU`q;ur;|WyaSA3jTY_CQ!o9Qfb!;Rqz97Ax&4bY(qf%%`QGZ zR1!dBcA>p<(GY#CSkB4xwKinc*cw-BkAso~60i-&I>?GRivglSNYz0|q@+(R{+o{tMq_&@Y zO(oviwL~_%%Sh(Qy_+cGvjLhOWU>HkMjs+_A_x(B=7~OOKEXBi`9%XLd%KtKRYiE& zCGnKvrMWqegZKYIAn?ct6D88$s)`L4!3Wxd zlF0)S0(pnE<-|T`KTr>bMwYh;)osuK_WY|m91>cEp6DaXxVyIjf_AN`B_Pz;6Kgb@ z&i76~*5H(*@?dr(Yo&M=m#TkkaWQyIUD_^~eIaU%Zm3X($&+8;Vkx}uk>8P+J!q=~ z%Y=9FJFhkGJ1Y^yUjg9}&CK0W&;dZBPN8R|NVeJjQD)DXj|tPgRS{vI3+}c9=4CXs zgzQ?ab%DF@$p%!4g=kP^(zc`z7^*wB_Whe?HLo6DAJpAQ0obDMK@s39oDQf;>W8R` zYe}}opKPlxC+LpB;093>bnck9yNd1tu7yoH^ykO_McLDadCWkC!Ro6)<|!D!fSf5n zPUs0U5U%_lyN(z(3&+i2OBkmXW8m&7;0Cn_P~zyxms-6yKR{}w)n@gmafyQHoAiMY z;B)Ygl7|6lNq#pfWq7w3=Ho-yJjf2+$Q}YmUUH=X%Lp3D=8&cOfq2LD`31vuKrq6d zaFj?)RIo!SPuX5DmpC`Igf44~f)(`hKC#y6a8mAWrK6?2LZid zJ5Kk6YE&b=0Zl=YaeUj)z*HhHr1bM=h#83oqudXMkT|!jwdv z$JG#z^(qu@A9i@ryVyo3UH$bgyk_6Nt;=IC7kgA=)dej@s-(zaA87z|$OSxRD~%C; zlZEn_?E}wE-bW3PYXT)({(-^4N~2cTN!wX~558>%N;ppnd0Zmr=H`IMTJ*Nvm0a{_ zANA0wvGV}WkP1+o&1!c=G3VokhK7f$0W{T-m9=%69)vXPi|Z0FK}un!YoGO#&jkM~ zXXyCh0)E1P&23lRXjBj-fW#77jU%&Q^FXRA8cD zG=U2Ls0Cq}KMk>rVPofCI?dRQR7>gWkfe2$ z8~vjFt4j4Z5iy3!%F1MxQeiB}2&>EddV=23H$&&4z(CduLOq1xj%gTW={1ak-)OD( zA`asZM(n8Fi4|ixH&60#q9_q3b~F}%K9*d;GITqlMQP5S>NR`rWvoCWOh5C&1Bd>d zjrLyYN%*8rk7NzEdy0Wg*AHMa30*KcdUOc7;V+Pll?v|FBt}3e ziP)<3^b0IdfOFesAbQPrwl#GN+nxhcjfE==IYL{;#S{ZIp^l;n2bLb$r6qsV$CG1nE zWnA~#ya*eQ*dx*zGC`;W-i~6U11TJX z)mcm`yI8&bMN3ew6#*%Y%MP{m_4WPpe`UkKQ9+BPumP;|df;w+vFi@l9~mF#LC0e& zVxRN3Q1BM9ZZNS9pWas30Jn09DqZ`kx*Zk{mVd#*GP=)>?wXbAZJMqODml4?X)=MS zWMzv_INX1pt4|X3n!K(3AFA=QV&1PE_bLVUjd#$lyekYvYT>jwJ6@HJHN``40-!Z# zkV0&+40v9nqa54P>Mt=h#C6nh#Lti0ZFD8k@sv{}jwggGp#)(2bfZpqJzoq?O=mIg z$;RTZEzvfC7j+>uV2k*xufg`I`GGh0KNq$Wm=r)!e@L6k zLCW7CWBCO-(V+JPs9nj!KBM(SrZPDtMO6LJSm~An7H2QKXsW5%h-MC^;IW4a+2tj- z=_OSgPqdg)cyPS z_v;)np2YeZxzAA~yNwmMI&>rWbju%9!NgWn=jRtZo$jt-^uhBHv~Lgv@FMs0f(ywr zNvrdqjZmDOuZUI;F zpGY6p5<0ib%gc519j%`Z0z90gB-!ksQwaiHTEA8L5;D=WVU|{;dc{vfF*jSybZybl37ei-IR=!ZV?@rBN?#GMzRD?5La`Tpl8`B}$CoQmaO#tNP1B5IuYtysr8m+kGt z!A3zQKrPn#F=YYB>i-D$Y7m)y;QZK|$B`KMmr_<%nqq<3^4V;E6&P}=)3iFmSR)m{ zf1{0z8axiRG&}tBD0>RZ$QeVDG=#g($C8$rmIq8;<+neFmq%l31bj%=!g|I(W`dya zg4%teeVE8mK{>RMNq5($?OtAp4W#6B`=mFbWiT>x8v6NLlZ$OEEq#z&bUAq)(Z|cQ zrO-}&I(8_Ca@$#BPn#H8HR|e!w@bz3*P`SE0|a^3HWsw>kX!B9T3iKFCfU|q2t``c z>&H<%3-$e>mNgjn+R#-ExZlg$rlzJ)sjbiWru;d@WNJ0{t>5p)53h0shKX&Bl%|6y zPS_hB0j(l$=R%mss)gWGHvvks!L=V}(>X!pJ_H?gy8)FMbRKD(I(l>ix9kB?kSq!U zfMn7(*CuX-R=p>S$BAg9_N4UPC$6*K!fqWjE0J?(^XuD2y95rpJXn~ITpTioXvO#M z5acP+7z~k_OF-ZqVVh~s@<*D7BTyG!$#W5LqLMNrPyTn2|JRs*!RQOcki7cZ9GnI> z{=wiM$#huy!mZUA%#}?++d@Xs3jD0eJ36>juwh1o2Pb#+RnIG~+`~soDmIaK=X0WsoDMvYbs`OBY6J`mh&J~g+uA`HVC`Pp2Gl8 z@8rw-$0K{BCVwjR+P@u+a-2-frk>pDnSK0L{#3-HX3KS_!B%RnoN6nU9_1k5ybVrp zTR?S0(0c~$GPDFUKgysCF|gSD;7pKJSD5_?8HkTfF`;yU->xn2u}UiyuCPB}Ma?#d z=C#B-LkNn8>XW4-)De*13=BYDkg!6ZMbr|6MDf6Z1Eny-Ekm^OMdu=o{8ficNct6z3Yvq_L zky`()r*U)W_74Bky3{Dk@~mb*d_&YT2m%MGv-g^iVb_d7qmT**J7vnu?Z-Df7i^|x z(`wdu?V8_n-}6u7sPz*u6^<5~oEUrko8i_J0&2ryY%KE-XhMWDw)2nkLT6`{zeAY5 zDpdo$riqP{sQOh>dnkmmZ;}MDSz4($=<9@WPO;m~8{zJC85U~MzWN&}6SViu`n5z8 zKVLbc)gB}9)*5PnoN$+b8N8^X#^4;7YB~VuA+$%RZf;Y3bX69#Fj~&+=YR`S(J?eek<_5iZBWG(v7HVl>F2Rkq zWcL|P7R5vJHFubW+8>=>xllt?RxMx=O5*IMnrf>0d255ow@bKdr_gkL&)?t^Rwcv7 zdTX0j!pc>EwFIYzP#Hj_zwDAIT+bTYH#ZFg4-N;OyLHcV;?h>io||xosid$CG9aUV zRzXW>{|pwTA^J=$ectBoib%7gyyk=pDXObK(>Ct@63j(?@tbM7jKCV+U#N3kTH$Gk z1GBQSRG!ihlj6rLh;7!nJcE?9f0FC@>0PytTJI>QZ((4QH>1*G;Qd_Zef0ev6A^X7 zC++=8Z%v$0|Dlj|mJGU)Cx32{qFx;T={ajd(&`s9B)0~(e>>HzXNQKU!+g&zWL?nb z{SY9;Qsz7Eg}mp~e5D&UJFX#o61Q-ZG^r%Jvzg=T368f-@1-b|@9kl*8N*PPX{~5{ zvTYAOL*%R-+$67k%={C1gp{=FXmSE-*g1$O^YtTR1CXYsx zY`s<!Y^ zsdM5sd6N22cPFJCU)pJOscU3A7iEoH8hUh<+5|;P$hcyvdOD&tbRx&>)kAKQh$;DE zO4@PB_HbioPbVK+I~qfE+=v=DG+8^IGb#Pf^q8G&Z`wV3qLI32SMDxaWLiz8b!CrF zsGO*5EK}^9)5?e$*WVeZ=0g>LF4Ly&Pv(&Eg+cRiCg6&pz43@=`jhxW27EBU8qPh|#+ zk~+iyNkO$J&|OWl@2^G8O{6G6636=dYip$nTC1&2TtzrnKJm^kmmay57A2!WZDKzw zximiRbEo%YBU=qkP8ZnF;Aim>vCr^LT|b!y3UROL0tA8n*qQ-cD93~9FvNX~f47Ps z9I&*yq^iHPx8upm>t(`O+$;E+>ZPs)>b9~7z+(v;J4;Mw$A57*NyzKUsPNy^|CEO$ zGX2iE^Nmdi=;r(kQoR|;c;6NR{-8sfh&Y}|=iV1%t<|Uf-H&gmx|OuDy96Ajd%U{( zQPSSd&Ec%pJ(MwX*$N5blh0=4Rw1|f*3JV~Za~h&y@1v8YJjz@*IahYkhSwfS|I&1Y z($bdXru$GfYIxl_U&wZPK-PC$H+%f((|vycH0MTs4*E@@hOTbbwF@Zz88ISK?+R)Z zTV(Am8f8X{mzQ20q9e9H?}-W1dc;i8P$OJY?O7UEukR__O7>2BLAd2of`z%!Sw*ZyM%L|%Y;kU8V0x_kf`Ql|c ztC?&ql+&mC(;pp#X;U}QtfO#Z#?nKh$vf#XJDTQ1Ry}vl>8$? z8(JS!P`?$ASP14KJ`@id^V-)OCRfh@&~CQE7U}F%EKXidT1E7w27TTJX#2`0tCzw4 zgT`5DKg-=UyL`3O&gfQ|(i+Cnun7fAk0?bLlAq+|^$g^3Q9HwM zz{fd}VIQIN^5)2Y?VQ@LYnVzNJ9h3Ju$*8ftf)~T9DD|=Vf9`bsE;@NkO}8KtM^gJ zjTg>fym_Rd@G|5^!+pmKBw<9Owpd!-Y?Yn(^2JZw_LiMDHC%Fe+-QH1rt5VDvxtU( z{Nu~6q?pHj^1F?3K4dVJx~Ha* zp(@(6|M_Wz0cj!kUQ|oLP))C;_C~{Kr0-RR^C3}uPn!cjy z?i#k-SHpGG+yp}$c7)_An!J1d#ydVTczEz-tRUX3fVMzg zv~SXV*JJOad@Q>o>@{MQt_v`79@sPJKpyt-exl80EJ01&X?Bk9JRSK7CU+&rx9JUd zO#TtSQ5oy+^F80JbMUO?^OcfE0`#Y{G%(@%xp|m;4J9$09+*K-%>mqx=yV>#Tvldga4stmrKqyG z2CRm*We=gLI?UL{Zz>%MWywKe1 z7FxQJ_|rCAlm$g9`uDkjl^u^}SkjOqS0$yNj|_k*Iqhfx6@{m{K_d*-|zBxj^7|Cb{9L~(V;at2$OKIU1OnYt;x{4Rce+MUhmtf70AJ3-dfK6Emj{>;< zkN)|uo&Jg3U>7Rz1@7iKR=v2XN@I&(xZj18J1x!JG%}^<7vgHpwEW+GxE_s0cb?79 z1T8-8sL+(!ezJGwqm%YV+g15l#S!n+UQJBymh^`2Y*nGWw8gS7Q~KRPP6|(_XI??R zdYu}z^+h7Y2S$+%{qrydU>WiNMQFWteKRzvyaH&M@0IG=Tfhqr-UEo3`TGBLX)jj1 zp6Gb!5Y{@*V?0D$Pe~7_p$6~JnyB5yJ?ea-qDi0r+EXAsixn^26i^xXi5m6UsobED zP1$}dL3A~C_zn5tNFJt*-IA;QQq=~2z+{KdlNT_NP$?R)QD`I+F%>YhhE7*xY@g&$ z7xU)^MDsE<6ZQqHl&4$NBGNLV#^{9FX$~golfOhsawAN0RA2_9CND4lC~HVNVB-aZ zJ^;%{?1{r*zkCa&Mff@f)Z2`pL=D^tV94D72TP()F=z#7@_gs0X?3{Ax1A;@Ornl* z&w@C~(CZJGm$G*=?2cOHd>tc8`3}~omR_m1 ziKy{p=Oolu6kQg+5i50&{qXFpyz@UQ(9eiv%<)h5;-HowJDMx^0FWW1DuQCRRWiNM z@_p!ge27=}-4d|Rw8Sn|GC;Y!o{@;Hqh>-S`hx8=Kd8J$atT)4q=bZ_T;4y{J3H3X zAdw9VRlxG;0SmEIgzy@1{UHf27Npi2pN}?h?HD zel}&Z`Ob)K9yVJ`ivRY3Rl zGDBP(UU=!(vTI&z6Gw8(mdK*n_-8IlKM$HrR$Wd?TGmT+9PTQsOI@4&dGN*}@L`0~QPy)?p36g8h+7be=t(O;g>z>sicN@7nXH?AC19LKdqB zmpGZ#g&YKFxH;ZK>2ME2``T6bCB!68vUUHRa^`rk5l1c>sXn>$))wBL%kAOZ9Zf+h z6|1wqdCeCc6d0iAuRMEUIm1I$f1$U%xbgwaS#iRmYT zG;VMhTt5u({Z4d3w#l9!Z7j}vH|*XFtC4#t0zx+QT>bzM_FqFK$psR!$I+_W*^H}t zFSU-r;REIE9v`6;FZBArrJONML)1h#J#5>%X4k}WY$|niP4XtMUPTIMdl&B&TySjJ zxKHkih|%M^#elDd=U%DI6(^3mC~PjueR*P9)Xh$L;nLizgA*qLDyBy~Wm?wH$dJ#e zLNK2M-P-G2C5S_lX$XF{ZaWe96^(F%TbllO8a3ve+U0wmaj2X*M+M6F(M$W!je?pWq0I z3jzyApQ#)3nyNQ>o>m=o8(qpxt1j-`v}|9g2|xAi$%a|Kdvnsm%rHIGv*cX#$$8vA zoSK0S(v8w`z?c$7`53Z=Al$DXWb8);gTLG=0`7}Eg2x9JC+oJiG3X|Hans!vxA_V)JcoaZ=H zu_#u+GF|-Vc&yd#Gc6)1vew00>fYQSZ>8=4nYPQq8Qp`lJ=Baxek~SXS8B=_2_BG^ z#%6W2J_ObVk~e@Eu^HJCV?7lWSYU*TcKjrO$X;Gv;%baHh84H5a&#&PHCk7RtO`%x zM~N&JkEp(&>0)3$Sw{2Pr9uj#G$qgJq4Z3F=hI6Z9bOf`3%6!_%*7qNS^ZMr7CGBy z(;U@(9@Ufx2{ee{3E~c{0{!fP+0#SW`U_(pHg!LRUthKtlI3NM=cB zMeAqoLC7IlVz+ABE9plybX(@$!DJ9Jq`h!xq1y-XKm0vx4^nD4)%Y{((XL<=b%PIS zDM~UxJv^F;0?kbBEq1ZI5v|&1x8}*e^rNb_2P$3#bEz(E!+*QyA6!k^vAZfBPu8tW zh~k>iFN+e(Ev%y{{g-DiMSUuAA6324nsF>x^!1tMTQw!=hs?h$yYBIr`pGx=9=~Q% z55Ot-|1WCvCirI}P5~COP4(+d=Bb0kwPspDKFyM4H=WK!w{40SorlCTUV5=lF^B1C zjP*X%DSdb>(R4QNo4BK{X+f@sYV!-vX4~Gmi#19R6lAS>oA;=%e)IBVf^`<*EK=fgvdTTLU&ApBz#Yfd+ z;&egYP19q8pyFrOQd7`15Ysz1IBXWkr&cqP6kgh2UNRCR4w&q z7)?kF-+$0s5&6P%=aPBLE74Ta2NWtU-wUcdDyH)FF#FZL*S}v^4Lerh zSRA>iS5RbQ7hUa85*Q?1Cy$n|n+Y*A5B ztIK_6ULI^#Yqp{#5|m*C>NfX~S4LE-%Xsh*H@9m-R?NwJ_B$&sGejK$*!IC_UH|F& z`kBb3)QQd{`*pYEh93l!^#Wm{%Ckv9+`=Ti_7@IdO?9xd_ni*hb!>`ee*+={bQamg z7U)IlhJ$#ot6Jnt>2CA}=+ig@DKLh`ms9BhUi-X_qe1iP?tXIaq+~qxsqMp^D}^cK zaKWpQ&;HM1wPL|Wrz$uhqQ)9W$ZxNP9Ugdda{N2fE`AqS?V;{LpO>F0V5fzW( z1;~^Ys2aR-?iNi;J34@owFShxl64IstMh%VF1r_96x9vAC7z#d17}nALS!0s6HbQgZ z#V=tADSHN98I{DRGMP#&NVMgf2L{F-Hu7ZWqe*dt2hn5x>A785e*Du1T(u}V$ zvuMiITCKE;COY1_WBhl{uQ8n-F*}`7D=VoJi=|7Cr>s=#bMRdo@jq;_+zaF#d zzW?BNS$bxe>mgffH9mDYGc5z>@zNir7RpzBa2>{7YMA(Zkv$C0*QL2Z?)NRp9R4Wh zq5U>J+scA@-o~&KO9Viw#D+(e5PD)#`SUjE+9v~SmbfN}sEn)(_Kvi7Sx~(hi>I^H&O-mLIhi+G?r_##9-wN*Eb#nh24ucouX2Sx#%(k;T**#sB{AMOpg}U|4dA7vz%I?zB z?00rPrGIF~a(~D*=XtTv!uw|3?me1gDfYWYQ{MO6?|NaBAjaGSOnDiQNEU0Z$6R}{A|ofdYsQ?AG~4@vTayV$JgZhzQduE?o$S>}qtDNCWO z2S$24k;T?mzV{|4y3f;3HGl~FZ&733YGEVI$zHYufnfhi54qicEiAp3=PK{a)J-I( z4R_Kqgl@X=aVR9`;$PnGN#zq2xJvF$|A?-rc6J~BozwUC!r070@Uaw+imLpncrUMm z6Mw|VqBT2NKF;YL5aT0@XPwms zoHL~Q)aPZVf$*8K$zx;73NF_njXAjv&39ZQ143YyH8jMr#{ip%G^(&cUD?b1zL*G>k>hr*yKODbABUpVZ0P z^FXq^Xy=2{x9=Ukhp1HiDh}I}t*9MZRp3C^!9+AMpDa&~JS3Rn>1?zxBgUXIUT`EM zBf94+*K*5iS5IlXs|z;2YvGBfNRQ6x=x<`^Y}*K%nGeK2rb_9%g1nC&s2AAD;;ox| zQ8gn*aM`KU_Jt8Eb5YKrl*I?i-T!#!pU=bShNPed$?G+)SHRtPbdtZ@Yo~wQ*<*$X zJt5(AJrwjVKRW$0TeBBXzn-M9m@;0ma8_k5`pvn5v0SPw=c1oLqWN%4vpa=VcM?W z%B%xXh3U>M|JU`K8e7;ZoZr-0B~f%tqDPJ2CnJ+1;yz0u)*xoU?&Bxrbq`}79q-eSGlOHdhumk z`oo zUa>aXSo)>5%^I}Lcz+Z!M1F@-Wboo+vAJMqWV>A00i568DtXz~BEz?TWm>uZ-62IN zi3Y76sn2!&Yn28C;}xcaN;DJ|T$x1OTh7y)^tFddXO~A8-`a)w=I0lWJ_ij&!pl&% zTln>hy-YCnBOWe${~xB_0` zi+j3g_~n&Pv*j>Zjqcut!{j8he=vs$-;>4hs3;lTv)JPf9%1o-Lqad4HjhdHBHv+W zXyGPtC0uGiZoTC^(O*`Dgk8xeU&Nk?d$n!E!_Y#G!01Ne)I2{fW6X!e*2hXtF0r7j zXuds0JE;E`FV2uM`@uGq5z{pW(us>^pO++ zh@%H8%I5toKnMV3Fxw2hKX|d`gx!u$CPp^A8krW7EERTK|5AE3q|r0YdHB>!WT$Da zV%lx&gHs$g);0IUV{Q-R-W@a>EV44O_C>_HwV`joYx?eq_5xc+>xC|^yi=E?MDmT) zRes;}#|}LXT^hEL_3G(k`J5AQ*V3gWQ2@pyap(lr5!5vF^NpoY2b+>^>6a(% z*rn%XQnRDwPw(|Bf8FsgTaEeLs&3_6B)a!pAGo@og1?=X?RLCrJ&%5(JIZ;6{Gm36 zQ!DQy@ZIeW_jj~0XX!;sTVS{JGHSn!=cTy$*Tvo5S!E_R-U=^r55?rj)h7sVE=lHI zI&&jb+mxhcbbVpoVdRA)ae}$}If9xX4Vzm-dMSO~P_!$lkm>5;y4+5ii{hwZ;wWnw zkpJ(GM-R!tKam7?7L^~#%WOkS%w?Zks<*_r0=gK%3NSwIwS#fBlsr0EWX5aB<9E@& z4FY|=E<@E1$SQ?xNqXnsmf1yax{sCn*wX%q*qit~Z2ryAz~CI8`@VhYpDlA^HHFMS z-!_ef&r*{sk%}(Qm7AGZpU#?1y!M7l??K7#L!B8Ehhj8Dea|i$sP@41M=Pe9e6j+^ z1nqzXB|}eA3P4B(~P>ZbFF*4w4I z+jc39f=L&5bAGeipq{`7Arni3NffmMx6?&$d-Wc1Ci93t**&pmdTKqt!Xm{0pb39j zUcK+S_pR4eoWW}*l!J*$S=8w9WA1ZG!34%pub#i%AJ*AjD(}GwOOpk@z%86F@)3Tt z2Qk~Xl4Y-()8>UKy8{fzwu-ZBPm}$|0LtNBv<684%mgTe+%)0SKUj;ZUf3#nK_-;` z23=#O=yr#};r|3lJff~<2~f~hSY<0nOFBEZ6YfSGd6{X)0qXW_CalxFJwGL9nfBHG z_&rC@#AT{G$uoFADUT+-0E@ls^Xzcb&A2x6bDO>*?miWL8l4C$(AM6_m7fi~vPtli z+UKx*3;k)LNjRa^Qg5j761uF%n-E9qs2F9vIN|~&Lkta2)IbFZw4M8(a&p+wC@>_q zdN>9W!qIRWWZu1vUvo3d?H;vDsUZpq}sbpj}uobUdC4-nq|tn@%rC@;8VpnsLus|kj*Yj{UE7iY-{^Q zI{0?k%?94!Ygks}sUc%bKo?;$2c63!ZKLOl&Mrd-FK#`eX|Yrr!%UC6+y9Om+aYUf zOSm(=z2mj#(){qqHoEwhn@wc22~kE?4=oIzTYP&@KbtygSzXVKOs z-Q{TSZJvujPo{-yj=|w)#qNfUUOTf8wK3c1+c~J}y~LX3n(nfedme$kQ@-SRq`Zjm z-jGUXdgsBq;^Nqoy6KE}ZEQ1XMCQQ)MRx6RPF^-$1ZvRiFD?fn5$x<_il#A_7Yu$2P-S<2C(s^fXMIv@Avp#fTVsBmXHDm>X?;IcjBKe6BxJF8y`JaiMI~byBlhbj@r;s$VomUB3>sG)%}iAY4H>{_BANEP>0G+`-;e}E>)#ie)wZ!b>UESfBD3T z6Hvk!M2lwAlCOm}gZ99xXEzNzRzSpd(+?Svqhg)>B>B*mF$%xe=+h>j7sju-J&Pz3 z8!;}`J0kq58e$hF%LrC5<{@e&ExZaQk5fE(mxa^j=hH}MH+DJ?)*iamWyEl2hR&L} ziP~NwnMvhL>@Wm~Li&ZLS;^_6Ypj^SZ^hbr=$9f$O~oI>;)}&QAQb-zuDz17FgLgB zKR33~J%0Rq%*j# zK=u7U9M~Bq{b#G+U}z;nPQ#)igwS&?E!Gw*2ZE~IXe;JD7iW1ZxvV z(W&muu9mA?XBKm8`h1t7g~mTD?f%wg?zzrcw>3#RAD{H7((ws{fVR7$(`_>c8+2I^ zWE~WPK0qG^NmL9bGcyxQg6CiNs1hpcJfQs}pUZ;Q2*{Jh2svk>4GcNTw_MCX1|>$^ zrwZ~Lw=Z3~RCGsqe(Y+|Wga-Q0MCgpc$C4%#&bKWeG#<<8;>A1HkrI)8BT|(2iUou zTC!ucJVy1Gb&p1N_gO2;Tte9=<9XBlspVY;xFglR{`f3Gd)n{o5VqQY%~j(jPivCN z-Y+YsBasyMANd^Y#?A7qn?0Y;=lsylSsOAVU5v=7Xerc+GL4Qv?6X13)jSPM&MmK_ zACnsgj-f$vq=MWf!&gfbxSy8C{l9B!3^kzHU%&nXJqPZEhfv{1Cc}0F;c1)j66seViL;R z%t84CtB=R~2zDDQ_*k=St=9hpjNZZSb>$10JB?APQ$$N}B_Da2Cmrr+JH#3t6d#c0 zvo%R;VE^#r(h2NsuXSI(@VtLfLxF2;`&5wiUrxyf+@*qxPSCt(4wS)ypiXqz`P6># zauW@i|5;HD*ubFoV-3EqjHvXUubpP?Se>0Qs#Fkj$1$~x5^RUj|A-2EDbZRMxF*Sm z@H|LZvba~?x8i(Tai90x-6F-o)9>?2Wu6c0?Oh+S{5d2p>g}KSD7ELf#c+}e zshR)L(2VHe2HZr;?Ah7bffC})l3{b*D8q!j^k7oPvG9QGEMd7G2RdpjkXnN)Pr(S^ zEtJ+$k(@goEm_p>+f^NHZ?Anu_hL=wL%u?bJv>h#=L9c3yAj%?k4y(XZ!I*UH0E8G zZH4Ass=Ymvlm%1EuZ7NB^2>ZPh{Y(M^~$@`XDXOEIJW9-*11G|@Ov>>2V1%JfT;iO zjyBe6!pLh+0mnMxY42B}#XclW^t1k_1I=FRrBi4-JoLpC#AbGL0osRjhh4en1aVIW zlr?p8RQexP7U|k2W6uyXc*nu6YmMfS0p?_MG@3y&dd+EZ@QQEy2G}9r;ua@l=?N1n z`e~9@b)!1XCXb;b@xi_dobkFTekzOC5vTfXiD=ie1Oy}tf7)_g>@yS_Iv<7i(>17R z>i!yyca_AjU;p9Gtjob%4k?}3Jr{Mp+1hP^dGw!Mo>!Lk?N1I&YPW7^>@v7tRy0>6 zlqRUTbsW9GSm-rdRDS?<(HRPB=RohJ8x%B$Up^Zqa${aR9FC}~s{^YHC95ir9({s* zfvu$;3^YmSiB^70?0fi8Lf7B|-p{QIDyUJd2{8Sp9*NUh6Q5=kzdrKHs)Z+yLYUmK zO5#D5d=~TQ;rfJp?;d_raDmZuQ+%Je_{7LKF{Vm5|A~GSE!*D zul9dUM3I@ez?<5#{J_}kF;DbL1u+1<7er?@1Zm-q*u|6lLpvqvdk4BW0OLM@Ok@)5 z{tJh&%WprDK?K8ovHgpl8fkYWMJ>D2U-FI}u=OupIZB?F2L%Lvj~nvLAaAsWO4Hgp zw%vWWviVNp*LAMdzVgcFsCDo;aLbB}ddNykHeV&scfHTv%SGnFk}F?|_9?yex8i+spmMHp35fbTZf0p7QbYXJ*X)oD0*|)^2KS zRH^np;B{Lu0+9pNN{`Lgrs#z0uX+5S7Dz7_&IIId}bB%I6?Bw^ADHg8ZgtMBj+`YBxk0qkA#D{@1xmr*7>!rRDa& zUOc-RoiD-NJ!13}g>moK{yK$pBUFL)PgV}CkF-8_HA%;2-R0g{<_uMNB_JjiR5J=m-Mz9pEGZrvm<^I?$d*IU~S>yD3m-?FI_y=(pKK&mx63J}(F$K1LAPOJZ4c zzLkM@Y+eap47ge#?i$Q~_ux-T?-_?s()d!NC*t}(4S8Bo&re-mMq1iM(f7c}1KqEq zpOyC=C2C9#)v`g0#tp zhAO|~&_S4=|G~f8y~n|x+Y{-v$**CeTr*)#w6NLS9MV5#em^YeY~9O8r3766g#?N` zqjPA=S(e*to!fcv&vTERpf3U2rwRYA32obgNL9|>+-8j~&Dn$P4ue6g>6~o5V0yXq zR%1keolqpa7ZK_=E`sdwGeTd|Ns1H3-{;y#V)T2dN5tDxty(OvAhZIzuFX9H$_y0q z+(zX8-LR5pj~82_LG$MC{~bt74$7CrZW=e%W^GIQH}#~IqU(EX~(W+e_y3`ndM z4B@#w@Qzf9(3(6y<{BpWjDny>ck&}aUN1S%!g`8|m$5#+;tDpHeSq@RD$n2Kt`Ws? zXokqq*9qMG>pJ>7PFyS-rR*5NT$;sxZD+r~fc|ROvwaFprWh{Xu~hlbY~aqe)s!U*S}K?ckTZRX!2$5{54pYXVXVCA_-V)0_=!I>#^v=#PG z50}z($!0q57eg5(`a0bxPwwEhOdC8q*4kjz;@F8$olYKPC@l05+}bg0zG60D@~~Pj z-r)&GD+=#I1^r}oY1Mv5n#W3|65-0~6nv)%jC>sJ)bCg1KYVZIq7eLZzH6da7*BOs0zc}|_HF37REAC~o_TXTrjy!6wZC<>1aR$<~wrcmYpa^&#+J~9;01W`iXr8?7^KK2tnbUXO zRZ-n62G@WFlD_rlUwCC>R*{ZKbe;mK0c$Lw{rz7QL<%xGP8z>qA00DcH!dySQn#u08<&Td`O)K;j z?SpIr_qGjO{`Gz~Zjr;5rLMr0yxVU|A_NC>2ij-t&kEL zTV*G!f(K6B#iM(I06Y8s%8rVArF}^6_CXzk-G2oxw4J!oFgI6(kjO`*%Z$auv+(%_NKKxNCU(TN`|`*b+>vmYAGKmpX}EBdjLaTvE8^i z0W}t?`ug#D9Q~hy%5p}0mZ2==L$5QA&UFT~nie`DN-HY#poLpCz)x>J^n$5S4Z=+* zHJM&jKVIIju8@w6Z_=w=N~nH~M1{re0X)GG>qP^JiU5DIOj%O!2^nmDn6G~*CNqB> zjjZqp#P?mb*F~jo9ar0ls+fqpc_9BYsQNu?rz7I}r!k@TnCLeEJCs+5h ziYdahRV`JAUkrKit@7DPapB}#O7eh%tl1x%<|K}{_J^A$T{4U$1oRz;9(Ya1nK+NH z9-KZ(J(acHceT-+Dc~;;F6{NhdfUk-m(KWY07B|C^93*}5Ei4ndHwozv!bcrzvm`` zIBg4ra+;@91!?=h)=(BeiKoO|K33jAO`#)I9(~Aq$zv{)L?PdwH~O*n*RRQRMPj4_ zB3q}Ni$gD;9b0ULn7|4TkH@5_pINwdjmkfk&mnIq&cJB?L(TZY%rm;z4c{cu`9geI zeg-?^*^dJ0TU}k<`G%IK8@U@G61TG#K4#@&<$?eIg{3G1lbx*yI;{Nz`6edX^ss5q zX@C^4nV&IyL~^MSFMf@pBYMk(>r`@nRK)0xCOOTGsQ0FO8gO{E6%I+UUq$9V)KA`(nKSK#6-0R!RBn+AGupw&cE1X~|p! zhm>ZkC-WGLxvtrtcv}$yG7Y3bOo@koUEI7^e`^R^($lwR&o0~bg)d$js;a(w*`P#vv$@-Jl4uSBALmm9 zKBb@ZO2n$=H>-TdO;WBxhwNpT=LM&|w8(FDd)q;Dy|1=sS&=8#>fKgL@#fyf=bpaT zeOAq;&>j3MaQ-`C>MOCCilKTucL97;2;b`Co!_Et@$*T^C3u$K=bcMP z&iM~nvUA;SMP%>Am4nrTRuAJx`Qu)T`}^PJ*PYxJ-hbL@YF^3Y_}X5w-mq1WLtk?P zGrZeQ@V`0*gy}+}E5A`z9YIZ3E%7Wzlmc3W@P>8H0))Hc4Sw1g3d0^#s{l`?)f>MC z1}bYKef@;z2#0gCB2VFcEkzO(q6_~P^7`Zmx2tI^gmLptR+}%THJcbnfb1hnhYuf85vcykfgC`UBX} z67p+WdMTy<^N962ei9ml4zt%O<$jn#V?UPQ#KW`_go`bcM`* zxF8|UcoLNR($xzxj2c0nfJLQLdsp;s94fmak;xcks^ocP@wI2Ua9MBmV-lI{!f#pl z)<1T3u#r0x{=bUSfK!_IY7!upkrp~VJuOofo?C=T;miA>z6f9LQZS15K^P63Wo@q1 z;Tc^fL*5;~FZ`bRy&wuZOn}?oc7Ie>>F2w>!QKiuC56Zuy<58JOeufpWM{t3E$$6v zjzosUKQc!IE7$Y&IHHy+7YHvI_+&P0v|Brlun5#;F~p0@FaO||s&wRel68Ws4nShO z|FKLF$$FZ3{GSy-PF7}E22s`bY_mF=MLqrfGEm-ygk@%rCO=6%mctUzfxrleU4EkI;nu$VMOU$?8F7OJPx6ix$W!A~6U@${A7M>95 zrwp^PGYE_{kR{~TyE02ED1)bBi{qoaJF&$-I z5M7W7(W&Fe3LqPnJ4;V~24K(hyIdj(@yoUPlmvD(fI`@I$Y*mo$hr9kXJK`l`90Jp zlh}ADP(1TmhGKSm*~a$5VMH=`ga-=|MY|0b6ha4fa5E_)q0JUYV*`ILF{A1(*2(ot z`}~CGy4g8S&b|MWea1eMz<#6pNB<7~8jXJ00@p0R>)CesP-x&;pJi6P+5U z76uv;DdP1IFEY?-Qn;x_iMoxNB41>|JhC4%KRfN0 ztNW}WfM>QXu($R*TschTNE8qX?VEIIv{?}mkv!Hhl09?zn$T(=?@nk{rwR+OkE^J! z$S<54EujqBwlnn#N;z0OT=>3m9+5U)Kk*;lN6vnHc6-WQmz5dDifwfNZaruM$le5j zsqe!}g$~8FZB5c6+Zd+d1~ht%E3_EKtNili)@K`rgU98?i!ogd zbpQP_x`yc4+(QIge{&?bI1Cob-ZT=B5khc`czT^b3ks`8(9{rf=gyNEg!aF_4&-nD zR21OplF|tkwtjO2pV(e7J4GR?AuqF73`CLn1q#8Oz}Z5BfjV&cC0H$s$FEI|8|YOj zT-xlrcHBd{GtYh=@7^%yoUvz;UGv3Q??mT^Y z!y%a}moL8nj0CQV@O;49Dh+OPxSzjSbf zh1o8f*moVEq=6~4b7kBTG)1_f(cKAz*WoEgX#5&#d=qcqqBrb@z*QV{kj`ej{HxX#SlEf#6x&wjM&Xz^q8(mg5BbsB-kwvFlKhe8yFfsr+;RbTX0kCZTWK@acl>`{(-=aPiP} zrZRTXgnwuD7_senRCqJ2e=@xD$BAPTXwR~)vC!2bL*abtNWSY(DA9Z6hddfI-cBc3 z1n5N%=#5BR{8HzKL-)uA``4Yz(o*Ht>L#mW1cEU!($xuCT2J;$$8S6<^C?N!L*43O zx9K-a*27v7+@<@!Om2nVB{G5ufd&4Ko@vMdQVThyCm#{|=&EaIfIRB1dbWHwNK$@; zYF`(s)Bbff|JLm6>T`}3m+^i zDa=Ogylp*yQKTtw_Fa(tMjKXCCG(7aBiA{kc&>OoM)zr_&s9U%fi%S3*v(nW5xNoaa^+Ibp6A{tG6 znOSS*T+aK~%$n*C)TCBMf@bt)3`jj^qRo=%ut&uwpPRRQxDtxHu!%a(R@4KcYUo8q zSCDb6#e=B&g9BwyvPxFdLJYo#gr@iQ=rulRH>It9J3FURYFZ_o_XIU*5F*C5QJ?EI zp*C4*ew*y&Eao*GeQ8Lo`LRb%%FMfX}8o0=7cCtT9Vngw{5G_R9< zQKcZK1j9!E;Z9o@)!$GaL72dNN})YYgrNO6nR9={&?{d+h_gUY(*pF;PA zL>mHG+fN+zInITB0+wAYsAg_RKb#QzQeh6-oLbR>Cp4kQp1JH*>FX;VKg>MzZr?_; z?sSV;*8D#*o^}?W@z1==^6#gaTOW5;L)$v(C__}tbkxd8{HfU& zq*EdE%+$n4Az_YJgWl5#1P#o}n6(6rzCJL)`>E!?&8tg6t_j(k6!>oT7xQ~`|NIw5 za6=gJ9ZE!9Z|o0ipK^mo5rTe%&S08uP!)=2pFiX01hN6MAo$Udt6v^6FoMd;799M6 zfy%slH{NS9_91<8_xBKY0_We*q%otwapYqLSxp0wa#5UBi2FRlJ6OMCE`VCam|Gey zDl$sw!D%Mb+p&~yyI*bhgc%IBF?>I1R;SigyDTSV%C~jt#rt9hyPRiu<~|a2{2WW_ zI)mvriYMKheu>sw;!$&3lp3?W5vGs=j(A7ET72Qv@A+ojcBsYhyOY};e&=k7S^m{c z4e6<{OU(TjZ-iu-2G!a^U*zWi-*^mSP%)yOTc0}Yvg+>DJeQC__3`;0eI-PbPmp7a z3?1(3`V0kYsBe!2CA6vSJz-MD5|<;iA(S(;HPuCJvhQUSNHH7}SI|_Vee9lXCVuQu zu%t;F;vDtirmL`xT1E2mTk#a&lHBUywba)p9a{#c$I&2kHREhB`@VN*iiH!vzV}CS zs~5q4{DviD32YByqZ5Bc7vu>Hl2&cK&+A8j0_okXlYZL`VcLu7JJ{Hoora0CZiSAq z2{2FCKz4npdY_PVA;Gx`Po@Z5 zFi;WnNhh$gMoRde4et&Bu;+BJ**_08%b!qk2}-RrS3>Ke0O^p1ETH&ZBa1EMp|YuGSvz0pGOVKHJz(`XB}cbFhVfl z%c8zae4|=lfcCEopvN7F*jATb`3ZcIbjYSkp;tqdP$Em?Vt5F{0Q9Kl)_C`7`;CJi z@C7PKFsodb`t3~EsQeuF76{KEx)#W-z-9To_S_pU8(XV%>&Ej8bc=NDvIld{@-Gw= zrEYmp&mgztz#wjH*{E$a3-qBkI$eUe&lB+x*TGfr(wlS7KQHZOyRLtU^sNBRX~{>& z2M~t(7}V>({hFSh-)Xq z(eFAn<8_&TN!V-ZGC7KGESzk1ndbT;0(XVINK zES|H0gkjc_w&m`D=KU_4X}YxD6uu!W#-Pr_+f9!i6f=9OQX7s|*O zjlumA_po&Khxpj%=y9wvZI3=>C=Gc^6PmgvRAiB*hVWRe_J-3zv;0RSZ%U659`;?_ z8w*E%Gy{>Js|7t?u0-jb(`*eV$R*2L4FMamXnxqgzMP#gt?Y2HPJ_m zQJrE`hAHB$gZ;OrtqY6L9;QUh^-p5oG+?B;rQELKGxziUGr{U7%LGi# z>OYJ|X_Qe>bL$gL0mTQ2QTD_NCxlpTLVqF{>gz6@MU(tmbH2 zO8a45H2|k-i6WD9zRw>{-=;$N9S>3X4!nieGf3RmT zDiEGaD-#po`p4lU8ErafZ)t;QIQKeQn?&n+^u__jm3{WyvSw{fIDJ%7FNDtK&bQOr z+Bv{4_)2Nu7j0LU)pq5d1ra)4LZhtv{4!#nDpDIUMden!4qEq#P@nJZ8N%Si{#|^h z_#m)l2SL(dog58OGFCxF;bF4>oE*!;U`7`oT%{}1>uTrV2p9r~$GC!ktGWUmJj~)< zqMsK9+}9ohkp?9Q#k=g=EL)8D47={y^lB50L*#7@beosZ#X&+(VH>-dL@YfYyqsub z88=o@paSlRO(wdR@?>sJ54tNlBQD7oCBh4_g+m=%iBXb$?BF2_wlnx~-4r@Qc+bN| zJ=*(lPDdXW2=#JyyNPrk>I}N|cqu(DCT*6#AJ4bClSx?qLHj}N4Q82BeqVKp3YzkD zhRP2rRD|YBM^%LB!xX_Qy!PLPav8tofwy-RbmqJRayv3Hf)2*9<_$+W2_7oBz$@uDS;0rq6 zU?ma~o*X)|A$^l4ovCA01&yEN;cY5+-#ssq2>Y3*4Kd1mQ#EH_PCKTHN5RGFTL^0< zWV{dm)SBt9;7)ivspa+!*I4^b*mlsrvk*3SjI=|3$-mhJX8FD$-s;y!P z+Agiz0UVf6wHdTO@sz>|pnP0q8yT7{=(JUZ2lMSVzSG(ExBhmZe&H*> zp_fyB%)#B*EIDsjMCYk7N=tRh{)*WByP_+7(xO-+&nOeYN~*WRR{{NZreHD8XBqg$ z5Da-$o1}BHk;(1LBKOs#Hv^mUeIHLb(3D5f|NoafL|GF1(I8F=D&n7i|2Fdic@mGK zgYBYcJ5NDZT?eWX&IP}Xjm?76Zfo?82VF2;=edWbj~@%_-GRXt0IMf*Ys_%D;21Hl zq0f)AaLpsg%lA5k)ZOfykpSo-Zc<fmrhX?N$UiB0YecfYzv2Mbe0nYJ4Y z&cosrC35D$3poxiu&!=xvx;NcYW_Dkd0Gcw3%x~x6}EU2y09z=dHfpcPFhMkBQK*$s43ZDD4{6 zRRt82zWf?f^0_bw$#eWvHD2lH)PMCvNH9aFV6311=T5wVQ-(D=9E-q;a3?uQiRbiq zV|oVorG;jiMPSV9KD|a5ofk4JRaXyBMyLzS&VCbyi!HT|pN3V`!#37Q(M9XR-b>yx zJFRELsD(REfM-P2RqX>H(U^FjDg2*$Ni%E_Vt=bV3q3LMfm3%faaS)xJ>zA*xUc^z zL14ho_PoemOUFP}3K9G#%SD}L$h&c?NtwYlvvFp_fxxLMx{#c>TH=Rw+|?R!>a!98U^T-z~|`{P3q~BDJZ`s8If-e0b!v^+6rC@x5y-_l}g;8ut?h;ZX;E z;&Mqy+6>eP^F#MEYpAFZ{H}-yUW^3C@P)=w_EV7VlC=e!F#FkGjPK&1s9w%kN_CEH z=k?g_VZGzjZu#H*Hq(34d;+cuO?ZqR`?X=CS_QfV^!nL>+trxKWp5cZA92I8RV8xe znbbRqCw+Z_Oo@KpK3FGlE#u~vqvB$U6bCL&jZju~vo-Yrzk2w7iz0{J8j-LF#i>Dt zIbm}r27s)ofl#6>$&5Vtg{!^_^lidjYCsTSeZJ*?SLN8E6dHl>Zbk441t=C3BAVWG;`WO0x?{jp22`^@Apk%PRk;tG3VDIzXZlZ1TfPneb3=CYk({Qcz|&VKa^M8n*WGD46&fKMH6 zUOZ#jo*)X`7Vuz$X~6@R&>JqUHrTE(NOst+=)bZ*99?9}=kZh}5M_i^7KAK+L{#5h z&@W+fnAEO|i2i+>9&t&f^*s>_PMAGj&~v^o@7^}c@`$x2f4V9}=Uc#TP#1bNh}3r{ zmv9(%N8a1^9}rC>@K!`k;tO7`qc6t0~dmf3}+>zEVFhnUb%fd99Ym}y`4e3@J^F-}AU0Ef+EEZ~P zi+fHWflL%ZJ#Utx(ijrN<->n*3%17RYS^D4=Eple5Wj0J&3h+B*= z)l2w}XO!i3wvI#PG(rOF=dTNG^CRn}8#A_k2#cb6Ln;_H2s#%qm#$AtvO_hpe2OUclngfCmel z)?0m3@X$`jZ0K%g1=C)o)GhOW?)X0Z0`aJ=mu&<;ol8MpHdYRRsm=aPrVP9tuHGAcxL zW5=$LfGe%XUcTe8@mB_t+vf-nUqSLbDlOt}aX#bdYeGoBD+Ty71ojik&mArwJnbP{ zHqyETDBSofFAvWVgStIP_UDAZmL?zydZq@+_M@ey3%x*g?leI%zFHxrSI-cWBNCr= z%Cn@!eN5v`CI$9(NKP&kKe`Wf55`fE6q=d2cRreUJhtpwNx+V`JOU6z4YDir&wL7g z=M1D=^TGLr<_deIS1c}xyZ_)gSeW?Nq7twda+&knOGM{Ki5Q-Jgo&#JNpdS&+sKVX zGI|X=TQJLlQ;_ZCb)8jK+uNo4&_Rf-&PY_=@837cV5PW@+hRBat zbJPaXJ{;`$+*_VGLY+JrSdC{z`o~kYP4=kj_7r6u{)PDe&Br&xZRQkNz*pX zzS(%D$?>swC!IB2u>B8^f$yJ*#r*MWb_Ol6%U>=y+2W1(;FY_L^yP*M()}UwmE8LA zB|e1XeFyCfl^CIsGVoBx#0OLT#RhI2J=#uqeU^8oActt<=Uyx`^>oHJVIh&o-)Q@B ziA>m!>8uIt=cdiI4d-G$h1Fl;RZnYsa-%fRj_VJC&|~ zR_j$1-mjr6wCB0XjJk0&+m;QDxB)#Qxs!X55 zYbyD<%)WPNTB=;y(Jr$iXN_-H=67MJW9L2ieoGFE_f;Z<%s2XF`;u;BeJ4e|81qlt&P8 zVQf)zA-yZqP$y@CfHZY(PSM*XhQ7k80y2u$!yk~tx~IrMZCfM~_I;~&rx4RtcH+y` zMjR7~FFVwN04JJheg$UAh!D?6&q6HoQ_PJ*FawE)B6 zvAlItXew%%W(b8e&v(*TyP#J8p*h2&=MS{}h!q|_)W|Zga*ye%v}I?@U2qy^F5BEu z$HG4`?rXQvq9_iLs%q)2R#CS%MzXGz8p+d9i-qI8wEB(;xYHR(SW8Pw*1Aqyi>qJ~ z^X&{e<=fq)<-He(gZMHHb8{0U^N11E)~$n0?0k`P{3{<_zpq`QN32~p?|E7%9@(m7 zbL>EpfvHvBs(%w-nU^^t+Uy$g19-2oM~&tQ+_C`1E!D4noqHI_wfyMAMoTzd^H8<(BN!mCO=&!#izzhi)Va?^zqF8^`I(L; z@Y-%>FezH0CRmA@Lk%qd%`i9-Pa z3!S@$o2|`-8BB--Q|WT>rqve1!Lv-rwsDSWVamqhX#Fx(>mbWNOm%4b=`u5SMMIr8 zDLWlOjf(*%L+5pwBga*$;RXfC3jaq9Rai4{;kBumTPGvOeiCjoR~l~j^3R)Nviax^ zoy(HN^+gXmHeWrsajPVlI2vyzrdNvKbTcCB46LYSiir8ac2_HNsTV1GOVZ#m<>9&} zUTdMe|8U@mYyIBd+Z?jSpl27<5EB0R6gJ+mJU-lU0wQ{rGf4tat3|@txo=YI(#yNU zJhZiAnzGv%g|pC%5EWn=V`l}dsX-`b_)}nSFkUhh&vd%MSvudh&qDg1&sofQ;jsh# z6BEbVk@_08F$dL|c@&W;G1O4K3VK0aZf+c4X^d4i6F2mJ725$PCQip2Ms2?Kpkr&x zYi#??uhkM8S_ke)1YEukHGlzV*Q))gU4f~(%_uF>D8Nq*p}EKqU|Drb<-Hqp;%-c(7*GT05J9XN{-u{||FrJQbFGh#xZTMK?b=L%vy zS98&myQVb9raf8TLvWTVH&Bs*oN1%0z*iITL!S0(KRYd$iX0c=SK6`Tpns?;uNEv zB3q|)Dkwp=T_SUh=pJ@zkkc5N*ho zbIO0Ro(A}3^Umwfc8l0fjxCmZh|uGAYYAVqX( zgOLDiw``}j6r?~96$d?U!{ueG?J0Ii3CLcmgrcS?t|=P+|6sRV^CM&TRjL#+A!nw z4V*)+eI!e&8qiKLtSq~0?V{d%w0z>S$5itCoZO4e154b^?pG2gk?9XRKen|=q<((9 zMnthZQR4QiB|+fCKaUP3ikMpW+AfDDhkbKQb0pqn6?k!z)A!OKKcPsM2uB?}^zQ2R ziGQq4>%{Wj2P&M)GjD70YVRQNBP2}r+4GOTIR-PXQ&2$ZlUjE3TS+3LnoJKv#=fgy zC0QCq$ek=9iSM!2c%9F@jdpRQTr*sB#QVP3&g0euQC+nCG00T@l$?bpR(S+4B4slk zOUT2;m-F>3#z=s<*|lZQku9ZEzEQk^;(G)(@U$o2{8{(c-RK~S?LExV?Ckhl?Ny;< zmot);X8R%eO63<5HAa#QD~rxK{obeLdaP6(N)U4!>#H`cocMQ0)c^zO^f{U-vLQ1e zlCIPB^ah~^;~W%g0dWz29GVdtS%VA@A>n~Xd?gV=$|L8kQ{8(w=Bz}63cp9M=!n~( zFto1Pr+iM!hHsw@24mbfXDlFwUxTPhy4w_(0h)jHQgA*;N-!ME&H2d7^W45K)%zDh zodKI+3_OQO(>OajdqBns-3vgxkmsh~6@50`X9E>Rxu}#O_IHdmuUQKf5i8235lf2y z>lr3nk-JQe3aJYer^~o_WGmqLrl0ztmE15&RbMtG)bCXaR44!IesS>!`BU@kPEC1wl)1AiF(#LM~&8Bf; zI-BBqZRi1xcoYEinHw0ZA;YGj}zG&@8$d-MvZZ?uBYr+8k!) zR!L;wetIpL^8V;=5uT?Sl-O)rp@DO_mLuHi3(pyIN=npAi?j+*pr|(M{6=j?_;25s zfF*s@o2uvNVIA(o`;d2roTrsy8Qr2`XA%tbKEndajI_O8j&sZgUODE-!=r56i$OO} zpTYJB&Ud@e>MH#DMtpcOd) zwa*3&qxCB}oY`Gy3YnKk*us<4faX1mA!B~EH7@8Q!Cf3z^>=0p5^dt?LKk}&kQm?q zqFceI=_t5xcYpbyXP*_${)HeuRfQ_4ws1RA48bp3ldUZWs|r+YpVz9-H*ir zN}=Fr$-Pq6CysBlA=CF4#Th@ex>vVhE+Hb-P)|sM=lP9;um4PqY`Q zhIWtIEy6q>R{uyQJHp;7Mt-xC@a$6%9E89B?VxL8SSn-&G@`pPzv0`o}rVN^3dpUZ`nGG%=#k1uQ+B-B)~xY^cod z-to~hvN8+}?#Ckyt)JzkosbN>af$B_zK5lhW&Ln<-mNv8ci&8ii!TpVr8eF-;%a;O z&m(YCFRyMHE~J}1x)S?@0~2cT{J91(|FUZywd2U7m$!GqB4n$JTPn8CQj*Zcg&J)f zCB={33qJ>;%p=^iB^GD;nZSNJRF@QLz5O%nC9(%rE2n?oVcQrfWBWsPg7M~Jj%E0} zs82i6Npr6gm28U%Pf zx1ON6%24scQUkZ~6W0yEW0lZbrzSxZh{~x4N+^U7!Rz6+8mqqmC+qFMPxG0?Za6kt z1HUF5tzt0`S+KDrK>`F|XeHI9@_X~oQnv)KuU-MMrtNJ%Nu-QA%}NO!E#Ee*?e@B90Ip5r;PXFZ2!p1J3~=9+6};wcT( z<3s`7(;kY@3g*dkc`q2sQUO$d`Tu1gS)7NqMkR;Ciy!<7x;%JH&94G*K#wi4-4Y4m zMI?QEJMY$-A;UK%vOLv5UavzVYBOBQJs)B-Fiul*MzWL?%u`Vp%9o`d6;|t zEZ5BJZ2!{_BO`tlGhElicf+EiTW`#!O#Ic=0L1{haejl;cEa>fcji2jETBCwA){Z`G~(9VUw&ixi(kL2Gk0q%an8&_^DwmjYebIP@cw%dH^v(dvfE=pWyMw`-kaD=Wl`UIIn0(QXrwaQ~CXh+sQ z8kuJnuK~pv+$}wI&4qVY{D4|e7A>t)p-U*+Mo@m6kGh3n?r1BO*Us2^5HidpO$luu zwQ-N{efcnC28c|_Csz-ukptQ;>VJ>NIJ%FS4MZk z;6*+j`9m1RgJNSn8liEDsm6%+GHU8vk=qduHv`!i@L#>%3|7Iz!2FnZ_QYrJ3OADG zIm^2}Nw=-z8}G&8?Sxb(mA(1-hCdSPXWZnxhEbK3$E5dpltL3}E>F(R`U=!?`G7zS zEE~mdZJjp&6IkKY32!m9qX$01V3s4I43Knc`p|~^2I2SpBm<;Xl4mu-p9o43mPPFZ zW@nhC`51id)S&oht9dsSUcl`7VTNAcQlW@U2V=T*>e%|rIFz+}f>M@Zy~t*^=;gWr z=>Vp;&ug=FFIop%m8~Z!+9w)!yh^Ef`BI9XeZ>#zxZwD9YKm>lul@t_bN`UMicP|9 z*5@1T*^O7-!v66&emnlsut5s)!QszA)goe78(t`c_S;w|J zXl%YN5nz<)zkhcnKtUN#);*41tS>BE8D< zSc5sB(=ZNf{|m`QQ-m%u;e{k`5XCE|Ab3a|LJLy6zt#FfRLMVOf51?YIAV?g>VbJv z?f$`?_2+B~dtQsA`Cv%3EDXs;UKGsE5$4zSWt#qRBdh+Y3z&m&>`OlC!7PaLbJ3ZE z!0kPOjWAanKOGbbwG_=1t*25u1F1VPUP-0YJXWLg=C zL>eQ~MYYR~F+hVOq`&OcYh~TU#H1e3Eod(T8;jLTvPp@Fi9NVVVsC_hmU-HdO3^OS ztX(qCK5}J%zL8Bv1ULAlcg*jaqr5GMm$$KkUXqUA)JVA>UEWKPC=Qa12@3FiiPi31 zt_T}X(Of>9Tl{wCr!vcB;snP^Lq2YWK#`Jy7va4DLOIVF*b^NLW3+*op7okr@Er?0 zWPH|(obV*O^+jqz3~PmP!CN?9{EE4y4*B-UQ4`x(lpxxjG&3@R7K+Lg?+r24`w(uh zUolZMW)*aWTiZj%&loYw0DTW^sC_y84ER>K-_57|f)cTyMuG_v;_%wPBccIXMJ0d!`oLnh4w-)qoiDG!W=(uIrTBoc zCgs+_*@;Zu==)tokDCU4rHR8yH@^3Pe?!}zhq=h(zpKj?&@rxf zN#}R(87woqauHs=gRe0gbMLS(szP$~F@H|a{vjC&n5PhvFT4{QtqP6|CDc}XW!Dy<8*Lx}{*hgDOE zpgs3@YJlo}8Z~X!za0i?@MjWUvaIO83JG^2HAs$()qZGZqaqfE%dv?)sPhv~e0;j; z=5~KI^QFi@ZkZ+s&0VyR)Bc*}Kl*_9$F{YOW$~wJvi;Mx!I`cD5k~}uGJfoW7IXtn7qXQS zata{|Y6}Pms0TBv(D5pYk{?r-TdNN3J8vS#4uS@tCT^OdTK^tHzfT)LT_@j_w^=Qk z;t?IZn3`M>aV^!Iywbq{w_Wr=aW!W7GNgQg%s<3c)sPGLw`a%F@x1gOjXI4+zJR8~ zvzpt6=uFTt(+L7KDZ|?S_r;AbWd0amt0&<*m7dj+cZr`u_dC#0yxO!tzZfzvfsRX# zoStW@;hjIly%?V^UrU;JQB=iQ)4D`j{&S7ZSAG|_u+IqXi*t(oTA>?6<(;4ci&0lI z@BS8Liqsg-MHu(`yN*&$w~|2v5xjE7mD&}~s`rHQC{|wEGDE)VmLXcgOnx{-EG~(Q zl6;&Yt6Ulep^K)fCt}K1B;wD`KgF$Q3m*gs#YoPP8?r6yuh z43x|509~pFU^PiL81jptBL^-Qul0b~ciQU{8pt$z3dCu#3bjv^W0n_D{T5bph14S~ zI?`>v^E(*hKgV>Z34zaNb>wit{yuKTEKgDFgq(ZnBt3kwR;+Fy5EoS>vWJ{!Z4I2Z3`SMlv;c9l~R=M zQa*NfhQVU;ojY+jA&K9YnH*fsEqA5m-1S`a{EV*Z;t@l&@kNQGm;Y+NHt8boY`oC& zvQvQJ)gZnahM20dK)n|zRR#2Vbte2U+T}k!pZx8>%0ly#ob#`>c(kf;hPt;Z13L#E zxGRm0_Fc6gwojwLr`@c#qU=^mzE4VJ;QjoCCoDZS<44}9a9ZR-&1OoQz}!q11QLvW zxq9q%IpY&EG5yGggx~E-XJ%?dP7}hyTghE@=h!t}Bj3iaY>y1@b#%AeFBN%f{jp5(1};{2ozJQ6cD{Xupyl!%tB!--X>}`bG&?cyW;| zR{ZOUiSM`j-*%3AK5y!dr}d~tMBq6tXuPbEqW1RilP27y#(zZjrH+C%((+DB z6ukd12`8?)6RZ8SX1%)^WAy#un2KTfY`Zb?JwIee7a6=%pB2gY9kcw4pR^_hD~m*3 zynHf*PdbuZ&1|kN363plkXC8Mz1KPZ5Fo|z)thsB*>7?9wzY_}U8DJJKQqxJz3^e7 ztOP+iKO_2{4oc`7)h_%mjuSLg5Ekf3iPDf$>VX|_N-l4tWwi}iaeWD0II+8>w*1V# zuugIMFwBs#u9@!s&xPEVbNtyD=R1q7gtsK%`AsuX!QDj`PpK`Qev$5KZ)j*pk@691 zblZ;sefaoB-iO#gxR@@fgm$f1#+*wXoeW~XjJEq8WG9$%FxWq70ET0Q(%TR2*O^YR z3!Hxb;YILO)iJMdmy?Ww9PR;fB@A}8$~nH25_j88nUscEe&PoH#7@ArazdPR#lu&B z9z?Jvl0r^v@!K6wC0ioMlm>hqpJx?AxI)vtV-Y=^5Ixa&O>)7)k(Uy~*2Gm49(@8- z->D2kNRNN8bDpiQO_{yuoUN*1OKCA0B|4i#o5{zAyd4WG{?+y*i@pO*F+>R#!{@iI zV}2jw=55YFN4=r;@lS^A;e{-!MPgN=Z3e3bM#WVh=Ob&DNV4CPv|R_WwfJ^T8em*S zBQu#E%8pIWS@prZ`>V*i~lhZzHwvposz|95k-!=w;+d05vXXhjI_D> z=)>m%qkv7UuPiL!G%eXxDjZA{^6^0_4i+2NQtH-<4_v)iMf&|G9L3Wq zhQTvwsw=0%b!#myn}zCr$uyVxsh?QgnHJ?$Hk>*T*6Ncq8k9uFweSK67nnYwkb&Pm zPGV_&^~p4Q_^$)~w_g0Be6tmy5qNQQc8ADzM1&xNAKVz8l=QIq7IoGC>lZrjG${w&%wLx0-5d z0cEY1_(3>C&w)7)f!c5t6f_Z6%;0^%=c5Yn+bMRW-p0s!6mQAG2D#@xZ-28*u5-dSm8cIm$$J*kD1&xf=v zULR7bJeQA8jngP=G zDoqMS^l@gjt_6;rRX1r%>$E8{0(IO zLzcHla3Nel7}^idLQnB^HNl9&&vgXyxpL4N+bLDv&>CzKrQqE#nWl{x?K#V4?NSQ~pE@ah% zIuB@x;|17Li}?%9tqAu?SnZ#J$cD&$X|LcOxhIcsok(lmo_}dOJ#1028cp95rn4}? z>mkK9Vt{(}?hi_$Skha?V#zU1cJAA(={-rRf}Y%CQVc}=L{4iX!7NR=y}N(zm=?;A{uMY%s<*gKcD^G*n{8I zsD=0S{)5h6o$zc#HGhIa`I!_uaogT4=O>3{jQKrxXYgc}6KOUwqI#R2#KZ9l8S#&W zpf-zxboTFV%iQwN)#YRUCkhr#z%($5`e8zYMp%(%2_Kj}sFeBy8%*2ln{RLeJM7;i zea;QXyYx7y^w}Hr2X9C_M_OF&Km%{ocU6f3 zP=pZDc(+7xom^E%rp1d_v5|YM5yo~_#g;E}%2#v5xSrG&b?g|By8j}-xH8mr#s0?< zDa#pD4=rLc(UTc!lOf+7?67H>#oIPgJm708rUU5G{(X~$$=V@{V+=n9K$HiEy@}^n z8@8*xkC(^dG|c~~0gQ0KBAM`_<1B?lt2R>3-~Yve1l5^|C6_|G&q%MeG)2|^7OE3f z_)n^c9;+S3!^_c4??g}Qzy67?JN3=Qa5;D+lgrCB_p2B>OnG_OVmnBpO5cP*r0IXo z`H}$=Mc4YVwhx5o?!@R?RZE-xCSaA9a_;LIt zVPKx&NSTo|Si(pkeSLuS_g7k2G>velWz8(%ItJIQ)`o4H=SzIm(e%qOk zg7<7_+wd!>1MdVgYga_V=Tp-MsLd`}R=W;cG;|<+i_iFF)0pssWVgx(r%UCJi!><1 zx8IN$S8FrpQK;t{&9MbMc9dSXWTq_PzC}%Ey~W6#!S^%bKXXXZY?DaR8-SE6y^LL$ zdlHEOCxk>6Kz{Px7fqslWn*$O{)t%aV%89&Rmza~l(>14gc$R>Te_=~tiI;fwd2C9 zRA$9TQ*GT1mRD-17=L~-(~(lO`&4Sd`Hidit25;4M7%+ZuNoKBGLpOAjTp4-tN?+iX0I^@`C3R z)>7l-Y~gcjX3`M2o*QDvT;fO?sNkv znzJyp&9|DkRF1O9eiiJO8+c>?w$8oS&lZoac@O`4v@GWuzp9)Gk?o~BP2~_$%YoGq zTjPW!>Sq1k%F0r|v9!0Zolz5o1UlSTQgA}N%7tuZmusdByR6DuLc!!|EHIO;=WNL@ zc6L@5Vo}Lq-*sE7A$kr5Rh@&;b)jIt4mQ{-Caa_r_1O0j8asbBv&sp=1AOeYONU{x z@0OUeBA!+WJ=F2Op6bK3A1|)d%$=?O=t!5~#1gtL$|?u~^iW*=1RF&BRIXE1{IjV- zEe%<$E5r}c{0x{H^>XgF0iv#7fNeH^xqUDr>C%De-c}>@HbX5PCWbu zQm?XT>NP2)XzYu~wog-+PaoCST+O1|mi#BR{QYh7?wy1r)|8#viF~*O*1bjJBRlFZUbdN$Gsw?eu@X+NhcVi8w%#Y znk_baoCD4rWBT5u5Fxg(_pgw`cJfGUFr&5+>4Wz3#pfj)78D!Gno1~JX`xm=^^;b3 zzhEktCf8y{kg%WF-z3!1)hpG1Ry2Q-S|^}PkR9fUO?bb+z>o6H^`gawf)*!3_xlMj zweOA$XR6FHwSr-Yl}Wn0lrvQ|?Zgdq`72JL*nhbDSt>iL$JTJC=;KtoQM{Fy&7BfY zAetG;uc9AtwDs}s14@L&w@UBCx7BCkrTz>Lbv8yi!t_4K^HQi+w54g@uL0jKD-d2O zviYuNXs7;^&JX7`d_HDu|I8DYH|Z6uRMEWJcz4A~yO|Xi*RdPta%Vz-9}{a%er?kv z;{h?(hYtQ4Hji;9zB&?VdiHjZ9`_Kz`(-rq{;bsfB+0fxG_=v%?tOyLBi0`SFT`CT zCFLb0Aqfnl^TY#v=MPk}q|l3Mo2k=&{(miiDOkDEKQx48|8e9ju-9by8!7`t@cuaw z)AvKgV`8*FOP<|6EPbbhR0bD#k35aaGDth#vh3&ghOO-9Hmx+q@W<@yzwf}%J-@Vg zs7$V@n;Ho3PgQy{=u{}0J-OJo+DxOE11Iz!y=5bk^KHFI>cjOX(}MhMC6J~vdIhC8 zRHKD_z|j>oc!Wmbl2KNWxtqapM+=6U!G=^99;$vVXkQ9>poG`2ugV0>vw*bk7v z-zd}XG3%%Ro5LNVj1dl|_7d{rx{6P)B6p?UA|QMX`6u!OA+={iNgW#r4|uATfemwp zRx)1mPG-yEHiKyd?m+TUVbX>3Geew0`sN=gAr2N~PG*VV)`pX7ekAxVsXfrknvNH! z9UMFDPL!Z8!<|0`G#8Ps>wMtXVFoxUP5Mz+V8)Ef=Ix1^frCLGrE>&9jcDr7!o^3Q z5lMc`FvmY-INX(=WU8&DS3w+RIR>K~BiAY|<+Q@WWrXnnQO|Dyvz2I%$G5^tlyM^U+$m$s8EQ$PdZ75hG4IN=|?P{Qu3SLk&B`X z7#w`*4eXX8Y)5yxzjV7koQ97zhkqkXgwnK}; zh>1nNj81Ss=0p`!5@!`3;v9@;J2!nPAyFZl%8@q>{)#@(bMU58Ty@A_bG9`2)-IHl zFw!D&UFZm;iEG*=B!-u$@~xZs5$471uC|wcUYUU({&3C;Z zpnVjqy0^7k23W}=jkZ;>!LxmD2P-wOol(O`V|GLRE@fC1-fy1MvZ-)s2sTAUw8 zMBsaa2@&U)+hy_T=}|y?a35HdzR_j-+aj+lFjn3Zc@0owA^YfYzWeU(q=W#TgUKTC z$m1iH?-5pfc6~bDb)0=GKDX!NE*lxNn+LubACE?2w0#)pUrgZW?62b=!;lE1Iz&?# zV!gCY^#!U13+|^j+jy=-iO74YBR|!#RWUelH?#i&RrTUyO79@AzzmF*4u&GCz$`y5 zIMnD^v-+(rME}j4O=5k#7pVbgBTGI~!4zJdn zx97f4NA7hF7wu|s8tF%3VU`(G8e&sKDZQcC%k*ZRB3_gcY($W$V@f64cbAuhXg1Yk z7xbS8f418V>^Jr^u>q78@r-Ossvh#x6I5@2R`m|ZX}i!j^_*=Jk#5Q9uT$zHlcQ!UQ`|+|Dz=%vrusC|%5RtuJL$w+VULU{n zN`i_9@m@O3;<$C*M@_)%gli`}4bCYbAZy^WdQKmFZuP#Utr)@Pj&@ixyK=;oJQh6} zMeFFa-g?CMP9``thJ>cWL(+H0|M=3!mSQmk*R>#;msAG=Nvg0oMdT@knoj)L1yU^^ zlTSM0RXRs$2VB+HNx{gMgGUU>lcf1z6bWtY@^1aED+oNWUlzpG8FJ9rs1PBHMzw@_@KX}Hg5*gcJ;!iyiA ze8lsB8ubY5Oc&@olPem5{GS~oRn;~sy?uQ6!P<>$Fd81sB1BOMi~#AYG**lME?;@c zl>Ye{z@jEw<3B9sYPoHj59NMlNz)4o3f{YYgys*B;Mm{0kFb$c3w-o_h<28h_{Vyh zG-7#zJ_axKsdZV*3JHtzsgrwK=_yoN4uIG>%it+^x7=cGB@PH?l`b^C| z)1%@-9AS#wk*1vl=@QhQ{#)b^hsBRoAkE6OZfekzn3NWt-o+AuEpj}4J>$dv9YTWtRARb8fpPgWdyu55noT~L{|O7{zDXoo-G{r1B z%*E5TBIqCupU=o9q#j70H%1CD3pIFe7 z2HM(m9-fb!T0A0V%8M;wjX3xz2ONCmKT?$voYdwbTE+*+_Y3c(4s- zYpw8|vRKqv<@8GU{lnbqNqth+q` ziyz3|inS{+!MdC-P)cD`9AlpFPb0t*M!99Egn?Z4t6rTg$p67h9cn7kvMLtW_cw|m z6DuALYDm7f9SKKP=`wRIeU40R%Y3GjG5W)7lYTu2$v~=$i#5PV@;pVWMZxr4dGT2W zS80!)bpBfI-4<++Q7dpI_C&A)_`48~*|fCnN#-BkU0(0%aJP=x^e7X~(OIhW(c;&j zkCtZpz{Yb7W7RUp5*Efj%7C;iGXD&D*m)zr)-4+V4Ip7lK{??#f4kLaCm$JAggna+HeO-Qy2&epgLe+t?d*5Il6qj|^o#DbOwXWH3}Z*p1SXS#O#Pp;?wI*Crt5$8U0ytWqZ@)}lL+F# zf7Ukzb0OlxgzoH)hYQwIS6~)U^F2&rE6zyW@62b#{=m;HAW?16>y!0dzqu zA zfMkC-r82U%hO#0IJs;)Zl^qEl*F z9)YkCF?;y7fdnMniB$z^?>}V|s7;7UdWmx^oJsgxRR^alYui1fglOvaq|#?wmukM( zhv{V+p6GL1-q|$p$WC3glw7oCxt<$Y(xd}bYBl&>B8yWOui;N?RlmNMOE+QG;0Rn- zQ#(fyIBCPn_@x*7-ZV4#6YO{934Oqze z8c@OX{Lzf5L`0Ji#6N1eRp1+4$wcG zcnXInou6nkW}fpX_usLvp-3uslX7XUd=#Y;eIeauR))vOhGpSuw3vukZCor40c*_Gg<;CQCH z0zfnAXDjYA>Q*`cU2&JGfv*g%a+B4KBL}bee&p86#mfKPe~}-^@#XZWra~d5SLW_A z1l-3*cxU&OIwnb(r<2q`VRKX3e3{pWM8`R}UlE)FP)vc}zu$eCi|y`Z(x4iq?Ve$GVTD8wYNc#$1N>3Ql;LV9l ziXi<&YirIe%)XVoPGrJ)*Gs=LDK=**M1J&$UcjuyirCxp}kCt5D3jODaXtL?qX-!j&RH5&S6 z&kRHE4UBdK%E`kZuQlvC5yfvdl*lc7y!qnBTK2BWJQ@S9-!u6cUGh48do$!{m9hB9F&GbsNnqr zPa-W35VOu`Xy87#1vHif zJg~79?}6+*;xUsw=KY$LBT6GuA`g@ovM9o^eng;1K0G$>zfK97MR#k_$+5mfBc zd4BX1-dse?iX|BJfaHh)jYe^eaDxI#ZHh~&T=o^Je zXYv4o4&Ngc6em{`Z~N1nrqVYa_<=jP`oQ%+`!18+6Ab~nz>U#de$RgvNuNHMb_8Ol zNc%~}(2B0^WP=b-EZPmY`JUAUQMMAn=^H~g?~&)o@K)8KF7q^1XjAdxiqFzGH(lL{ zWi;^usmP|HKScU{q7u=EilRXh;+ZuIU$WlenIE&FrtrbUcTb;K{#W5=a94AO%nM`u z4@kPI>-voU#v0?!en*Krh!0rI*NbPtLv2 zP|=}e5$i4+@cZm!!;6b{^UPYzz$Ogm;h}ZTDm}?GEvn1IM&9^Na_w%V?bQ^HQlo-Y6vyfSD+;+L6xu{QT}K zAruFl1iTE~+(b*>$3&mF_5SXdpzZmCgAw`wfZJFvR1JZgxOrw;2}#rkPCGFYQ5nT( z3~9QbeNEdj;x>d?iwn4J{}i2dZ!_82wRGS>#TDMKQ|Qcc?Shihpnz}2Q)cVV`Oo9G zlPrHlyDKcXmZxJRWGLiVKYr|httf=!{+BYKJpz&;{OF&KM}!XIv2e3Gcwq~4ZWYB4 zD@Nv@2GWL=oHKdj*NP3!<;8N1+5%s-Q}IFVf4*q~Nzs3K zi@F&Fqouq-yk+C!0@MkJ3UKuaX=Z$@tVh9V(x_j1XPR44Z~_8#6Lr}5!=RbKwlb+u z4cw!2p?C(MEia4Siinrg6VLZkCGW>?hao?J!it_i#jcbqb8&(+lhY!|7jhL{T-S=J7ZQUj;;Xl9XfA^94-ybq*ubY`lF7cD#DfSRkeoaFu!f z{*b)9JiwBmKPud&r4MyOjbYgpOIc1`l>(KtVe=0GI{MiFkXNg}d#a~aBD@kF@^N}S zkAq!Syl=IXGm*df6)h)iK``3;9;r{H*%#*FfSQH(WmaOpV>|MObMA!+xLq}_;v%OHA;f%zzFp7Y(-_KzbYh47S zh@fc#->$A9*0k@(8?J@4xg1wRLl?>*u^xt}?I+(%tr2Xlrw^=GC2jvidLID)OD7J_ zkShJW`!zZUQv@Vr9(4J`=KjaSNAQC8_x@^{o_-6K!p86VuX0m6!7|F*7p?3X-8vC zyf;sE_ikx}qbPBF6aFWvjVlW?7NCeUxmcTGP-x%k2Qn!@x>eY(>lDvs#Zm{&u$$o> zPOTax;w%HwLuGR*&4Nsd4=ve$^H!~fj{e#av*;dD^yxzix{b)#-ZM4tsAgKxB2djy zgu;s-y`HM;lz4$OVehgoAWGwSzfqBgqe0#fz=gn20**-D1Rix$0yfz*&^7XG}TMMKDA*dT#PNiQ+RLmVOI9(+o0 zIAwZN9+TqjgR6O=G0@M%=`GkE>P=Lf(7BFekz!@-n@-jUy=tA|uKq4yX_esh{Q-@TT^+BIJ8IyU;3?%X|JDWi9{or)gEJdpJ zb32eQ*X@3PdDws5G9tcdq5+iUlwYVL+wL`DmORHwe}ZF2T5L~@Ej7&qtpNmF&opmc zuI~PH4_l~Pc$b%%=T{e4+?Ef3dZLjWz|eM;)PLXO%}8PPuIvTh`9bzH=bsaD-r1vA zQ?cJcQ+;{TGC5fN)hcSl5y%Ub3>@&p5_ir0UOqj$apEf*EUi7w;CAzb)Gxks7~trx z<%1Bi-F#YK>2A6sRzPAKHvORa_%mI7t?Y56x)?{=?-G}KGobVg3%{pkSl`k8LU(|G zOl$kF=hIsuimJVb6cM1Y=FX)RF%>c_>t2RaC)=)*RqP%8IewhFQ-x=QS@A_Lx3T8G zSicyyF#c=uekxj@Ep1#A#DWXZ`M{nF>TVqE9FfI+76z9(2dq>p{vv!;N2kq{4oKeiqY6&YimpQx)m%*EY=0o zq-IGcn64j*OXm(LYd*qHNJvnpSrFc8=k31eD6kTtiOO1*)j9Xk%3r)Y4eR~r^n!&y#_QeER#0QmYw)FezH3JjpsF( z&y8uvuvO2!x_|KefyNz8h;4)4wRiJC_-@YAGez3LlIo%oATI2T6#mXZ6ZhN&=a?B| z8O|WBzL}&o^H$bBs57ecXW;=s%sSrUi(UM7AcRB947)>XxV#^)&l<*{*wyZBhQVp& zVH1+1WflEH=|$r!nPqN_09pOD0$jP6J?w~C4##9nkiFgyNSWs?FdnPMGkrby(NT5e&9Yx8zq6DSh* zz-o4|CKcD|?@t-aLMQs4MFW;Kt81~+y?S;nA+z8*zXosU;Lm5H|G*%c1yD-Gq^Fn4 zV}(|R!NaM6G~-XSA~Y5B9;H;EL_lFtRO0o&d7_Mi?vZ;D907@rt-AF8UPiQ+7CY+f ze`acb7r(p@IDKMv^IGkScYqMk_8B+vL1(#@eWebAcW6L&ht6EYo!4(}ev|K|nqqop z(i##IU%%6SJ>u#N+TBza`zDw;L~PV3%Zr4+I4n&y+1I9qPo6ICjXVJv1UR=EyIsGf zB7rvjFdD_(ZM2<$VN6dnl6qE4X0+};&7<_0c;h?b_=_76nC3(-CBNS zH0YWFY0Z`!40dm#MOg%}0V!NZZ39X#Rgc2;$49R@-aVZBiZGTlefI#zB_d!_KIjV7 z(lm2WCSJc@_^w%~aE>{WJbtZ)=r_Z6ITZgiz!`Ztc6C|AbSNKh3ooVC*2mDm>)_f~ z;0n$YGL$5apVO_eB%^a*#^}MA?5(w3h`_+YF$TyR9Gs|;S_2sk4YIw4b-H4sHbaZ1 znwlE-!ybwXu#c5Xw;B&X$mesc(4%)9n1Oy*l|zRIUpenYh4wdXM3GCJ@6w?amlkc* zM0~radnwM!;$f$+YNL14n8d;GBS0FViZx|nU?$tP!%~}@xU&liT_?dUv-$3M!k~xz zNqkyuk0TmJ?IcUJMM^qyj4Ub0+uFhAvS#{*S)NedIChgx*8hi?45HZx>Au<)2oCYX z2))$XvetRTu{}Xl>N$JnZV+TSAo~8~+;N*dy=Y9_0alyO5?nP)aYujMeG|Vj^ z2`!k}%-U4HXIXkr%g(46^uhk(sO*9Yyq_I3*lkP+;WrKU`$?I7fTT$L1SHqB*@6R5 zz}la_4vqwD6*zCJr~r15-P~wh;n5?<`^#3X_yA{1^3*cxL4wxh=7?za?ykFs$Se%! z?tg4!zuNgj&;&3>VdNcPp6MZ16LttJODSwi3l^m~DP>CNBuk}d=jGi&-xg!Pe`{=; zfw{)@dyU)WF58;j-Q5L~_le_Kfg-4?dXfzY8yDB~^Y5XFB+wrAXz{G(k?sl*{ER-1 zC-_#M03`b5dkPq}?+5i{YR{^Pz#YT7*ZL&&zDRh1PE*xj`Q@_cJMxKk<5~tmDOzFY z=&l1E2X|+aFI}B&EeX(a&m$LCjelxE%>c6w0`+LcY58>cW9Llx;9w?gC~1X{g!^%I zibngqEwjm+d>M7(HMjQ-e@+yJN}p*eawp^jjS4c-0y3P;h&3Evg;TT_bQ%C|n)Mwm z1>gA66L9HFTpd)$=A5=+EdTLxI-LAsRvHBwT`3VN$gALs`jU6*~|?HQ*PEJY?W zd;W0w|5|`MhZD{8VmV$Ciw(KB&_JE+$o{u2qK)Ev=d1T;H2jm*@3T0DQn%ct`5kFr zSWixNBIj&H8elampKGR1i4xI?kf+!QLLeL0_fIX!R%0D*5=THUAP^%nNW?8|mgZSi zlj|KP?b^vjl3}zWbl!cE&@xFj+<1=adSmuq>nXJEKZ-B|>_#r4MzuUkV3N4`_ZyFh zs3%V`QGIua7%W2PGwsIH=xU>&6?Y{RUh)l9d0d-SR~MMx2*_3IZHJZ-AAL*HagCPiC)g47@)}vIX}a~ zTK@iC&=}gNozW5Xxm7v}beZv7p5%j2&9E})!1m_osEItlVcZ>pJ?&EZ zI$vO=Br9em4C~_awY9~%cC%gG`9N{Hv{AbLi*C!s5$~J9 zE~yAC(d0NLwA@l-_q)-Y0+0}N0T!ZiQMypeYJRaPdReW3H9riCPNg|gCxnctn#VpC z-F|a!C5U(T-~|9c=<5{-4p##sVRWT>Y4+DQwYKh7%8kX_+@yeyrO{~>rl7z6GP<#t z*X;CB%UM242#$9o3x01j13Y_=pT{9aruHQEtOFF@r@_=2lBN!z*b1*XcBb09@cdkU zO7b}9U^G~&a~4hGIN|`IbAQRsLK8)-)TKovi>D#zldlJg3WwdAsT_a<@dyaeSiG{b zvK-7T;WBKdY;qO!i)T|Lq4W8t=Da&g22@u01x8)$blwLtv?BJ)m1U7YHz0X79~A#s zK1Vf63LYLFz@*5=&D{e=E?3wth;bP-KGe|oRaWY<+>Rju76)k8SSA-31;G2wu<^kh z;Pz;Go38CTm#$!pf#+MxQXz{P3Q0~?y)I#5e z2r%r1xH{H>C>#jW2$3-Gj@LW_Z#RD4^S=OOJixx^>J(7HM()7K6Xogp;ogp>=%3g zemlA|Gvg+aS6rvAc+!7PddU_@>Oc}7h1$7){qHA(a~u_>CUtY`vw@|R%>*$8)Rjkv{|;gZPj5bt;kQbpyHltwMG{?b;H|^Y z1!9N@+5^MN-Yh;KZpaUxs+NuI#%r$J!h3>mwd2VPs1F|U9f`=c+YPESmM%=6!;R%r z%0=dT4l5XNBBEuFmb9Z$&@PKutiLj9vR<5Opv_I~GkK$uzyunn${qbON4%(m#Cywax)q;^|yp-^IZTUE9_{(}^CG3>V*N@H7(G*?qo+gNIo z28%9YL1@PTd-TvtksL1neN5Y>ik3rTP!ab7hR&`ovRgU?AG*+I*wQ!y)REK@XY)?( zK!{CDMddLtoS2x1mQH{@vSt9RqCY>JG0zg5`+Hyd+J9K;iV!`3H|LO)*rU% z^5&w@F&m>5Edq-Z3YQ2OweC4Db6tIHn=gCyXiStG^f>n|Xt8vCCNo(;cd^y`hF4;> zLk>W}ic*^4uA*88ro0@i)WS~%8?+G0*?LHVzHL4RW@-byFqz!ZWpKsN+lmCx-$OQa z!*-HY4THvm?SpaZC%H{T69btL%#2isq)D{6xA1fY-)|ei!m`X^%)s*!_G~t>PW4rI zf0NP;itpaK#!63`_~R$jtpi3tb;9Y{^crx8bSPKe)Aw5XM^!nNSg6_~yvaxG-SfCO z)6L(KneGBv&%eq<*me~8{K2SDbqrqj$q$G6v%=bq)Q6+175D@YP79XYue$w|)JOl? zHaj^aLCu*#q@6;m8ehiIIj;Cvx&@1T%!E=e^O@rd!uBI9Ovr$YS4j%F``fKoqd zL0mBbptr$t-X>ZqY(WJ$9t=p!(e;pE+{>E_F)bi%3OH(ymEO-H^=N6e$vqfKV%)f% z^`zXzJNd$WeUE9%jo~}y@5wyC^+j0tJk>ry)@&p{>?kh_Q;fOS%lj5*Eu&^ryOno% z?~Deh6tM>_i9jC}OYOUdx#haN)w@=+b)CSYSNS6Wu_O^__3IS0=l3q%qTJF&oxaUX zp*JI)gJxf1;?YXQ$LOo%bayTcB$B2>pSXpL-2VQgYCf6NOA)mCWMJls4R%$zpG;__ z`9!z1NrPQb5&UMo)djx*A@DO(l14U^umcF8=d9VTCbW!t>K)cbzA4i*^(w=V$}kN` z>++xEuu;Hm9j+8VeTmjU{+av@=rMtUF~PRDC^r6VRLa?i#zy?~QTR`!F6KkJ&mbIl zA(8|DeZ&Gv7oT>2iP8haCjUmA4|KhS0OIR$aR+iX6sVe(Giv(MiaDg~-xBW8rv!p} zvslY2FN6uC7AJ3~{-Zc$KPIHh@1;+xIR2dRr1nf~B#o~($H%Yt-1sD+rX4g8Irgw_ z?d6J^IdKgU`QBjfY}fk1K5i-OHmP8!we_VrTHVjkRBWi$R;rG1zALz?9O_4N393E& z#marv;+{`0jzJgA`GtZ>RB(Ol&1UnWIM*C!uZMlmpqC%g`n0(_+^p9e{L zEbWlIJd?REneLtpdXKJc{+Iw(|6f9uPd(%RNz z&-eW5(}BZgms$dzytJ;Ozp{~*QErP76j$}_yG3OhH0hpmE;q^j2r>)IP&FKaKjD~1 z2Qe$d@t%j_dG77AYcD2xh6D~r=zFI>VS<2dw(K3I-eN2e&p{^q)pJxpS6WeV5FpOU z1DlHGoj3Q_n{h}O4Gsx@W@c2tRTQ$`8*U0_kaHSdfikl`DMczVTcLkwy*gi@kP+3w zyT~;FCOLr3VpAJ{T=ZD+q6IQPFc8{y6f`stfH+BiuEeJU`>co|T{>;`_O~Y zIoDLMMeip=lkH{P=1-W(91>V)8~79eUjou%tKVV1`kCEO8nc8<9}S=q#L+_ZlGsA+VN%y%-Z@5j>OK?pp+F@|e%z{3#5Li%z^H>;7co{o?yws?G6RSDugc z2uqJQq(CC!yg3KzOQud6Da{Ac`|l1Eqx9+Q44{ssCqUj~dlC4=Ap*9yLNtL2NTNMJ zRvCI%DP>g-^It6ByY%svG^6J=y*M04yB57yCg5#aS8L4_F${?3lSDq$d~k{(Nql)I z<)uG8D=d3+Yv~9C+~fdq&=kg}Id*FEif<(W%^sn4{t~_V&mT)h-G zUmkF$g^Y|8(88vUnYV#3x>k)@WSL+(xqtxihh!$ZOAh9aYl?wbVusc@uzACD=s9lgd0to$;^@rH7qNpP?hpd5I>Gx3 zIP>WJnXQS^3mX3R>%h+^%xksg5PAcJ zj!r#Rz5`|a(>5a(z-X&~D4P1Wc1Ic|vlq%@JYD%$9OYO#Pwo6LB`}3}?q+!4U7fG^9FxBt zc6VcwNnim}PWzwFL=BjbBf7{3Qh#*<6q?V%Qc$xG5y@i=GJ2QLz`s6FO5H6x^O>-L zR}P~{L3~SrN=7th1xlY`181?1X3l@3pE?H0Tmszaq7%WhPcgQ#d@zy%5sLKjFHqtx zCeR1A_W4>Qu3rY0;jat4quaCwVh-lS;-@%Ha|4`5`0?;fQV_rfvv&B5UC$gTiZ&yV zD2lY#-CZQHX-4NGGac-@IHtMs?$SC}_P|2j+K9J`GDU!hSYd|`TTqLW< zj+30RzahKOXbV$sZ2OykT=&j(kUJN8r5U4c zd>}mmYEVyF$hiZ@`X9}xR#wi4N7knUjGnf3ns$lZIS3QR6K8_DN_gk^YIu5$cU#*T ziy)XHWF5gd|E7KkQc-k{`F|@+Qhf@D+#AZ?y!~u*%wVRgVMY9#^quXbjSaeane-34 zGadQ262NJ<6?_lBlt@hhLO<|El*f0U6TiLFcs|dA&;Ue_sO}A^%7HRuzgLeJqA>nv z|5j)Rr_I9a)}@ zLty)8-;Pbk-4WktIuGvT{q@Q6d%ZTFWqi^&KDw4Ezh4 z=UFn{873@@910pg2WHxDdzI5&jZXYrk2zmWH=9MdRiS?iK{_=0}DAEgxf$V zW!8yMGxd&|oc==E-t)8Vt(?TLl@XGK*DQ$9BLa@AcxvC3 zLeZ@NG+V%ws~)#7W#a>YnR}OyM!GRZj$iHq4TKA=_XoagiM|{Tk}Q zpM3?$kcMH?)S)|$z-kk@lnunx%(I{S?*;TF}myye|N?Df8N1DDZr}%cs)* z)ALJg|x zTqJRY!2Ca#WolT}#$)m0FRR%Of$^dK*O<5-dN##eF6{%1O7`#HgRCu(|D6XRTn2bV zHC=63>D?vLa1aAhd;bC`=%4YZ{U@2R2N^w%vLf`tvoi1l$E?e6B+Q;You`AvKUNjp z+yvhk%`$M2G3njti8>p?bevVr06y6G`Dsn@XsksH;eG_<=|J{)TLUN$&rkxGl1itZ zWApK~j$hwnH?x204+fhH+3!+!vjRwT%2UGoIyyQ$0sncjf_}<`i1goc~0E_^66Qfma0#6cf?_}(UgYA`Yhge`V zc|^4JWfs*c4#w#CW3{ZO&lsz3Bj0W=3OOjzn~R4QPJY&mf=#tAqe{>~1fB6R^IiCg znTS?4v*e|1jMGEHPbQka$j+b#`oGay0r_3zem7Pe*SmfXPNt2X;s2z@$qQbvXr|Mq zHa?)OSl2CFJ=J=w2H7Qgk#=>SMG;#Zw@)v-9)GpZ{vtYGYm33nNwnY8&CMO#zPgDK zD}Z77?VTp?UT}dA^_XR%`LRIT#bbQI=K*)yz4&*FofC#w^WK>wHB=uau5M2Gt15HR z@8}n*nu}m6^#oy*aRdS%tPSxqb@U?&DhvY%ca!UlwpZw77S6x666|aUl2(W_m%XTh zBPNI3iY82yzjNNJm;8k8U`yZsBU$ltljepOy`ID!O`1_2Ue>IxZY(CsQ>Oh)hqYP% zU#G!fJ@dmO54O>DlyAFT{GugxRrUE+N|2`FA43NQ@?0 zj^+bQMxtV?ilpOVmH@sTkh9Uo8-!|DJ6<$cqjis7QOs8&x6U zm)shZqrY7)jWo-89NvV|wLv?nd@~0%hhptD@sS69w!s$FDzZE7FXUr5`8%NE;32^d zkJ#q%poa22hJ|PnrYSok%~?vm=y1X%8_K?VyX2bpQD7oGV0cci_x` z)lizQpCt75Mzu-ys0@vhbAMvr)AXf*f#JcFjiH`qG_@&i{8&-T-ffRJ&Hl|hUO3sS zjEdt|{3i$EY>Ow%T}3LFSPMR*bE=cU_IdcPC%w1&LRnB3U%%sAx>|+3-ig)rSMRRP znT`_R?|Q*X}KwN6CZ9KqhS8*^>4d`_4he zH6JcKRv0~k-hB>NJu+x|zB3m@j>|tHeBPGdKuZ(a*!Z=ZuA4_2Ef)4DJqtE=^JF9p zCwV0in>c!KoKQYT{)O;8$G1v;HnNqOUmpW(8(wwt*I*&9vq!>^gClhR5y`RD-kukR*_{W)`lXDh4^}S>+ag)1g6my@+nvUu3+QqmkQDYS>wdi+8+fdnDQZdKn2$<%S4M z5u6Hg;s?G3CnR}nV6%88lnL=m$AV@|<)!-OQk!_2;~qC$@og{_%_sClSwg4$7Fcsa z%yONe;@8R%s52BiD!Y!CI|B-oM~}8ytBCoJeq&~gZ(a}PkHm5z?{#Da)EU$-j&<|Q z*tHkga1Hq@g^r2AiV&+~pyBaPupyh*ti+~$dZS+8?{$ged6%I!9vM34+}Hn^`R!!iH}Iwcj;~8<8VIE z^ok!bcN`Td@%ZoVcGaFM6S;{pBn6AYW`DNQqs4b`>U%<6D>z++Fl%5Wmdq3r1E4(} zZ$EPZ#~Ij}YP@pvJQD?wnSZVCYVj6rIc=AkumKgpdftFc-e;IE1^fZ!Y)UIjAvY5a z1nnK_cO}*Jb;zr$JcOsluC>#or~Gjo;eSt#F5lC1pH6=(BRBzPXxPEv}}$)l0r1-p{o`~r!g9A zDfyrhkgC0im748rL$}A`5GqL1{6%+(xV(R7S5lLD11cRFR4BL-JYKF z^o$?jz8n3G|9y5X^ur*lF6nbci_rV;ErO z`7@c!or&FCRrj8Aaf9wt%WA-rU-*yNN<&2$BT=N+F9w~4q9-@AG!^^GNe}VcJDv;2 z(>+A6$(SCGJ*35Ok0r%v)2FrS$C#|0=+aX^jNC-5q%&0Etl^;kaPP$7vux1$0QGuM zZ5U;2&pAwZKbcyHcChji)H8BsAaB-|_MYg?B z9%nF+*OT2Z$0k+v>=+!P&HSRBd7GMzm8YXd z!pDd5nQ&`XXH~i#^p}RO_m$lEAXlYjx4~ELUyPk4^Q9I{i2riw+BIEu-sz*nJg)AT zYO%j3Nt_~n(v>G5G+5LM=HeoCX*sSCpzy0V^MG2b+Z$TcR6y?6k`X88ton|3KZdwe zv$fMOG$eCgz?bpGNPohRbd~;`eJMar%LHev!x8=BMc3oMv@rZh7^4=+6K$07hgC)u zxWIn3HMa}y-RRU4J+g5r->{$Ilzwil$rQr$w#KIeHKribUQ6wS}KJm#e^x3|R9b zQ7>-R;ZKQf0Zm#5}b($+wI+5KK;zp)Tm!- zR_4hQLqozQCKT2-HpCs~fCklSu>D4L_=)3JLmFV$&Fm)9d8Wbj2)>h0FONk2xKlQX zti{WTU5d#gNZM?zYlYiDYSWXxq=g_rS$4u7XBwklWP2!~8;889N*Rw$d@$9ERT?w6 zoON_AeciZPX2H2pVrAuNIgA9g5@4fr)Nh5^M-||U__vu>VC=0?N0pQr;jqSy!Q(_u zXZHuE4Fg~)U;W0(-~c2_8|t*%fwR;ZfqIlC181Cnl;Xv}+N*FRsC%JJ|6zg4QR zXYM-XHX|;|rYSA1e46`A7A=oFnE#JXW+Bm;@SxJR_u}}d2h(FBNKhI+4{r8CMa{|I zL+bU2UOM;w4e6)T`?&tx#e*zYiBgSQeaPGZZ0D2KeZFsnQ9B<|g}sLjPW=p`4KYIC zI}O4Le+$~PA9Ly-Prrbh?QmaCDl0Svr42L)q9#oQFBRlopVj*?=r}#?BI-Rd{phY6 z?bvMljBMOTd;d%5|9Js0=&z(qXn7OXsb4t7Ym~eCyl1nbhoE+nj&EqRq#h08iYnl^ z@Lx~QhCA;3@hqWN5a-dE4dUV??!^qZmUtk+vL5V3r5lxO3+p$NN2o>TjcJnY=@UAj zv+Kz-B>lQ&FqpR+-B-`XW*N*1EWeL|VlGk5#{2#~Tol zGm@_R$!-s}l9ErRmdXt;qZ(S>;ob!Gt`^DtM zVCq{4BPIB#r&k=IAurnA#`E&Kb!&|h@7&kwG&iE8MZNickgHF6T-FuVgHU$+AQ#8) zd0(BaaK?En0atq3jjkG>jI&o-T3-KNR{Is$$yjTM{?|}9?#>JZ zoL#NIXQRsds7LiFIG)Zr#2UFPpl$TjVHnnKYT;J+`xG+LdO1?bR(3Cca)v=_CCP_r z35l$P9EkB@y%q)o2%?6$e#v43C=Os~nG_O_%;;%${a|!%i^5K)n2eF-0sBU;p~Bh> zI<)}^*=xwLM!QqBlopX(u~DPThvN;z3c6 zDI+}?v|aohSZakDqNMqvh27E2?wae7$Ef`C+c1B5(Nbr?V(snJ97yXPNWHESvF3w)EXU)*0+;Pv!hqi~68+L?=6}RiMuj^7DHoMC5Ll zTLAj&rnA+~wZybSHe%ny$RDxKjX~u3V3%b)7~cM~l4oTu^sbXT&<{W4c$>d{hwkeR z^~OlCRmx|AAW%~nu6*Ta!ca!Q)fpHZw~HK`?6J#= z%+PuHJBG<0Sp2f8TLX|r?>*1VqjSh>Okby;g*}~bl3q;cr-wKF>`NgNEs`<6@^}6i@r#nTb;V2U!;S`E!A|^pey=%!1)~BBV6ItC-hQ& zklYxZL^jxmB@e8U5mlVEF%J-mx&C@zL%`ptk$Q4G)W^c_JdPyu8(c6@EDDSNxBv|& zr|Ri#Fa|TBAuA)}(A7&Ok{?kJt$rD}#BwI3U)oMuvP;X$_k;OXL>&eB`OxRnw}BA5 z>39+CItjBzJeXPy-iHEn@kwD6X8N+jF25|&S7&Zn#}z%ht)=`wDc3V~R6YN8vYGz# z+^ac#l|^6SZExqpJd)a?yz(o=VwMDdv7cN3AkHPui5oXkWI5IMxsJVMa&5Kca=*L* zvJ=)(V>z_wv*7P+Kmz?1Q~TxlvbvV0QrvHn!9*qOU3dOAhzvHbRvD-38^&jH1-neL z3J#xgTXx7%kOvC;kR&NQx3mRTc~>XhMYssipnmPFCLSbQM$O>aI7DfL{QOu$CRa+( zPU55P)PMH-x78k}@m}eo(yX!Lz8^6HYK4!-OYo0$ZOb6Y5fCb{dr%7M*<87t^l7#X znn@_@7qa6A2GqvQdc1PXu0aR?MF0j()l6QM@yBgD*h+;bj`){i{x-Sj)&Vte2jf#x zKFXR>YKt7V+6)FIe4vDJyHG%?;ohZ>LftJJ%-NLXBWt$M06hn?_E= z)s4Ah#*pi@2M(qugv5}1$9IBlRttfCl0z3{>JSn+(7JIxkYyIC|DeRG#9@WO2zk-< zQ<}vKgS?L`vK(n;!Or9t?ndQbKD2A|01oQ~G*1VqX3e_{evC%-ThX}AriUxxE2~eLLkFa`}wZ`<~OgyCuP=~ti2bCt&P5$hzVB`0KR5{D=;hJlSI5 ze1i~a=Br^sC>qUaXjgG1&imF*X1Gp%{IC;uH*0{l8m4FtcqXF&7L$%a8;F1^F}_YC zv!Xt=@aG<3yx)%vQ-B3+mzcT@=2YIrt9Yzu=t;A0f6U5;0{K8la*;0-;4*i3;?P;Z zL>cz5hqxuw@^kMYydA&X^D;oHx-$3hS2eXDBNEs6c%K^^n__4`zuPaKm0#4#@J1x> zmTCAOm$7|oJI%Y^!|xi9{W96CUblqZBx$jq-(PI|-O!2Ub7XnQDN?+J^(G&OU)p0G zRmgZu-vwc5kXLP)sl;%FpiCJBCGWzI1a@_3qe*viOJs)&kDkx#7G>z=PRTE5!jg6o~d@Hn6%E&8T+ zGX?tVzYES6`@x$EI;5hnPwefJG2x!^4;i-X(5HHl`mi+H_Mt-FtPdf*KU4 z(!IVS(cENbfbj(dBLf5)UvijyaLQXWW~*Ll_eU`|m-_G~nCy{U`g`Ahg;*K6>GVP0 z68DuWyRMfllXX5wHhyQygU9sq!Yaj_@or^+p=OYb3()(rduTrt{CV&ns^K;AQ!in$Y7jcdoZ3;EjKA`&+^K^nu;Ts^vI_lIRI zBr8L4>rX|FU?t!!NbZi10MjL~c1(n*$H{|_na)8pNiLFm`_tHntvi$*#^}mmb-^xJ zArH^ZFsG;jw-hs~Q$y>1gW&%BuS`ljv4G`#DWUAi+3kkNQ^zd^Wu}1(p5Z}7k40x% z?4QqMp4N?ohb+NDT|SQ7qQUrpaFCSU-uR`iR+#Pg;R9Tp?_sX;8lch z`^W|BCQbi)L+$*BWSC41hTG9<<_xLByY)rYGY0yc*r$LboQQ}cm3iM0c;mj0A zsmDgyTk1zP1smAU5Gzj?mQ-#4F zu%M^k{J$NIr|mplTm3e-^9oC!T{f=2&3%@bbt zq{g+d`ESp-+mn+p&PQ@%f}63t{m}U*{x+0|f=!!GI&){LWlj z8s5k-Wo&g7whR9mRLzwC;hcYBjOB7O?dQ9J1g1A(jSk0jOW>-q&}iSgoeCl&oO7f0 z&eRh+cBd^KK7L*ETC3Ghx-M?Q2K1S(8q#&RnA@uiD*w9_#)B&XP50eP12zL4&FC=+ zbkG*U{M3}W0xC$;NBf4wnV2h$Ce4{i?arf{W5KfaT{Lkx8-)iyeGxDQQ}f_oJ2kp~ z(_QU@=TlfQNh!p(W{#>Df+n1B$JfWz>>Rt{MZ$2UVd^I$@aU00eq<9(K-huD)2;K= z+(SwwVL3Us_h|IdhcrA%lKuExfs* zt~5kd8Q#3hRzo^Q{A9TOCLUi1nfy`gz%5uicy*)i%CEL_VSjx!xLyn8`nAn#d1#F*)cEt z(c9C5g-2Bp)vM&nODrmyJ|QTeCe&_RBA6I!OFue!J`Q1Pv9RXMr4lTn88ESj*Lh$KjVI3s9l%)3{+e)*>~|8Ahb zH0ADq2CwO+x%tl9;xAvc=lY;wZwEpxeq0&v)|5|U66bo_!wkutLRwiH6@DP{O?l4c zE?~l+Riww0ewgre!}oJvqUl6nqrLdBdIaTjFUPDL5OhjdzvwNx-S_? zvqnpF{Ur|EzO_FjV|h?TG--BIOkO`++L4hB<2hZC5m7vAU{#85gP|A|g!@ zfICegQJFVw*_~%dJTQA#`ubnQb;48_)6RZ+mr)kgGnaGf_8&%8`S9V>^fuVZL$Wuh zbci;i=;k^G)5_H@~&MkFZ?0hicve-vDKpub|2_nketR`T^ecYTKY zi~8h(a<-7B*?uJq@=S5en#Dr2OP`ZYVVBHgaWKC0MF zuR2of!?ib6q{LREy@f*)-oJ>1R6T`}gGxZwIr`vZ2N)XK4(2XxW(N_m@J-?JNfS36 zmrP}tpkIGk?GTq;BeCQl`WAthZ!t@^MZRgfw_QPO zs$9T)>12iJSHo4y(oT41Rr%-I^18iW0i=LfDa{=M(pMaO;21%gqMWm^uWrCvC1|G5 zLoc4GfYb(q6Mjs9hU`cWyMHGXkpC9-XW-L_8-3NDeYL>Xr=ta&-lz1g>%1H*9qu*L zC})c4TyI#(#S~ZC%;a7$rAxyY`4qiyTr*L&(qoK;JyQu?tu<1fvGcWt{&53}Q;3c& zyb%f{ak}mzrRomabSG{?hfnla=SoEo9dV^YisUp%ov50Pdt=+Sn$;;7T%z&D16Mj2 zPL6$FPP_`VqXKLO>CX~___*525riB%H@)!pz95Yjw(EIpSMm?mA^LE;T^pD+ukvdMMvqooTU)E0HYJA_Y0rKwFCU&9*BO4EmLU92>e^y0MV{bO9JN3zCC~j^ zI>guSTNJEDvvmcUBg#eAeZkOiu8pMnPlPN}Qw4AC&7>yPEdJi|*Q}9-=_`Ii;g@?8Y5Xt6MK7CE_UgC_F za?!#1>*M*VT-ZG2MZ6BG&W9^w)3=KqKjJ^1%ZrptsHHt?-+uMjUe&e;d2lUf&R21$ z{evUbPI;Sm7S2jDd*6bx^z}1^Rx97)dN49q9QXVx2Gb z9;f!{pFv&6Wy|%Xp*Lyzm<=r@1qB3zT%3#gmzU(YsV!lG-)7uioeW|I^h7DI6xTc> z8i%Jw81gq5PcG+8wZ%VOaFfedRiVW7t`31s_U5@b=}=6ubqYc47j>8|V#6?+=Gs+O(=|o{qmehWtzXrd5^t{Ev~=x?w4C5-(V!GAHR{S_leHvD`UR#yC)gka zZ8DXWP)Fyq&zEr>s*KVtH%N1&WR?v2|!R#FNYvJYKIpR+Q5N5I0D}jBb@wkjfb8RI*327LDh8PQaOg?tCZVU zt-w3+eb39x%ID|PO!O~0<=Op5ckKjgiS(MgU*5rx{EOY zYUix1?$TW&i52^1860e%?&QN9&SHK` zmU%T8;#sS6f49;h#P-2)><>nL@F4Xbjcd!9gop5f!yW4TGM0a?-Gi8zP!{~52?uWp z5>+&so7GZ^Ow-LEw~w|*SsI?|z3UL@4 z)fBT)qdz;ID)(R(g_$u&^$K)nOSqu!UpFZn4fOMc+hnrl(1A z@kg?=Q)DTBvz(=(IN?88HAOkFt?Q)x>fv;K7u2z8Y(X{mnPloE8Im&Wus2B#t(XoC z!-;!5PSWxj_rzOn5^Ib#nCOVLc!DV|*6?6hc9h3oKWDKxu<+r0HFLUlbT~1i#eVTu zklGVtdCN|o+am@}$Tk=|)%cdU!sZ^IZ8C3v+6ip4KyOZ6}7kwvP}>Q_;AHu zP1x2{;QVJ54&Dys-l_40DWzS?t6s4@IB)7X#Dy`U6$XusHg*PrO#X2aJCEa4@7zzg z`Wa0XjmKB{I&0<)(vIk!w^wxyh}T7Gk@Q>>$L5*64}9vLEEBJfXc&#_h zI24*9w3s>LM~c{ca#4G&w0QXc_E(|4c$W%bs{&*qJPMRh!I zDIoUkL7(!}QH<;<;+i8Lec@@)t97FrnvTy@M0!*!#;eH{Xq~AkFf3F}Y*Pq6_^^;~ zX-dZ9#%TZfEUNIA9oB(>PI-DWWB+IpyN(TKwcn|0)RROz=d0=jSt!o?8>UlvHv!>} zklp#C7P{W3d1U@&8_H)?#S{6=A!;XxMa(3*Z@n^0`u|{xLL7aGXCW$vgQ%m@h;;6t z!IAD5Zc3DF5yg6D*$*bWr@_$SO}LHcmc$u1*BHW~RUvsMqTpL~BZu0Dw9zq1j7nnV zjVN2fg1$3L&XIqlOg-0hgcYOJ8E>M!TVz=IZQJlklWy&ixaG!7{c)%nBVD0kg16tw z{01q#g(aZZ#j!509tD=awscp1m_Bc!`VqApgQ5)$uo#$kR7gEkW0_Z1HMNs_(FMM8 zGy6H-@fh>Fb2WEl;`3<86~L6_RxeO~;KTDgA`1^6&_;w4itvE~z#S^Xqy^`pXFbR^ zHq?`&0gq8HyE=ZAgkl!@z-ye?3Z~+FI_AFU(m-~PTJ_)dX6$;xr<-J=5Wc)8r)CqxHy$#(nuQRi>39{tS#^UrQ*k?~HBIpLUqTI#z{> zdC`VHyjy7<${;cogIg}7@fZFl&I(2<(VnRi>)d8F3bJm#E8rD zOTbi%FDpc7nG1>gP)igZa3>$Rja^u~)-Tp^#ipFM=JdeA(8IBEgnVjY0!Bfv8EwNP zWf7Yq>2i`3{Y7}=>nQIQ^@X8CDe#IWV*)$JXJ$5v>l2FF0y9RCV8YBRoNk*E#i) zOgkSUS^0l!o?AK_zyBPKmD$r-#=_6^ri@5XprFf+(yk_BRPqSw%ZFJP2on#oh zjpv~Gi=t=V6N9h>zsU+(M60y<|{M?>S;Z;rp z^$KCh2>fF5OT)aR>?xNg_nG4SVhZ_)!V5)dDHxgw7d$=uGwnG(+uEksKSDbfT7imj z!)#UzmmP@Y;@l1o29tE2TTrj7!KtlR!2KtRfJ+Ry3>yB6k_cxb4@R;!|iN;wB=p!sTnm1gtjY!{$P-M3E+7!R=gDp_V-W_uT$%bj~Se1;j9Kufmk|k zuf9FV>T!)mp#`bye3!g2T-8|UM#hk6Ga!59%4`n;s(v782_E<4aJS`V_L^s(RglDR z0}MF==$Ebn6y-IH6miq?ieh$8=AEcXhH3-+r%NCyDeP`hlOr%|*kvztqHSm8Be?#p zQl1}|dU-kj@A0(~;CTD}(|yx+(KLrqc7g?nJ9$#SGgv~Gii>6plOLly*$NYisSOqWUTYIN5@n3 zSpiiGfm|qGxF`EBVbvKt^%8BwOn`v(-vdP!|F3~fklf_=+bD)q)snqqaTRI@;Y&{e z$brq`J5El5Jjs}ZwhYt3*ltTA{#5xKB{Fuk0!p*Ut(Ml-LyaR1I=r9z7Y2W@PpQ2# z5sg0A#ef?xX*ncI!LAfBx1Pv;Se24C_;8xxQ;d}Q%eWB*!X6GHoC_k85d7=gY#7d$ z;YSYTszx>$FCx7$^mn@aM);@=B2gtRa~z#e{L0mD{h~ry&>eTL$?~DjNN0@+V>mhI z=!Dwql6dtficb91ilO^bHY_}unYW3C^PVJ6{FXgO-cMQR2E#Ck2^UBjs6y^GcP-n56ip)Uf^>(>p#<%<5k@kM9l)d?zu(ZOr72}Tf+#o$C1 zB>gTM^HT|3R;Rq`^x$&8#2y0)MWo35#6zo?CD855;}c5K5Zb2F3~^KEd}P3Dl9$mx zmEhT}jdxWj(iO_&`4-$BxaDtYy#rH8U@zLAAo?<1j3kh8Pn&ETIc3Dxu_MIaSo zHx!=#dtm=Qg(Q644)cAAa5fhTpJ^IUz8&SYrvnYEX;v)WcYaDig&5~tRtg~_Q~kR) zuc}7o^z{?%6M%%G z36{-!86hLglXfx&vN+IoFCKyg+k=OVt4v;ec~WtbA|l<{o%ai2cai_h6Av~yt?-{z$o}ADMD^CqL3CdXwgc4dPRyd z>9x@L7U=#nFA(5o5&j5oJj+77K5*k>AK-RPuCKnJmww;-BE6~7!%9JpHajXe_$S}d z!DDdu=S^6QXaycHi{RWp8lax+z~DY>zezs^#QID65KgV0<~72WFG2!nuk*scMt3z^ zn0?Zb>N%1xvfRV|x1w2*9^Id}q3?Z&zq{~kXy=RN$jO@xhMthgjYstK)k%xkA)=7) z5>Bu4u62-!w`=7^r<%(9#{E(niV4Tt%8rylyN66g7Du}=ixG%s~ejgDrAKB#W@$> zsSsdmDzqE0P~gKk#t;J+=p8)XW>XDFn05yjhddfIl%vr(A2Fp#jWI??A1B&JtaVY%sbo(;;{3+Kc&z11z<; z2^drQtEBo=e|6eI&@wYp&VdEI>HGkD^!Kb=HUf9u#NpLgnh!#c8+*`8WLt1lSrYrh z0uHnpuKmLWsqjz55Q6})IUG~9NQ4SnDl@p!0<-Q#ummKG}YHQKC2 zLG)fZTLA<3YPK~0#{)`BM@(;D+Dl63*1uY2D;1q{nh+u{x$A(2kS*w@oj@hJ(|+lLic zFCa}$?lc`MnlU)>gZaS!#7ZHE=fO1k@fX`hskgiaf9qE}N2!W&z%{1rnnfB+Z2gmN zgzX|1q33UL&Hn*Z79|G!l+@Ru#ot^p5>i`TlA3y6L5!t~=WI86Joi!letZofxI0d$ zWhs9nufI|py)UyYd941SE`2FLr&Zqbpp}xT9e7vOwFJpunP27k~A&f)HpPs8Uc)OLSbwBkL=BabtG9<8m&Z1$Vs!`N`eU+z~ z75oZP8(T#nClt)u4_8sMPul#~J`w;d49tJ?TpL}Nn`QX-uP`5%mb?!mMmDHcl6I{X zmLqt@p=L^Zk~D>p)3?3yjqZmuCAHZgx^{$btlq$Uf(v+j<;kUxyUw{dVEjm^%Sy(H z70P78nXb)Me2_0x-bffOPNdE z(8yO7Zh$I$vX_*CL8l()IS~VvfunL9Zj?B;wdKJ57@#Jn3^U(Dg98#c@M1OqLS0-H z(?pcx6#;1!cwz{(Pl(nAoz5@5#^Ng_t;9C>npRt9?a#*}_$7+e^q%CHEJ@m0*RC{gAW@ zZ=XV{hdrTzy^uMf4HrB?WGMYK6p2HC0i`js3;`a3(h|4sq>~f^sTvhTsYRnzO-UpS zdC5fVLEoj&_Tk@mst1fSZH+XGSWI9q?A}&YjmLRC>boo&*G$j*h$Tw&ER6xPoTy9V z@Zr_SY0IakLSO*!2xuS;t%pTbx_54a&)U&6nQx+ccA=dP*vl*g+_z0OxtoVk?bGzV zjFCkFXc!@IHK6U~gh6`vhquzlwJ7`PFA;DkvuZP`8u+eHr_zI3g$#Lb8MV~|$lyP9X6pXd@R{aduB)+;o|0Mpi@Ab1VJxWmCz zItUTu4PT6>=e9^eQl9Uyd@Y+3Ff-R)WTYiS<2*FTRzs1M?9-BC!pBLv%j_u7-_qPw z-8$847FQR2(Ov${&(*l-K)KB#ZF6RW;6Q>m|hvMHIZ3h0})V%hw(oHWF2 z(;fMhgi7iU3k5k|xxf)-6Acv>@Vnw(F_Ca)dy~tX?Re>g;Rk*<`>IXd;xa(97Q;Y0 zCCESvBv&IZ;D&;=Kp#9jccIc1qCF}4fNKFBP9z3$PiJLDG*BVqqP~(eu6%$oTK)ag zs%!h{7XF<=&#GvtSgU9^%x;Y7m0So`01J>ZK{@$WwtwmnX9O}mQ+a!@o0;j0Eew6> zIH@9Tc>fb(@3H?AV)1ZsH(i@2EyZnsUGDGN);4@i`41Mq!1YqT zOvC77NBEbwPd)nbV|9)#=>k1I(R1QSqb)J6hGvlb9+ie_6Vn32Vu3S04A_CFwX6b- zurqf)YI%)jm5L(De$;S4PJn$If(G*B*fb@*f zKf~FU3qhB_C5BVYIDa>-lXGVRg4k%Oe1pyUOXT>xP|A&y`vnRb+*#MOvTLf&7jcZQ zhqEpErc#bkwgGq80ko~0^oL(;YCzY2 zS%(d0#kcs_pVK{x#mc<=e%)I99!@KPvbN$K`9nn4E_15Zj0h(~tbvEcf?kyOOEwMO zZSoG5ho=VcM$^Mx8h+vY70b6*Y<{2FI~S42D_$oO*tAI5On~98j*pi82H{sM`H)}2|rYq*9|Y~Qz@hi2_ie? zET}#S1$Yw0a(r#Re-w+$h*T<1l`#Y{o$DVp%AS_n_D0euW-4u`| zyWDQt$Fkh-h&C8AUaf=%_`pYJAPc41$M{`z(syHelI$Y2Zsf)nZBDq+6a1M39}Pdl z#uo)Xa67cWA#w9E*)*%~y|%5Vo$3E!>MNk4Y@=?6?v`#)x)D%P5Rj7YZlpu$?x9Ph zQ>444LqNJq8U&<6kcRur_uqfr`!02{U@^`-abll+&W?Cj8amh=VL70&_RX?p$d>%- zWc;z&h~P;;ln?%jZKzNFAkw+HaBGH}jpHRMmMFitYISgF-Dk7&HfGX)j6af=-U0G% z-;x1I0DRXuy&Df{%ga-PKz+DWu!?yqE&lPIu4c>~3u>V$oaAxVI+OSpkuoM$X;+nL zj0IBbi&5uHP-!Sa)A+c!Z#W$A5|M^l;_p#{sqh^C@YiI-t5^I!ojI==nR^G@n9UQw zr$kMt7#UFj{YHt2_?ezNX^9O+s;ZlxzU#j&e|u>Q+lUSrq3y?f=)nx=DS&?Sj6isN z92`UEyo5H>v1-Nv{;`MJU8NMzl5nCdUGmE6(CUUeS>sC90epPW^Jh}Ka5|GNK{66t zmK1_q5>Hw-&|T`5GIuqDWaczm|EbXT`Hv+EtbcCrID1jdCH>qeKHhuJX=U>Ai>pI# zYAn9KsN(vn%EHAx`WWE9N&X5=8VyB;N)?|CIeVD<^M}6^iW?>Vo}eK>>(QGL-3Gxb zcV@%pYo(zX%`7Zm)V7`hCtgeasSi$?5v#vukI z<12mHvE3DufI8v{es{8Og=_MuM_F6pCNELxj`o%+P@empg|=?kVJ8d%QOV>zG-rtl z_4O0tosAI{G!IuZw0|1)Xogx4N81ZvMV*5z7Cp6Ax-~ zFHOkLIWW*Y3&_B-B-TG{ZkocpbxsrJY*k?)Lw&uB0JN~A1g)Z?LeYqR-X84lW29xt zWi)SCpTt*}6UMnvf~2z>c3xbUUjeNkM5;1)4Of#Vj=eVQ+=Y=6+Y34@#2;M4wqBK| zCIs@ik9Jf3{Rs12IyGJ+V-ej37$0kn@{q3guj;sXz5kHbIc6tCuoe|^pU~5;N)rYQ zD*O2U+waU2Lhlr!*E_wd0`_a0Ad&PR^qQ49%-w_Ka4$|f#C;odkIry_{kj8ekIiWl zb|bSdIunil{`@-IgbEDiOrQtrzp(jOTlvC>B@`hwBFn@^y{4wTJzprQzD8UK<2@n?E5m6|H4sR^XZ;%8 zt?HbeGwY`>!{$E3N*IdRaRA)lUo`cct78_kmxwgR z%F>0@3MPD)4!0LD%GiW>zy(O4IupDhXIKU7Dp}Z?oJ#&{oq83AaR(9=sikMq5V? zh|m5G=2l3T#7q78BKBP@!(xJ1LLXE=rir7ad{XB&Yz1R1asJ7)8KWdg+)SmOA<=I^ zAiBun6T2K^!IP%FzVU@td{7G8KRtjcH+j&s3pii_NOSYccOAe{ z3%b7 zLwHk(ATAzmOm5mv&Fz>$QtiB}%$kU1b5(R;rMEw2X(_z#3swwjc*wsXgZ18O+j}xq zo`gt$dt>(jx2L`bUZ>o8R_^|0Sp~+%YGU3@$JM4la^Gnq$6e!5X^_2R~j?9sg!h98?NA|mF=?E%;p8cFY_+TB6_|-`o4Wm*rkn)gqRV}@ZR<1x# ziI)8_JB_00c(b9*?(osMR@nV{sIBvOzKNpImi%n0$ouY^w1sFchV%4UwfVLXcF=c) zO8a)2sgKgaPMGU#&~?G-N#A@RjBB6Jq}yi8c~t1;C#Spq@1TYh4)SoFMQ-Rv9&tii zNw0QGFU4bd(N$0QIDah~FOjB^QPT->*tW)ZN&eS?1{-RkTS0^z+;}m2Undf z9lnd>?z+$#*0O6;y(7jk)LVV6EZo%iLD{v~I0hd^QErb4`#u|{+HGQPnz}A3%g)M= zsB_VkiJ03wLG$tx8B%BGyj|#M|J@A4`JAtfKLg!?ds%DqR`NKfaPQGr3ri+sgE4vO&lxrP5-s# zQnDG7PBDVU(dw~8*IrdUIsWrFNOcSgWO%67SvJ2+<)+o~BsH|{GnCe7es0ST;<2|N zNy5%w&ROn$;0w?$1)_{%h?7kG!@yxjBG6#^1mFKH1i@Gh?$yt3!LS!0k%mnoAHxT* zZpf%_nA$)?5g6?=7*B0bi!X4kgk&tMrG$#+RPOgN>vD?d-eQpn@KA#XZ=oKJ_OEv) zPfv2b#Qs1cP!*n|qJ3oJm5!?|bm%@gaWy+P*)$NNw(Za95M{evT$-Jpc6z)v=g;~N zVL*HHAMEr6h?tb?)MX;;%vb0!%0fIIZZ8#6#=(?p-3lKoc>Vehc(9Qm;loXKi||Q< zh%sUIG$Y1b#$YJ6qEVg4nQ5Ut*h5m?=K!N9SPzJEOphg9oZOuMw(j(oR0oFKEXij8 zq>>O!alr3w(B|hr!|T5A#NFiVX9zdzokUhSXx;?9GJV7S^sglbKmaT^K;C*fr!-Kr zd@B4q_&H6=OJpkt%QvT|GjAjmtO>aR%`Og+ER%sKF^$$oW7PCIxFvFQA~D zfbJp0%m3Qv=lpfoyA3|I51R}+_}=Wyy~9qM@KNEFd+O-cC-W2BDY$emG~tY+Vg}6C zsKjl|xpv}6yd+5J*rR5{1OzDmYI_5GW&^-hRJL)r{wb8?bSx0NT=Xu{Za};2NopG$4uxql{Ap z67upe-OEFB(ngHC4##SVGQmOp%>Rk|4_?BQ)eWKc?LPm#yZZ|ky<5L4&`1pHWC2Yp zn_#tJNQ)S?V?Xew#*MYqo_D|;B8U3l0lGCwh;`rSrTa#Rd7JOiXE=mXfG777s;Pzh zoXm_A!*!cT=)dTrF=37IA&&0L8)oQL$d6aPzO3U}sf5b3X8Z3~)wA|}H-J70w@NWQ zpnd8lBYe(LyjusNn#~4QhUWX*5UwjmgBT19eDz5#{h}~Udf|(7%CdK$CwRreWsUL~ zMfJ|{YlLGJ>)Fk4%pV~Oox6R`6b_kvegQ?SS7!yOANr}8Uaj{;s9!3?dL-}#^mXKT zphU^0>eG5684K>otRdgD*$O;ZTMFHsqmuGV+hrL~>;}CFxx;@RC6y)at@mWw zJU~Zu5)GcjkBoFu=KY8EXOMqrNDY+5Hm<@{9!x4;Sp2JEI89@tmi&1ruw+jrH@}Qo z0$Oh1bJho(D;WDLC3QT0d^`e1^*a5Tpe?HU{wF^wwQ(?A?px3K_Hb6mPLh%+7;I3K zg=+No^NDNg zPII&Bv)|f*Ix;B*R5YCKtd1FbM;t$;{ZHrFQX*R!udEg?7`u=FqK$ZZ*0b91Rl1}L zMsXb+oyM#D2ujv3l2&k@has0B8pwwnyhO!Ux%>x)M7-8#xI*s|6XEio*xfu1Auht0 zE{&%o-*mdM|69w=Veu!jy>cjelAd1B;}7xB-PhA}5X~8@wloL+k|YC26_<|i1%l?+ z#Oqv{0euN*$V=>F`KU9%LT?q0MzI1>UQc|yQwd$h!bq^aM1^Atl|oHu01}Q0Iii%E_vcZ)^KJir z*?Is);uo>SL6K(Hj{#)*yb&0odnZ5=suD8)D+=&QaHl0 zSlwiJV4vkkG{0l2GII$rB7>bX17;TFPI(1+7$6V?O%;Kj#T>Zf-#kqp0iyEd->OvDKzrdN9k>wt@v> zmIShIA8*q^qwm7`y3akVmH%Ti(dCh}wkK%lr|0GsBIB*i$D=Bj_9-Sxa8SU_S7mX! zyQcv8Djt}8QVq~E&~#N_Y|KVQ7}xe0wdP3}zpJ1a{|DUjoIs5rSr<{EprL zP|TBl5k{-{hHs5~@EA$b%3LaV>s2>lz;H(EiXSy3lTVNebo{zD>yLS!?&+w=#E?;B z5|Tr*lL@w7qE@N0oOZ`dpI$e;tF|$^T;E0?tAH%mwn?V2xDQ@~qt#0EdwneQ`|2^W z^P5kQ)b|3=aL-csQxNjV&Qll9zYW11kLPLr{;e5LEoU{LtfId1 zm1J=H)M0ppgmxY)s|56L#i9j&uQTFygry0oxgMz z0>)Lq6nm1BligA>MlJsv`3!`3Q|qq|>&AObohjJl<>hU9@BDtMLz!If#r#1V1xo7O7>v)@v-u3drfQe{H zF?Px5XQ~&{fNZV*kb&1HE-?BD73;xI@LT6pr9OPq!y0!fgbl|l23?MmiftK7QSjr| zp#tb(0{kJ0izHro1f^G|SMza;7}7uBaEV@_&zDTn z8|SxyaXW_JeS)SBT)u}PfoV9x9{*5VhiB+mN<(cluK#}j8s=j_p)m02f4Kl4k{|}C z({N#dskb%3KdlCO^)d;!XewAahFy?kx3k0d=h`g66rIxm{5*WQ%L7~6_Rj0H=97^P z*m;sToXkwwaD7FZ&d3582tlNM-E&jmVmgTj3n-M-9UlIqp!;0NBUzeDZJmJVHY{s* zBBY|0!6b?2`+l3VY_peFOMyKu{vVFic-Ro9hpIc;bCVo68 zlTuN8`Ne3aI3l7ZL|geV2#H)Sd36}>UHC!!(a{NxaDo1!wNRb=_->A*!%mj_)j!L% zG|!wXy-2H$o9`2r$72DF13 z_zE#5QB78FZj3iYaK>oV=*(%f{x}99$hxOFX~D)#B($jTZ@a|q4tAH$ItgF2lt7jr znQfi#u68SmP(NzFEW1w6!HqsSrVM_aROjsA@KV|`Wb3>;!eeI&UiL`D$&VkNjbYhK zlgxoC`PZK3gag0n@n?$Yz3H2e2d%wJ?$f8t;jHrwcMo5kAfoq*sPb8l7=@6u~Z7TY=5kQ`@Epi~(MppF|E zhO{zXh)aJa&`iR6>Tsh8D++gQIf4?~3evnXwaKG@eMRk5uX`sY?p^DK&0pD*e4t^YY2v&s1Cag2rc+0TItLTmXr$Ij2n zwc@y5=1w16{Md->1%0GbUFH1Pj;V4yJQc`x;S#yd13fHQjC_6xl&(y-L12Tn7~miA#K>Sl17pzTBch=zqVY7`w_MVQUG{ z@hu15BN88zWYDslGWTa$S*;HkSZJ$F-E7KOehug}(g~@~Ie9y_v5QPH? zf8F9Ao3BB0pP9*2AoZ%+Y1-r&wa{bQC++vC@dTlZTRaK4WD|QG+n1w>u{Sq|Do~ug zHiH_|;3JQRmhNlg6*!;PBa*qpvXB)!N!<{H-Q7N8Q-}KE8v5PaoFNlF+ZCk!u)_xP zPp`0xDj%B5p3UEThn5a7DPZ=GepS^FL55t6lrhpxVMGl!?WRWF5-tB76Kr!^p+T0> zIPLz0(CptWEwwZf>1O)I1@*Qc(L`NZGG$&&vOxH?#&pJted^_ou8-TiO!i0D_3<40 z?y;{8kqyK|KX?BVAeIAajL`cYkYb-s$#VjgoPue4*g*3ieSIbqx#IatMvZo)mEc@* zG|4I`{4j7|dC_9e{+a??`2MsPCebFiVhJ)fn2xKV|AQ+D=BDQ8r`DC`opjr3%h7a> zChy+~@7A4ONjAKflpMlGgi}%&?_F`M>fNk(C$!A)aw4dkIq%x-t_GV?9Qjdy)=b~+ zb9o1*40iXy@ITOE)Nj#?p>+{HJQiUiSzrW5C zIZS0ym95L6y&!+_y!qm4X#C;;EzQH!i)!w(dVX^~5jO|<6n&-)rqD;zf7GmT_6^J`-({-@%08r ztm)1azi`(4hn@gd-^VET^&3aGZr@*MJ~B2;ROyMq<$rPso;0VK{Agcj1?Z@1I65-0 zlf9IKv>sY63vpvyDUL|!*b^uqBLp2XRQWjueyJ=YbN?O68u<+Csgai?Rtu-4n#<5l zFH^v$^iA3I8t=`QcRL@ZsQdFTq8N$n`~Di8s9ur~6ZUU(4=!@u!nqhkd{0+V;@to7fGeO>YqY}tdh~wmgj66F*Q8=LdrMI3i_sC5U1=B}1mM+VJGcnxnp&i9+wvH5k)*->DzhsP*pO-06i=Tj#&rV&8jO z)NY&4MJ~TQ95qgW6TEE3#c{RU=zm)p=Ks!0dVNQwgyaiV#JCHwRkGPU9cF-p#cnse4|rl9K4&Dz3HN@^I^^b(8?ybQV3#wwL*pNXj0zOE(9DJ zR@SmM+3i79?}y)^!gvXWs6heDH#Mn= z)EIFC2ywe3L(d~j;F@jqk&nqz^5m#{C^eUPX$kyq?QENth+ZIXt>}euW4@F06L)|# zH;e`s&hbl8C8`c&-?-e7YWxuVxE6%v;oy8_V)EkjF4l{ePxLDD>bSikyo|6)f03ah zH-En%gcdU>w{<-pKQFctKG>!4h4U?A=z1UP9es~=A68Z6OpDO-#7Ua<$G^Av{!?cx zZ#yV@4U}=C7z=mZ@2+${lLRRVQ2c9IsjJKX?e^XoobvvQh##q<2?h>YOHAw#pRJ$j z!dI7yDtE8jwKK^U!x!S}&Ov=o3xr zg4Vo=lHhQZ1~tk>z)7Gpg*l@UdCvBb*)lD&gSjz;w^VT`uuTJpLRniIYSJ4<`{D%> zb~pksEDP=40)E#UDCK%hV`XNR78V=8=BV$#_&~?Wi32o!*c{r<`Z=1GI{n2g$1)=p z>#WR1Qn`PQkH7QqcqL4QBPTEapH37|o0^?nH8>QzJFNRNUzLN;83?q9X;6bK2{s%^ z(jvj9Z7t_Wq$CLOHxi1+IfnjpMAZJhX6b1)E2=NZl@LfySl_Z#?c)Bu*cV&VwF8={ z$|jAlV;DbtBDCKybNvSvQyW$+8GZA}@bY0?L>MFvm$C@v%f7oWotS(=$V*eXsTfd-2ZgN!2UeNOyGNzGG)zq zwz8NJCX`70x79`E*cJ_=GT1mjx_;y8i@emS3q`tY^uWivWYd}arC%lUeeTcuRl^1x ze-D59bUlBx4+4$#CfnKQ<;!Y;-n&%;1k-=HUcJCX%X2ILrIxo)qt=6PcJT3*X^skS zkg>_dPA!Umc6IN%;g7BS)#h2~(lhIEyJx3=kiG*qrC#vgF%gV~Gp0Ld1*ag2h`r}$ z0=eSIc+qv@YbUxeX)STShc;F{Ny&Lh%VTQ{9N?2%eq~00JS~_Y3SOMS>!x6D* z)7*IAh+N=S0$6JBjsQ<(-0~%=$L$n+^f5u;F44)4O0&-Lf8_Ya{SCdUTpuNQg6zr_ z#3dhlO?kRZU*;~d`|{nQh%ST(d`VvCoc^mEk6Uhh@h!wfZ>=I)JnkjG zjRM{m{C|fPhPXO66Xaf)R5CX*B#1{WC|<%;BTv?1hI%c;de|CY8%7bz1_SC*J+GLs zf|}72h{RCc_jF85QK_guLmT;V){+UNsl)m+T6Gt4srN;rNojQKsnNO?b&C7B-jUx-JEMvU3~u`-yy-|IuV?*JEj5 zv9CBhW!xMPp1ie@qrYQdKrnxurL(2O)jr|Dd@1aO%)AkXY$fejB<68`| z&33(TTFz`*<8PnmUByWIQu2fCJg$Q%GLr}@T(zJtze!v0iy$js%Eid-dX+=izA34S zX2`W&v=nMCU+$2BH~xqDX?5mT*l2jEMMD-LC1M>^nG=I?XqqaQp9E17c~Njhv8>uy z$plvzT8m&ahDVWx7rSfutebG+jLxFtmQrzq5C~Rg5QcgRVD~$&>ck-=V_Dt%7`vcS zrKLw*$3wog6r4TE{*MHV*e^SWrJCP_-YU}DVv|=Tx`1_Bmc074x zGtfDvMI%3Zj%cRi{9P$dkJY3mFWb)3ne^Dt+aP>CrQ;mL$IZ^_EaePiFKG6y$#mef z2{?V5>s0ICe-uq4(;lr?!_j+8O6r=gY`ePcLrL` zH6X~b;cuUOkKPEkdN5``dF_&Jl>ndHDI|cQc5Y@tIgo-l2VoGS2V;M*2R1$x61HxK z&$p1Je2^N7?^!_Trjan~r|IIC zqp?bo`=*eEtI~bF(+lDyLfdf~2(!sK=$QqN%I>S-c<8;Rj0`Ffhdxxx$d?dkGjhgK zC5v%$@bKU(37;WWcHG(^c@-O_=)0hWVUdUF)LCwTLFgIfxdcxxZ87kpGo@*;_HQW4kT^;%Qw`|nq0hvhQD&d#C|2<(RTCsDXpYAMfXbWFRZ zP54Yy4KW$E`c#?mzV{WV)g%doN0JtAF(Tt;Jy$dp?cyUvUVOWVaW-`?x$4w9R|3{r zeUQQ`~%o+UA_?JAtRio6%bn8>h#f?}A$u5JL)tOBrr9CKA z&}o!!-WVo^2viWxfFg$p5WdS_`Z+e%Z{M^M281_=;Naj`E>!(Dx3;+bAANwbBAJrd z!^>6QD+7?4L2Y^+nqXpzsUqI|=olCp`^>Pjl<)+L4SbVsHv_K(Sf*A>MYb^^QPl_9 z?8m81$Qd{qIoC~vbC#dy`R?keZ_v6uPVYPZ@$kJe}%3AHi#@=E9C)cPL*oLMj>!xsXBOV1o8uA2O*N z73;Kfyk>*=r+$ucrn{TT_|1seYmVEN9WBZxa`^cPyE^rB;xh$Eu#m)#D!RV(&O)(k z^OQal1glDz@I=ac-0>t4Zq;sZPM^mUZ7A2TEEo&HUK{ESe zZlN-&VQ&R}NF@tC*7aM^u?nJIaV`YZP9NWdBc`6UeynqHenKR{gg0!i6|*7JtN#0e z-6lh~=EJnfWK`u5M@6swlR?Z{=JdPsAO(@`()R5I&w9-R2O21dq6~&((FC_|%C*ZO zhvb)|6&^kt{B13t;tqF7i!xSoLW9A9fzJE@8sC?wfq{X|KoZgUprXkXXc+)X8?9!Q zVa)ps{*A6cgyNDCabI5%czF2rPl9;V)N!C<_>7Qn1Dq@=Y3Z=>+jO8pRfbY6B_##R z)z0Gl?-8PiIs2Q|{GwvW1z@jOTwMGHR16_qd!Oh)XJ1-c+RwqkZa{hDc01HwIC6_I zg8T1?b?EawM+28-S=2G+u#uno^J8v(Q;DMkEM=N%(;X85R}ef{PTd=ebqg}_kysr{%&X_kYt)s^}2qpQ7@RT+=l+pN`DZu`O1lM>18 z*-j&s5D+SB9#(dJc{>Y5ucc$}39P%5_M~Juseqx|0Qi1v^ss7L>Tj`2<>spC&3O@m zOhfw;qDISkQTk)ITQ6svs*gq6;Ph(xAU8>(6$EFfMVBc#-$J@!ap%#>KFU{~-qtnf z%M=2}%KV$Xd#m4bt)WcHc*Ev1TWE?tIbJ=lQlUPMrT}`k2s3+lWC2lI$RG_3{ZL>} z2yYp-puOcYhA;?3+EOyNu!fMjoX~ycb};Piwao$EvKTWtKt)s!U9Xcud03fQU%Z^i zcO`}vV=UIVAas>O${Pzc1vosdnfa-d{T{o&f1hl&GY;B3!UtP3$qA%5^Qjnlc?rPg z>ALrxfL&8ae~FgF@P4X=^*`s}cXHpReG!A!v#8|9T9$QdS?P9IQ6#!n=?UfzhgpU2 z-pfCSN9g*cO0Qm6H1cOMUHabb(aTPZu0t-Oe(=w^;eG9YSSgF*wa{Y(m|nr%nq(gnacnpr!8cU>&~As2~xBk(6q zu|#RbTWGDpa8KrjDeSbUf^sLn#RErZFb$H_bbbId^}2AT!M@0!91$qftQZ5xjrhQ z&KbbdWI2HY#103I6(3#lz529s8J!kKn~S-yPbyy1So<3y-=KVjw{VORY&&_reK7v# z1i^%EN+F;xgto+lB$154rnA}D8VQ?B@7L)%3V8zF97M^#acB`%6N+)Qv+S@ZKnQJb)9bSeEm}(inUZLb7QZi2W8{2z*3H8bO^OwC{FIH^b9Q<%)3Ze=^fk!t`r*4T_ipcdvMWq3 zZ_?_k`5`N0xKt4ig84WZIHxwR{h1)`HqP2~RV#fr-b%{sXb|i!heoUUH3Ih5%uHsB zZ{pi!s|Ffc63rwP2LU*lCrU#BVI+Y#MJe_8_X&O%mHN6VmOx3-}|03VD}lOVgJ9>V`|ez!P7y3lkh zu#|&!%}Pq>EXCS0Gvwgij>1@XV%E1;y3^0SjBsorcStXSuoy&;16~~VB3(d#&cjzs z6%Ba_cZmQzd%jatJ{jrq;>Xt6dLE9z#_TumhT|bLsR&xsYNt}(gzT8a?_6K0h&~+- zmXhn8R=sE?wCCl12~jfA4FFMlWTQOnc2I6DkFHVL@WB^ z4#}0mGFJ%-x5Uzx!RDbD>#{L8$A3ofOsyB;Z2h-g-|d@$ad-E)@gJAHYSmswNR1Sw z(&fXkz!STe2Kx{NT=bc+F(82YT$w+OSkdgBhJ(e}xK*4)Iq~css5@nMwxLp&i$EDW z7s7nEu^9b!>eEikCas&D&28dviZ5OQ_-nPz8r2U-h5G%{qqQ+=kM1q8m1Fy7rMjN| zb*g|3+H=o|ccYstwMwUq!a`nsqs)hnA4IsHAllw;lT+E#N%R#CCv*J3imp8hqj6X_ zHDUb6Y=evY>(7Pib;z$1(fu&mi9tJkkPgj2!IF{@^6sKi^C2AOY+2+UXbT7Pdy8}+Q ziwr)fN16W3W04fJmqEjkG;EW1`M}Q71;ZwhMu$!1=Q2TjP2!B>ic=9m& z)AQH04XG6vIiL~d^+8=1xvqlrHR2}K{^Y?sf!|k$G;^tVr9SVmmI|3>@${b}{wm&8 z|9E!27KvYVHR&}Xo%Pp4IQ8z#5?~Bei}u@nt4PI#xDGoWQhe5INnu`jnr!O?Z6i5XU2k{^XI^;Ti7P?L&;#lBW@U2*Z=3>1-J{>nw~$Nvy^EP9XYBAEH~*7H7$87ZoT#2qmo;;9 zK}A|+FxFwf?X45qNPk8P2do9l=6*@R>+Tzmhf&krz~a*KaOmI$5sbu`^7m-O-9E6g$`Bz@M*F zPe4r6zY*Cj8yRk?N)K=H5;dPFx7p%TdcH5sL;T-|=`3LA9#3lFLxf1qFT&7!DXKE> z+xcGcVNzF#{hsv;f+&o{XqM^y4*!9JS5Fn`teTz};UZW;zt@){kz+9qr4Sd7W}r@3C#e$Fz>x;I(!9rFqQrlh;X1YB>P$G=-t zlXv{BOQ#dz8Swzf2CF>eUYWuos#~V57X(@6=70M?MZBLv|IfIUm>at=i7t6)Ym&dO zurJ4*Lj(Wijo8sZFty!OJvFRgt~mZKdbrYB40@kH78$ewF_++WWfm3^*%G5~e>4EuLA4*to%MSuEY z6_JCLCu|)iw6CKl;_RK*MVe{(d+`kkidk#Df+gESp()IB=@B{uxD@3K2$(FILv?8} zKcihthx2Tzu9!Cw`>Es=aNFo>ILN6wXo#cuDf>Yh3KA|5^}Q-nLbSw`yJ%^7C0iz4 z5)v&l5b@+c7~s*?@d>Aqde1Na=px@kQt;t#oBTfR9ok$sSEit{;e7NvvBi8DJv9td zXNOJ_sb5nFUloaaX!EmKC+MDDN9kTU{$MJz?*VQR2I&8?c-#4k*fiMRlYes4p*M16 zTU%2<3}AZTE+&u@hoCJ^UVnHH7ryCp!}2~6L1C50zu|j5-ne2%7=IQSmq|s0fWA}P{_|VT7rx2TL)>@H{s4wMMMceH5gX*EaREH=#vv19k^>nT@NHy>H`cBkDEm)2 z6EJN?t}Z=dwe+^lH;B4obuhY$^ z#988Uga@7Ms}X>9_5--4Tl0~(D|&TR5^m%tt2~$>GDg3U7Eu+ga;aK^LVuuNoC~(I z>S{nlwHE^bo(X-cVTJ6Wwoq?dH8y^`<$$<&Q%g%2n^o7ExKO&XDuq}bvXkpVHA6GU_15%ka@B%Kn!8@gQmFmVrP!3JrG7-Rtij# z_-B#j9~c{{Dpl%Nk}L*VjL&L^LT4hUZP3uFKdc~iKKsD8;mC{b{P&>Dsi38#*Iohe z08(d&Lj`e89u#C6$_{|-dmx_V?$9o23$93XEfYanPIm%NcO z;7#m-k0&^g2&ua=oKF(`_jz`!a9+~{I4@MR-&ZYjJ5|3pZJ&ht3lBu^F=X_Xql`Qy zf7>b|9d9=ke|jopwYR6bw|s2D?(Outn9_JSt2%Kv>&tf0IpTsS{9gO52|=FN6XD0N zDy-3PBS)ikL-LY<879>;mNXb_1RfcSV71=r4|7cS8xJws)jI))|5lB>ao3KR`cRs% zPLf%vPgtu`o)u~a_u9<0U`YDCuP~O*7(n>S;JS7nMFwZAgi{P*yEI#T{3SqL-VdlO z7dAOY?PmlaV~EG6VmiuQ;mY{@Bm~83-0Bp->=#&y+YHaLSa54b-oVC4>_u?yTQA@Z zQgGq@DW?T#OvUs#PxR40UB>yK!CWKyoNwm9-u25<=t>XzXH~-Ih+BVkzMd@7vXCes;49z1wKhWX|@cEWQD*U{R4T6C{AFjR>eCYK~$NzVL5LP^Ej zsvSh10*z#F*R7NTr@dpm#3s{afDhu~Z81L!ZSM|sf!=4}69ycl{|?s#Q0*E*@_BX{ zIU)_q&qC$6|CSgX&~E-)Y$()+X2PcDbC9+ad=~`fvveFQ`T*-lMVRF4yNcsRf~t=I z42tpoi-E!lAsEaDvjUFZ7C*j;L7R7={0!kA#DolE;c_l}$jsbT?-}#)Q4>?$K$DOL)4i^hz!U)$zr=`@3V}bj$)gT-< zB!=BfOOTTRR%D!*(dTdx3)f;tH+uRZxUz^7TSr<8lfe5BV?r+pu!xH6(SMKNN(Ped z@C=*JxUy4M=U9(PFU{o;8GXcuUTazP8q@6~A&Pf({Z{sAKFN>Lv=2nd=%heXj{U2RmC{$;Y2u^}N^ zMBjOToqsaAe=4k}RfP0j|&=mWA^4tQC<2wc?9-gf8u#WY$-4<=V3`rBhn~!BD zj)IjdMLBm0E2PP!aG(HMEVpWE`<0je**+egwNymkDZoOrgOjm9=zXH1vPRbm1EUE4 z{Fed^<~@wy{9g~2ZzvJ-rmxoYN$0^J`h}33^BC{iM$Xzv|IXXlQ;z^ZLIjB7%zLEu znbS8UuXGY*h#FXoYT>KhXFPIdPzj?>g4-UJdWrJIvc;&~2gg)BDV5`?BrIH>#_mc; zbkXY5omQaFv=z>&Q)2cA0)Y?diJ#$8xho-5_C6@2ZN4mjIeAwD&y^so$^s$B@-eSM zHsYv`$F;dy>4r)!Xc<-9L;blJqCYn?M$~rL(k{r~T zP!OVnJv5oTtA%}FYrMexD=_HFKl>oY=Z4*H#Yr*b#Wr(7jNKef!3_B!Yt;b8+Hp^M zqTHddZZIe`+)ATt+$J!Sr26c)(*gg>K)R)nk;67dx6Km|@cpTw(XZ3E#HIt(t7}lX zgl;Ay|0X~@IDDmhFl{F1y5{MdaQBza0h~Wsdl)V@i-~W4*kai{9l74 z2?Q4w&{!VVn@%dV`0l;8<0VJZGJ~V<#FCc7Xdr4Bo6imjRZa@#e2j2*zk5r?R96lm zRks}mw<*eGK@Hb7`+KSF6J71TrF~K^F&z8xcsF)XW~?M=m8in}df7y3?GMf19r?3I z%1}@W$;e^dmbuY0Mlz=J1X&t9wa1eI4QkiVXeUDNnW&pnRwodSo?uJ2hv7#});GIy zy*e>j)mI66C%PKll60(h#9lVATI;z8>UzVet9_|8GpsD)PNRW z35szN(NFcNa9v@j+%?p*T&?H=KIC@aHYlfu?ac8@w%U;-;{_frY+aGS4$HWZEum1h zt_1u@v%e~TA>qS$+jAl5d*A;;_i))oR4nuBlw!tWd-X!E6M#|-JdHc7x6h)S&Py#h zU0o~a3($pb4RYMqH-W(EBZJk}e%_!@4$R_z3IZGae;?|awB($6t)+qy1od`UA_A!D z8gU6^$MNl|XQN-IxL)xoW8V1Rs8H=drU83wG1~mAei16G^h~`Nh4ot7?bhC;b zCb-(YNQ()w@i#M-IqHrUM+5Oq#RnrnHAb_Igvm6#T8TEf$H*Sa0oLu1dtn_n{WYex z#!pqn`~XNxKEPGsd`4{d4&dwCuB)N#JoH&kzeZTDO5GF5vhPp-Z7lc|5Ow-lWoa!H zNh8XY-Yd*dzUW6~2StVAlSb;^lhvh(ZGJ~KR`Cx3NbXNRBZsD`)v; zWV6@+Xgv{NxZHShUwb^zR$Zxp&ZIaYd9ca{PQ|5XpZ%ZyTIq4q3ZWC@$aIwp%>QgL z+Q6`~lG==j`a6z#^iK&raF8Z^(xVWp7HzCga$&Br{ufls&SyL&eF?-t)*_$L8St zo~K^#&-eDbZa4WOw{x!RIUbMu<9@$Co>#`8V!Y)_JW%Uu^f$3)b~szIw?Y-WLRr%P-EKp91;Z7M1dHC96dxoDLBE6;}T#<)5)CJG(x;u+irV&i=m zOCL|AeV6wp<8r>uEd1f{~qWP_SZ*E%{J-PYF#?yRw6u7Du+fM2YT;BNHVv*7% zfjDzZ@@e4yuqORUDPS4|Lg^JKSM_`1cXJL%rB0aLhJt~K>8pW!y3N-aX_0Zob<&01 z#Ka7W3&*3ACFWXGm2N#52Dhbqo}EE&<7#CxubWr7z9S&%c4d`_j>1DK6R59cuK6D> zgEKxEVethpC~e&QNz@IDN$@PZ2FKh%>h-{cHF&RY3z>M=&iffE@x5a4-nZbe|pvTl||1UO!LDtQin0MOCRC=Yv=Hr@KE<1b(xc$?%Ita2nb(j8( zc4wTH!i7thmacq|l^=RgRnWHfnW$J=^A4sk?8wZCmPEQwb@ym><@5>^Hfv*Glw|%k z|5kG98;4J?4B6}67rtkG+BF4CNa_8@i@g*E=($T0f!-8MZya(RXqUc$rUG<99MFQT z-s^;1uJuq&)_-~$eFMDf?J`?^p~BixNXI=H@=L&ra0?Lc9`$L{4nNIv{(RLNE$?#| zUFI$G-yVYAfeV$N#LmYhsZMWmPK-O!2R42K^d+bK7ismB8~$1K(u9xypdirvkT=qt z4h)6!?V|zT0TYqtRI&N^s*{%o3lNJT2=G^(V%D0p%P?#x86e15z^-HLbrNDEo2o07 zm&`f(s*|Ac6nSe($XU?I$C2jN3HCe?&;4+sJJMS^u&O0r*5~P$t3i8&{ALPp#shwv zZklPWYCM_!eyrW9BS& z=tEzR`+Ra^udYd7fmCX%7xiybtiBraWn=KKsRnk=zr_l>zIkp0sAfSV-w#%)B>y+)6eo3@n5vtw^t4yvh@5q9 zUL?wk*ID7pt#dD8I-{xFvkh|{&!rW(*@ZY(`3U{%7=mwt?=y8Rrt&_GMd zhBf<0JZ)N-NS{>cCw*6aNeF84gW)}33Yxvaw5IuXFqF1*BZ{ZyW?Kvc;+s<-4Nz;! zEnoANI8y^^)PB0{md2WJM@JY3@FJAZC5IOVvu4*-T?KCv0TNg!{z))p_U8mW29jRi z5I|f~SDlASA`0C)t~{OWd35*vx~1xD8t7kevwWEp*eJxbHaSV|{}rh?w&A`7;v|2*73wVfsFUvrV=`z$iTLjPCQ`h-l?-X5L^@IP3q?xfw$3%8N35cjWe5`zMX5RhNBTYXf3&s z7#Zri8gvOXg1u~)-})#+49H(Zp-{>7)R3&7Vwrn=CQ{shBV+W@NcEj@@jYF9*-k`Ng^Q65s5yZ!VsMDAK*0fxbhK{e%>>*5v%y+3o-m57sb+3(vLUx=R0A`ZQ4&P3>9e-^dw81bjc?0_e_BXh8KjUK9;;i~J*EUE%=A1!2@MV21LryY8vPOwtTA#o`;@C=8Rd0X zpR_qZo(RajoKwsmJ=Yig6=sQv7DPx{m`uMtHVJZA?l;mA_BrB0o>viK$qdkC5EJ=T zQN6IE^jg7fCdVtUgZ56_=1{BNp*80 z7K6XHor0J85)QCpJ#)9d1WcQ3Shh`9j@ZE(?^IsY6+K20 zzE01c?{kO3g9ixbmvd3flGdAAZna0ztj7?5o;< z!8VY3YE9&m^mw>ALVx7alg<|wD>h7Vk68V96IXl z3n&&n8bs9e`)V6r>a_FMn51!WDPwnQF1Byu-}UP~aB*DtC`pxEj1pBUCtVs#GgVxt zcGeEngVB33P>m)^`&aA6H;Xt<&*E~blC*Y>lE@pU5Q6T>%fyw(9#Hr%a}dEm9|_l% z_3Lj2sViFyQAAHo85RTY)DW}1lnyu++?n5GcGo_sNsGG~-+=&8j7m=4F;Fk#G8il? ziIw#r0g7np7#~TSMUUI7Zz&lS%xG;3bMh7Tr9g^okC%(lS&29W`&v8k+T1*_YBUKF zicPUf&%9&f=}`O_q1y)70WOYr{XQIkIRH((asdy&fo?1&X=-G7;fN<_=nX(``82-V zY|-8#>^3%gjlSlv;*tSsKTrzs93~7S8TF6e4}XD^yHpU2y2}lI_YY9TuCcXS+ZO+q z=EuHOy7;-ET^94mf7?2E6jH8G7M64rd(f(1zFO(kRNQ*|_S93W5ESGTIAGPgYrkT2w^3yGbYKsBPk<#0>sby|ZJ)(^3|wJp&${oliCAhf1cK^{|HA8GVuj<^ zT~6)Tu>q_)*5L}Ii#se5u z!LU#ngvIFR{+6jR*TVKkgeN1P4z{jQVVZymbSa=QfASpA1|)rcb#hIS9lysmCYLvF zM3XAe!tY`S>CZP@-v6LbG{MVfrd~ipHfSiNTtCvEf9%1`$HedpxGCS}!eggO5O@Mr z)veYep79G4)~MKl424@4+1re;|$8pr~^UBT8C*yf$s6S2>a4D`u9 ztqXk$TRGKH(&0?#F*WCaCbP%i2D4Ya!6*bPS(vqHcHD=dAsSWOj%BbUVXng zWA`jk$CVOE#{m@4BmkF>m&uNKW!9r3Sd6r_UQN{^i6t-g8lDMMd%@K9zY8~5JfL$y zjJcbptdG-}Ebu;XnmGjM(*NIx7j}(7?zORXrQD@VQi~WJSvu#iKOj9{8 z3*i_~4(XkmD9H~|DHW%8619AxRrZ?{hLwH0lE0npL8!3(qpc9o(uKKPjhO_p5FiP# z2>p1{3jdq&^~=mmC)R0c`F7|OvU5uAi>LbedH$H~LWZP^1+Ag=7t!|S1VOY@VkCzB z472oX*oWR+brZV$-|Be6V=YAV!c`@TXBxCPU%!gW&5#sC$ZBQJ_dsqP;&btP-T7wO z#vaVY?(4SaSikmz2W)g$F*q1cH_y>Q!P9{pR6wY$wey(C3wWugg%9QuU~h;HYi(Q# z$wv-WZbMwcZyk0L7kPpn=h9$77Fbxt4Fl}#hPtr?I2I6SN%{#o9}rl6p#BSPL)7pc zVCe!pW0Dp*aiP-5gLvbI9d>`W9D=B2@re3*Y&BqfXZxSsxyh6@6Hd%?bGb74+b$W> zf}g&BXsx|0nRTrD(OdB%BUnU;Pm=5SlcWdtC@{uPvXs%AG=YV5M&C*sW%n=ak8~G+ zvwNee?%NK{6hZ-<8T#xc;p-54xz=AQA9*Mn-?He1(X zh=92D$mz)ECZN5QfAMjsJ6%4J$G5;g&B`I{>uV2}{UBM68JKNP%+39UI{+H#)bQ`&-`L?4F-t6wr7ntmQw~c@{T&UNBUTiFPhtU z{TK*qZw27?cM4~zu^K^Y25p#P&eH9c@3ucdAIIz4bAZ}Q8sZ`7f+ZqBcL`{Z_(=W? zL1<6*3~=Zjj`|}ta{wbQ99a2U9iYI$1*exGbRO=v>F&Q%9X*5UO#3elKeh?ZeP=nd zOQ|q?RsYkDJ{uf#;xs6=36Z!$R55@20@?(*rRHnP}ZO=6u#S9gF27&wqM#1=+ z*$Qx~F7xnwKV%jZ(Hp$2!^g*w6yRJE8pnpRwuo`(;sftv z;rmSFeI`aB0VwW_TZtilh)kKwa)b)D9!knP-^6cSaXxIv)2)R8+p(06evk}x7v`7iGL+wO$5Fm`umD>=XxqO)8Nn2&m2l?F_;6@H9(r2=D3s^hjf#P5@A5a+ z6y0)@o_LGMUFIBp!DA_O$_hC=I7oNprHH<@pRl);0f5+x#H;<>pkLz-)0!4$QM0jL z$Lzq2MQ6w!o>zoGww`4iq8EWZAIo=r32Z`=g6_7zS2W{;>z5=RNHPKetZhZz${o+;4hL!`Pog-FW~3}u-JEOb5JQ?fl?wa4(R^8@ThpmM-ff8U;U9V+CVw* z^{lZ!1R4g2Y9@S-3m)FZZu1j8XOZp5$7G7uaoX!nVu|MCEce=mg7gS2_qDsMz)3*pzXkywdX3y98!tel)fd`>9ryqR8 zS#VqIbm}*+Och)TYI5G|*Qn0SuR?ziD0aLhvER?Cd-|KAiAKLC#N9&kW!}j2M^!DT zR#+EGp#HcexlKk9ts|iw1E<3K*L%ZVB0+1Px@yBTg^~f zC;cC2eX?A{dT^`OAD&IUEOE|Y))2r8+DRWfA&{udq7uW_bdNsJT?GvJ8Mk6XDnHBj z&h{g*(2CCN=;EBB#O{}wNfpBOm&U^rr+?>x=0EcYe=8e5(X3j<<9Lf(OABSK`L zZ@{ancxv|WLtkoCj9i_oEW-slGfuP7^@qjXclf7Y8114dT?B9V^dSrNg#V_^H_OVq z&UPdU>(8gqtDAm;7v;zIUVuP=P!MwraUHMR3cma9L#s%G^W96bGT>~PL^AcCpi2SU z_zHIY;*o!_4{WGgVd|L`D0?I@<` zinsTaV&0}a`nu4(cj{T+19(DtU`|6mCD9<;_7rD-H5hxsXM6(~h+Z4N$EG*~Gn2?{ z!3Z{vDiRf9?YmH^AUlq}xvs$=kTy}n!6J9UKroe@LFDhI7rpe_;bg|nU0W( zVzq4!j2$?4jJyEdv*RMsm#tlO~&>ZvSDXvA; zR{)#*R8{XTQ<@NfQx*?g9}+)tw$%KB%Zr2f0YBYFN5k%fFWv zR!+*St!cc4J%Z@RD`ilv+!1HJ3`|$i48C^wrcoQv4yrGe=cSxpERJ6+|4T%J-U5vE_a^DZxFY&Ut~*Ikr! z>TYY)k(&JB2)+Gl?*4*R+{4eS5O`}wuUm4Z+Q4FJ#prfa^1vPOar-IX&Ak8&{;E-* z&!H6Bqqkz@A|QQxbYaO9t=!Zbom%FEYALx2$zU!8;Xn`+Y>+z~Zq1x!{4#C6*BE9a z1>0^td-p(PDYDJJ&y=xL66U{E7SyjLe^lMb@Kmu)v9z{0W@q~j`~+pcU_Nsi{^O#? zGgzo01G6QGI@!L+blXu}sD2^9WOiQZfl}!cXJ3kx-i=qBfq&{DvJbVEdxcRAW_;{> z&Ewm6z0Xqtx^r0kWW8N$(eV_tsQZ(ZkN2^a-`nkg9U0V{Udrim#_scmGQ&zzg6r21 z_tUAiFXoF;Bk<`PgEZ&OeQQ_yrpTRrXO!Ng6UbN*)IC}Jq0Rpl@a@a|qoe|7lMeD{ z$AcqRH%=jFzc1DjJZ{h(eTAM5JTe<%l$3-Z6$XWz?esslT#8t}g?C-8m_)XpEd~=I zA~GE@dyF`Pmk!p>r#HE7%e^PNL5*^Y@LIG%FPmQkG%oeQ4`2Ki*zQC3leW+dUAv#U z5f>PZ(?tnwQSYDRz41nFdL4Fjp`|VsHVc(guePjw#C+ZAJiZ)w;(OE2=cfMk${JkQSEcr&TvCE`6Ao4F-c<&T6;W<%_^{df;IG78S>^$%BgXE{XT-Nqvt7Vyj)?=bDc{G_PWo#H4P zyc)Gfxj4@0-X#24evl#tDaxNMCptvnQ*CD7f{mQApw@CrIRhU;%$cEZq-IX}!wqrg zX)2zRA3SXt0rSBxxp}kdR~b{jR(rR-PFlGP;gNKX3=<=zn~vjTHL`Qf1N*PhD?k;! zx51f{n5hHQ*(}=64-8NO-^JCVt%zxK0j8Ig=~?+;s5#tArE&Fp1YVsK1g-Xz5D|gr zgh&fh za;^#05ICEM2k^w)?Ks~vgS$J)@{841Xo%#L+h6V6S51I+Hi#VWoAXjI9)I9R*0#k; zMtM(MLHyi??^b@Vx4{b+V+hJ`;FH_npS~Ng9y=T9JmVK=J9=HvTlmJ>`yLcT;9Mk` z^m2khaqM=65douB$a$p@q(q+P}F5(aSZd*j?CU(*r?*FZVZpVs~v4O-}vvb?3vHH)oi$ zg$UOJM>6V{)4~$=mPLkqxgWuX9sG?`OAbf(jgl_b6Z*O*@nnB{e$<>_i<)Vw3!D*; z^!>6@zA^WEP(y+>J+L$MB@f>vYb^)fmydHr(TAmyZqqTx`zd`<(x;>A$XTZ`n$f9d zwx#eYWSlPXLY5;ZlE$WleeviHq)BFl8Q*55aK@ku7x3adX4 z8Kfx(?04Xj|H;g7+K%=!+8=kGHT@-+QFSurm5r-7cR5+%QjiA}ITC~$-&7B;R+%uo zh}EB_*gHM9^t_JX`9x)t@$E~?4ThP{cT}k6#O;tJuCb?q^(oEYY^yyWspm6Z;sLAP zDa;Ge-^;DDlhnu|Yi79A{7OmFdTZ@+D_)ty#c^gX-+t!?NNYk1HRjclk!jLTCIq1s zjbVnMjDUp)sNOJj&}OkGd_N5P<0SmSDMsG+@p` z%*Zjv!EQ+J+@gC{e$YTZ--~MZ86an6NT8Lb?}C#Rw^gBwX!Gjc4?nBM>*Py zh>+{0UKPX;6#5yD7d%7DM{#H5!0~sFqlAF8d@1q$&6z-6QuW;Jr6Yq`zfm{p=Xn0? z3;OS%ojD>aAN-&$qPu-(zKL;_Mm>+tW;it>z|LLj59D0$8}c=)mb|9w-g(3Cvegxp zO2VNsx}g4fr`YBjQ@N!4T`YTN4b)q(vS+$(6b_(!|V=h_U{Wr zb0O`)FXY~?Zw2ISTgKk~a1?MlL1`142F}5dku+?>?mdz^wXWq{F)90b3phj25kpdk zz{Qzd7T;xzk4pr8{m@ zKy7YaO4GUrH#~EPGMuhlnbX$0U%7>UoexQa-*ZjfbK$jG7f0PSnKX~!JUo}u9(A(i z>S;7GQj#oDBxNIg%=;D;1E+WH0jbhB%u#ofBZS5=u7fp zh^HH`IpO|4Q=>RZS3{4ROyUHNE{QucEJ5G?W<>#sf7^xB z{$&x(w(m(~cJSN;SUvrLUdmiaE6<61)Q-k+ytZ5Y7=o4~Po7b%m{$aSd!B{wa%bD} zS`%)I)wya;gHldppMrbxt#q8cs^*ee2ck9vULXU zq*;Y$&?feLNO{3lU;y1hNQauX= z#V0XHqi25{=UAqhv}KP~A_n(VU*16L37R=Yp5%LLfjHE6_fzPe2gKdyO`q6~D5;ek z7NufHc?W&e(4E%)%%$u9dYa=PHylmN5QGDS!r30=rgbCo9UFpQT}+6HN$PYD97?l2 z%V^%@st<4l@|eZ#*}5ySWvhJduT|Xe#zuO6dHJ&)+d{_k3yCO!S#hpU;t6OUD^SmY zEt6k;2|P*O2maCfA2ga)8;^&EVeNl}rx|NDCTJ0i{A}uGb+^p|PFQ^h%W zJ4-agFVo1nxr>=_TkyNHw?Ze_rHipo;vTDNDNIULc8^n7=ci4*dcbkza6WF!dSY*c zH?p}I_jZQi;c~(go&NV@)=KA}*ze#-%v7&lZTZ$g7kY}#qxMms&?^{c0lG5lj#Pt+ z=juZHB49{q;98l0Q6RUijYAh5SOZ#|WEh#yi1nu_^6?ck%K13J{HjHx_-f zO(QA5+Zo!QpG6OdL9m8T4@utp`jXNTaX$=}6tiu7ufyR>Si;L>}I>IOo> zy_2*OkU1j<%=i1CL8b5!k=jo~{tq<4F#`558X` ztwyTXAQA57<16E6lk4-vwQC(pl^2$KbulkxZS^NO^m5f`PpN4mOS9K`lPeRL`@8P;2~_dnx{bjyD8tL%Z1Z6VPD+D-a2oW5xkn(vM^9GmLc(-i z`&gOv6WIzJC{y`=BO>`+;Vpe+8tu0Cc=cGl&wOSsZnsv{RgBa~FPO!sz`63{p_JY* z%Zn!RFLsP)okz&&jI%>z=tHNODjw{Q)LyYT5|L3aG~uH{-6m%!<4{Wd9ayg!t3S!!I?EVHIhu3JE@vUa<8DcR1 zvu;A3K8Z)U!y(#Hv>+emF$0YVBq0g`2k~LdAbnp1s=600i7@5flq3O z$|fP8n5}-_7}nMx<*C+(Nxw@Gh>A~HNb*La+KGj&o7MZ%=Fx(JgPf2_?*Rz^YvgjJ zH918v2TkcPS>vV`d>6Y_Hf>*Lo5hHhrIUOrgfgU&=PROokfxc2CJ_Py|s7 z{KiX4PU-jvHG82ukAKF)zKAR3&SxjHuS)Kwl2{yvS0%e{oS|ybt$6+!d)R`?`5{zc zGD6x?Dr#fecu>dICcjK*zXfm^QaE5G&TIWW%sRbq{yQ9$gYLr&*e_lv4LHq55oR=T zOL-imeJbtmlFyBAVBR%OuV4p&h$xu?f^;eWVFlUEr5$$)(Wk2>3gDFeVryn~(~5f~ zwN|kF(UT3>R-`YZ7`Y1P2JTtQ4{cN-#zog0aWP|48fKHxC{bNx^l{bb%^K)KR)lJe zpApVgS_=DCUgj!vn{(KJ{2pibhb%i7-s&4K_xr7lV=>e-BV7|7!nOW~%RT@#o83j( zzV#lYTq(VXVo{k1zbu3#qdgi4PHeMJP}HJv0S{>sIhrRK;?J!CW}VGcmaxVCo^}7fE7J z-woOe{9RGY%?0I>y)(L&~EqG<8HxmSVW)p^%%uc5XOdoBlcB= z55}zU{e5k9{biw~cV~59x5_sXW3AHiad!GyzIs4<<@mheSS+_~DO{R_%_qhS4v=+C zSt^4w+48t?0s`dxfO%wsW7c42BhIn7x!21xK%~%(Jt~8s#bsMQaCa@2?Gkt1z0h-O zpLmmwtLY|<>AqS9fb;6;2?%J30TGCLzzyU_V%mF-Y?}4#Wzyy`o57~2Xy>WZFIgvi z;!rL_eSaaIOTclS{r|iGO2v3I)N8)~* zZJX3@-_tO39YV5-^&C5wN>shRfzxf47Sp_KCSb#r-eBd;ZkcG+I2~T*S)I!u?SFBl zIT4Jj=rH&fjBB2xy!k>8!ywM}Up5_6WyhO|PEn)h!+#zKYMZ?}r7eZmRF;t~pJy~k z4WrC!xzT3?C$M>1jHk`nxv*2jky$x2h_HT(j9nnrt7*NzUJziPY($AGv+CoxgX0m+ z;+C9`=OT@`t8_M~3;X$Xww@EaGTmcCV)c8YuoaVjy7$>H+L*pL@|YRVsqfdFea#4X z!|5U(ogH>nx2eYb#GH(nzL&Jd;;p@M$1*@XgxV1DHdGq_nYJI=l(Nnm?4H884h5Z3 z{kI*gHbYX|QeC4mgU-^Mti1isXnP}S{Jm^U{3r3=q^oa|)F=H>8J(pqJ*ntgK!QRv zyvF#eC!{X!S*i{PnSkKD0ty;$$uM5y?((UN|15IxBC!rsgQ!BrIzI06!|5pWQ3`A` z47=3NHb_Y_=C<{q2QNg=~Uxs^xOjk%viz zHQ5@-8`rybU@sc`{@#2~0V%k7i%TBKKla9!Q@?1lX?{x{wjz1QOmnEe=?jzAS@Ro+G__JR1Bvjunc??X%>*t}n=memS(uAh zNdvmIIVy0c#oceYmyoF8f|s3dtkHeO>!~FUcutqr980v6XHQIr0bs_=5qc+0G8C+0 z#Yrn)qWl4Q?0N-@JM8|4I|gr_S!RGGx!}(;Yu3P{`D%VNWE}0wqC$QSE%5@nUzHTp!<{%F!0zjtu%eagW|BZ*apKx0wtNX^Qjx5&7oNAXp4=oSL zJ~`sfoqP_yM=NEea^c9_!>Gt;3@yG43IY9exM=VAx5{nT!ZWkX%K&Cm_E_Zq>!{4~UYG->_=DZ{sZkF;Ud+4>^kew&8ay5yA!<8^;4&ucst{Eiek*5y6U zV`jRa_LR`f8wai&NXr}~Eu>>Jx%MtUa@N(P9{E|-u)g;is9zh?E*N*RUZ1@%jU!dyAt0Q~JxZtmCouz7H7xGrz{ zJCeTaua0-!cs(=yHq*{9q03Or;Gn+Si%kXcVm%P`(A0sB$Juyzp5Fv)X9NH-3-CsF z<3=>#58Kg)?H6zO!LsmvAUe`1U}m}tw=A}9JhBo8P?FZ!{6I_}fw#{EfH8(JFX?@jw_bxyTO%*Lt9@52XKx* zGHrnu=$%nLv+pcf1o0wPFeO67b-WQ^@~2BX&hnB%>!~XO$QrZy`v6SstiT1qA?n*K zlSsv0k&Wfx*o3~QTxSEiQZYBRN`8m6 zOHj+sKj?Y8CO5-N^=x-fn9PT+h3kpu({_+p`b>R~Gzo%o`8*-+3Z#>fQVcxg;_-l| zQb{?xbF}F=6qIc*NRM)(O}*YH-#!6_bFNsker98Ms&}v|0i+pp710}JUh9Gcv*)kE zhaXg7vb=+lik&|t%&{5J$RsGAYVg}(>kHiz;`m7j1w9q)Hn#`Cef-G}I0SWbE309* zp4ZUp4t0s6I2wP(K&fB!B`*_upT zJ2v|~#V2J|9Mhl=HZfhf!`vX3OR?ynTHtK-xtUe1)he_hdIPYUHA^2$#z9X=swcP zR*Tyq=|;&y4PkTR?OD0^zj)GF0QVW-!v6I&hC) zBZ5)XvIhc*qvf0LE)gYo*dRmunV-y2VIw?g^cnu^{0kb*E^>Y=C zB8pcN@#yF5*~Z|4I81^(@eHN^G9v!2($)!e0RoX9uJK9T0w|-%Zb0rhHwUN`xCz}9 z=Q;53@q~K6ne|c9-4dDw+Qu;wgKj!r>S;jcfXKVn7VA2ij+c)p+X5?fe&ps{vVY@r zC^jP2zld-EU4!v-V|GaxfnOCf{rg3y=URifkS$yfY2V5jUFl zi(*xZIUeMhx(?s_WRIM)+^TaLuaX}0N;rog-l>AI7uAU$)ZHvb382jMqTASz59P%_ zVsA2JEDc@KHT<4QXj87n<(zpUYMdZ_3J=_!qFU(o2;+~6m%osC8C}5D%lP~WD4Gv| zrsGv)HiUWPFsaWIs?P6!MRUN?K0O>w+GbNy$3OW2?-0eg9Rds7os1&JEIpkj11Q|_ zV~R&)jWJ$>5cq__o zt%wOM91nqeZ5je;wYW#Zng(Y*;9vtX`A(=t2Usc>2AtkZROI%DtW-|%fV>y^cNMjSfW`Hs011vP zjft_w)hv3#9`S1gN5mcy8MMU~8>rd9ef9_a-e-~fU?HMXcxLFZwE2)FYln*mRHCKA z1|q}hKG3S$h^tFP)?B5%w@$q#J|N_oe;8Ga7D(7LPdQPds>!y)-{)GFU*(0&Yq!$J znw$%MKfnjJ1F+uL4A12o;#X&`g5pUHys8B35cxE~0~BnZriWf}zc-rM?) zC|XDdTlJTdru`u*lIIEpJua180lz@>h@?vB2?GMF+*yrEsrXu%w8z#dHmQR!2+p9b z59gp8vR;EEOw|bIz%HVKpPlu5D)Dgd&;;Yf7dM#zs?FQ)JPU6~!&*O}vKR^%)@NsF z^k?eX+9!I(>g}GURs|?=rAS}YBIzUCkNBFzp=IMzbC1b%5t|02(xGmT_1n3Z$A!ZwFoc;WkH-Timq|~KM;*CRH8d@ICfm>i( zU&+WP80%1060C|BCE9u5s7Rzc7-;P!8t~xr*0ewRWIIkFVInCSEK8LzX{8T!Mlm zeC~HOh~l+Wr2YE>BRr#u3_$eCln{d%_*dOQnw+{rRyt3%W_m`th0P8X%_GH+BvQAG z*zs!4o7)T@mMg_beKg4_2;G|nk+aOF|2fMj04|=&4V9Z!Tz%6xULhmsH@|fvK<1MJ z%SF<+clLR#CIk)a{lY#16l9bS+T=oC9~7Coz`!yLIN2^$^$3_aJr8K$vgzq%jh8P% z4_5rn%_K9*ra%oY7e_Hl`Z_+q!-ZtXY=u|)acXbASz`r>d_Pw-=+aJMuMw3^iLus+ z2ao}!|HXgE?rW&gS|x*9g()+-?yp0LY__p@8#x#p(N*NH#B`&8w592LuRW4v13DSG;#r^VzKcv3^WeX z|9u&YqkbV5u+yXpKR+Aao|--?v*j6fMyZTs$d7CxtnTd%?zfJn)8v*`WlKZQ@Z+ZH z%`&cx8(9ZF;}a}zJsdB9Wb&g}_v!0}QJxt}4B950&J8g+Y)TCUMKk?fV~|X-0H;^E zse+8)Hcd&rhsG=-=PG^T$t^Y|`5NPyW7`8F@uM}8R6B=v7zon2w@Fz&YWh&vhHy?y z5K8AC;c#z!#QdzNQvj^sk4EtfLFT?&KC>X?d<9fFqym3<@e!3qCNTvb z0k7pe*t}xo*Il`|%lG&#d)BMuJ;yD_k2tKSO!4jDpZz`TtgEoYj}jB=MrrUp~bbVdmxM z0tJ4Xii7K4uRXzJW3_#cxCXo(^5UZ?Yr7odF@xANy~cS%dLnv|Bkw5|W?gFI>^0Hu zc?YtT?Z5Z|*ccXIQh>{El^7|78s;=%>5u_)&&#bYY6=QYTJ@jK zP431Ldw1IaywD^pCQ6?!H5U^GxaG?}_G?c6-!L=9>t50++$b1U8y_mznBES%SI(pS zskG`Vc06d5XK{{qi1$9-0r#%z-GHf1i8zjBlxFTVf!|$<;B3W(g6dxgbuk12$CLC0 zSuVn$VUZXI;^p)@#rnFy@{40okI2ih)SV%BNFE#{NJjS*Tc0cG+z60L2KEl(kmQ=7 zLvW8@<5b4L7=20==9H_PlFoW_1Fr?J4`$fpld$Yiuy{cY=0L9^$m47mAL%-ZN0`39 z{Z~K27WcMoXH%mfL|p!FXL-ed{NY_1%{r7)9RTm9JG`6EYB62PM|>D|j|tp!08Q0t zH$7AmmcP1>GY9Nfi5Cm_*g0Y8z6^lZ!x@_+`vlc?wiy>Qztd!K0B|=WCyzFw4pf%g ztAQU3D=bD%gK&TE<3E%ORcR^Yl!r#@>Uy>*(+h3Y9JAPa2{|e*@E!QzEBN&qomXpt z<&FErG~>u9ad`_$UEi>qI-mQ2(hfu&3@x88g=tV+;6p*lUFeMffKK1Ji2+I@DoQ`q z+fNo$ctJn@(Z5ipUcpL%5!laQ)yG6e+^gYqqEvDp6rSKv`;@_keg1+tPut0Lsi#BY z(5y?J9I9OU^yL)Xnd6{N%o{LN=YP(PEV7WzV7S%{{Bg0f1Y);5N8t<26mckZVZZX# zQh-~bVc<1ybKmG>mH=>yD@d5}p+^2oTabkO`Z-(jDk~N$byH)#G1&VGny~+)3T0IK z$;$GB&78fbLx=rb5VA9IT-GA%40XnJI5(?0H$qeH4mZNj*M>K1L%4r=hlPNgtlIRl zo?q_fT+h0;{w&38tv755$p7F&Pwkhc8u!9I!ibXrq`8@vJAnOAu;nOPyR+FFEOmz& z$_6~AHXHC;V_CVWJhCvLUwA$a#z8z6{q^uNG?EMl3^?G>LHD8>g-O^^A z43QutP5&9c52t`ltfS>*`m)LQ$=h4l< z=Q}WJeo<$Gn5RxSsoKVbfA6^nXAV^j>PD!*hUTvk5`1RA$Keb7b*zf4cC;DsDLkz# z6o@QcGkAkoC4yt`#4yZ!Ew6i2EM*4NlLS1QYkMv=EaoRO{-~Z57%gAM69HCilB*i+ zt}Vjqs21edDFIieUg%1WvV@TI`K_7_amIo)4$E z^<^)fM-mhaR=0zSvfkcm6PmK6k)Q&z{Qr^l7En=jQTzA>1Dh8S5D|Ell9rN=R}n-? z=|)9Bx^sZR1W5(y7U>x24n;bpYv`_#jsfO(?f`z@|Not}bj{K`CwDyi+56lPg3kyv z03_rL*WUSTqOn)%7IAx2t4WI(#Bdb`R9`e(4wHe=sS!sA-EFyo4yBj5YK8sN26Kd09PjgW{01o@$dq%DF%=fK zyXVvr@WXb?o=NLsI%|fUq(!+X?QGlBGm#+okyRA5WfO&!b)4y^tT|yRwv7>wdXv!_ zRLN{|&q$rg5bQ7Nvn^HB)F{SH%wwARJ@`4t(o@!&{Qm$OZm30Bb=ssonNtxsz8kTR z;X)1AW_(c>DSURIkE#$BbFE!=kJ&b(tq=k=x(f#TZ-9uaXpCmCu8{iQuP*2_YruBq zlK%tDkD5u}cdr$u!@UfCGVutK9uw_ZSQic5-NY}9egyrB|Mje@n`B=1OT#>{*_G`s zf5zu`>g2a+H;catK}?DZsycoHD!-I^S;=5EG&NC=myrb3J_fVwhzl{&n%m4Z@m)%$ z08BdcVHi_^&$}cNax5G-LN=ho{~m3pYj=^==#QvF&czoeu&vnv_dm*E?#H>IvXeZ| zL7qNI=msX4+m=HW;#-QXUw9M8gRWWA;ze$=FaI?NC-^4PKn@GE0wq=5x`c^8G0aDG z!P271sgSj%;6(cU-kSK#_F%%>fS%I5Dzh{ouDW0Rpmg+ix7^`Je;AoaEDuzZLY_ja ze{E(uM`BCl=5uy$@o$(b)pSqjx-w+7M*4bTQZoKUTHkjW$udF2W3S{g^sqs`cJD6O zH7A-;fHau$W|_tCGonjSf0p;^p~HNZ>(cF(iN+ob4YCjeoV+8EiB_(A-kT|_T za$*(IS(@*#e#3SERmMtZv%SpBo#{_q(xoZayY;agBOyxwKqZ-M8KHcT_gldSIigY= z&s+ABjdR-+W@o^8c9>-ehcjepSUFZ$e=Fi~3RtI??B0J6=@WFucAb9B@ykL0@ zQBY?e4EmQ{pyvGQ6gC0iR2O<_-D*p7UrCjJCb#@Bf(kBDN%BLR4!$LWJWZ4IVwgyR zOk9D>_!p9q{7(hxw43$5J+VPJ4TVIiyZsrp^kD^c`9+u!+9<%zFW0mC!AwS`jzENI zCL6VWCteN$gJ&6|Iw%V~+)5A|0^yaBAD*V1j*> z&NzD>(K3Gt9Uy#f3xJ%@!AS&v!o3cGoOy@bfj0v-1NZnoz9@r`>oe&0{tk~&^98n* zG6%7`_0iU41K#}N2!nl0oQsxyfXesa^@8aG01T?lw+=yO1i4pBg&0{Ev4186N49>P z`lC20*)Ga^GNwhDiy(~Y=Dp#sQTa@yM-Wp!Hx*(!9yhxiU_;b7miKu_SIs+2%IgTazpQqq4CA4aC30o2T_HZdq6>?>-GQb^F z>C{!e?UIgF4Em+-zL~u9Tl~Oup~M~*%V+c!+7)+tRzY%5r&A7s#v1+x5K<4vyXilM zH-1!PueWW;=EeP$^+{!16pYR@qwJ1r(7k+V2JKwH{V6pGICH`FUkAirEjcX(bK@vwO({u zfVdL0<0NKh;dWTI{W4Y-4^OVkpacx$qbodQ^y@1z)52fTSHUZupWV%r1j-JqVOTo2 zNV4^F^R4O`Peco+6;wQ0RGeg5sF<>SubcnRlSl0`k>iZ0H)eMWe(|tbLu%+ ztyunAj*emlU$0p#uC<#;M2RzbtO`cGKy%sA9Bel#u*Skw{ee~j{2p-LMBo7gdA}ld z1?Cd8Pg1G_-IhVWT0RkZB3iR^uT+<0D^)Zq_*|)`MA;lB8`?C^*BgpZK~S!l-<*_~ zrmju%%CG_67$jx^Dvb&-+#qjdur%UycV(2H3@}>3SOhqTJ3c3YQfKNN$4E)ZAg+4E zGuPyfl8vB^b9ZLh`VsUXwQ;JN$QTqWY)1l~%Znd*`ytVo-$7UUh163} zHL3p`w@19tQF0TyEAbbk^gc7vlDRq{3@NH!gI2gI)Y_VG9;d2R57>Ni4~pL>=_fK1 zT!N~B$D}}^m9)U*!Hmb89|Hpo1iC^+rF%p^D3)L-(Z$&{xxew-7yfrb>6E>o{CFPQ zpE>^VsXGQ(I**#%{}g+%sn5F$s{v~Oj@1BBK-D7^(xzD#y#WpKlEDnPHNY>;B!6+xPu2Dj+&r^q zGIYBrwHR{>h70D@;;%}9djsw6t5}s|h41OfXZqb532OSV?t%-A{`ZuTq`HLB`P zoVmy-6ryX^{j&?WyZY~$l6E6fm;D1)fcFFKQuzN!UTUVO49z@YbUpZqaNU-du5+py zaYZ9~-h9~E7HuNngf)E0GqUivJis2!$nfEN0A~Fuf*;tp2&fYK+UsJZypYS=<^v;r zD!xb8^LZSXoAx^2r4T^j%V&QR2r!R-jR`Ff#eefH!-<Yi8F z#=>Tl-ALlK7Z&O|`J)@H7r}VkLK!<7S3<2ZJ%za^c8pomSxhmG>rS09ZD^nE z2G?n~b-lvT_#>8Ia-_MM3EI=e|QGxC}zxw}F${#Wd zOH6cr0Tp{Aa@aG-r)cme0CMqhuvGfDJ?Zgq0GPfHA>ppMXD2dAJtr*?6 zqPG1RqgE(mv>bbnO&3r!;qD&{nImV(@0d-FyydAS@>JB$yR(h&2>Rr8a#Bi~L}T>& z<9oMwG+Fzx9jrRh+dhfi1jXpgt&C5xw5~0g)*F z6Z9xC9cYV;ty8DJcX*SAbFB1;$#xVj>p^dUu1$E!6%0Tv8)oz6IU8ofH@E2`gdy?g zlSyn;T)O!dhWjh5j=!ACLQLS2G=Oe+k99FMBz-MJ<|RgKQ=^N)5#9izvAT0f8uf#e z!jLi0x-?QIK0ktMU8XBqe^1q~s7Ec75bro>x(h$u_& zJ~|j+0(rVhCMO#^JJoQudWOULPA5aoZ);W5)fTLzWv?B^sKU3f&Y-C^d6_6sxTr&!$HwT7dos`UVEAC?7eRv{lK!WTI)KosCfIJD9lTKNuP-0Vz zlwyKsuiU{f%EcA01r!_hQB1xcQcD(7Cwhh-;e-EQRa2F51TyCkC-gFXs8#&YV@;0T zFq9~3+h{&pkD#g}VRO2&4GA*uiWP918z$vlK3*y5Whu-rNRwlVRz8A1GVXdQc(xey zTvHoth9AH*Dc935s0ynh*+}i_`{<7JFXCm55TSi-3QgY~DoSxg_#mS@erT&5KrGd3xcWsn&&u!fI-+qOcZU|Dpu$;6#RuaM}~~6BeU$ zLyx>e@rg}hb-0)zw)4lHK8>zqmtGa*3LLcz;Tw7HlGeFnh8lJjOt)4~L(krQu|a(S z^~wQ@m+#`J4A>1-;I%=Q!nWd>@Sh-)ZuV!pvPdUG9mmORrMi`nb@>RKzftQ*mq*2` z`leTE`xCimy$GOxQQT@@Cu7u-ScfeKqap|k;3PR{*SY_yw1c0z$IhCzEM<|piQC}U z-KR^AWn1Bbs~MaEf`Hr8A4>fIQ0{dP!_0Oj9(zckg6_A$rF-DLH^+zeH)_986D>r2 z6|D&%4t$qa(PQ5)TzDjVe^5S75!jjJ9ay6@=j+7LmJWTcU%5^|2zQTqC4N;BSJpzr zJ2C{-f(lPr*YP`C|JhGrDRvLmzT3A!Q5*PiX)SV;$Kc>A;#6nkxe)*+@3cq?yAzFx zh`JFC5;%7|O5x#1{MHHRBI6qn|Fm%@OHrFgzprD#1l$ZD-v1Q=N{7dvPi59zesJdo zC=*EYOM;dCzW(^gSxU&VWB@PP&l)ZnVG;P5HOM{P`u&YP!m5`y-!=6?SO+`E2-&6Z z{+7|#`odH*ME&HjsLQk%g@5=Nd>SMcXgSQj!u<(t32frle*ktFHTC}j zrRI;_6|N3EDCaq4N-*4Jqj;o>hJTMDeMwAJUDXkynNmzdZ}0&zys4x>G-i}!c1SRd zG(dNjye$D~BhYTXZURny2M1X2yUh!0dK;KQgt~*Oy1G*rsWSft)XDqc!KusK=XD5j zf}^}I2-Z=pF5G&0`|Iq-p!%ETSC|ykga7%-5d5G;=Bu8FR4sJloHN&@HpX+88|Zm1 zU%o8rw2URX_dppGGV?7JI4-x(x|~by8>|}DF564!9o+Qj1AuDd+S>@dyT4y%DIjJL zd@8z}e>fimRx*J9$az6n&CCcHpIZe#fG6;_hP;)-5cn+6UOhZ^AhAJTgzO5n7#I98 z`6gnrPvTqtSbv6L?Hu33Vb;r+yUX^#&tft{xWNQONFEpd%lZEv+bl({2nXAkE3FGX zH!Tty&R4&g0fRDX3IY?*7>_L;q}-yBLh8vw zf2PT=kz9~KqvIyXSQXihXX@+PIbkM>yATnXhs_J_6T}MQ@firbXiAjbFg)r8iutF- z?T2K=YD{5E6g-~_PE5w6L1>%&W+@xVh!Mr9YTWv=biEC>b#c%GKXL~%>5=-*G4q`t zlW`d4i5nMXUmtqPYD;MSoE31CTtPQE+bCA<-JFdr-cVnhDO~ziS67)%Hu9{N>ZtQoO4Y*yCwtt!Jct9Um0LL?}eGg~YE zAZob#W@pZd<|d+*#^X79sktyqn_!GopR0-$i|_EH$^%HkkCt9Jcp`^i>U&m=+XY#? zR6AwYB@z`{Z_s$FqcooEOX0ur>8VX1AoW4>B=mNxd{#cPqeAMLSDwb;@nGToS)!lM__>W=fM@2hp_pUVj2cV{T1`HRW=M>zmLgLof!xuC_T;Fr<6lXLC- zm{wqN`r?^hbQI;3D7pK?T%9T^-+!9Ty%@k zi*Xb-&`Mka20flTSFe|UK~NrQ`!h(*ykg8~_akFF5N&*Ay6Sk=$Jsw9`IC{4BUUT) zd^LlSm!j^|;cF z`aGMtSZC%>EBl)>ZknBaaVV$0C86JJ%UY%kXw&A)I4HWk$DQYaH-D>HySQPMhLF`1 z1G3Qm@R82e4BbQ!KQ&DOo1zF_wLP!$HF4m(g@itTn=_?NWy-OTt_=Q`4ofHR<@JjG ze~^3s)ym`i=T^Xvok6K@Uhkc@J6-B*5`@ZbhhV{)dF- zO1a~=;)DUstzpWp7b|`yl#WLlV;V8`I|kp|U5BZj20gw>d8|e9t0GRiUs1iCE_AE7 za+i>gdVn?H9>`v#B9((yoO>>vAIq^>v0?0z-3D_9t>ZlU$eeC`;U%?Q@;sKc3PZMsgvBG$)Z_CvW->Mp{p8Gky*FkHyx6Wm z6IHbAtrhg^nZdrvO8_G6a`k%nO?P$djITq{ri9kwXbfKRI`sdly6|bwIDS1Vx5y8> zau@{yt7YFXaK+xLmissG&1so^-~B%VpQBw!$85RHvMoV}Uu}bL{WRXIcPMwB)}d17 zgGAcQvv|7-(|hm6sbm85Id?{;E_FphkJM9nIB)sO!fPqZBYPSC_3zN9HrvDpM}T}0 zgs60BM1Iz!yfNcDSAe>&r+tnR^3+rAhZXfkN=aPW;3P;pf&jZ)mk;# ziBA>A4jYlMH%*PSg{^n*Qn`VcY?&KLux$qUBVc|#I#L5irMg=))>XE7{?9T5t8Du9 zEaDLR9_uew8lJuGQIU=Os9BJHP#8~mdH+5@BO8&K#Iq*dcEA`tKW&{tFhZ`zWoJ(*lzfcxQoO4Zr^1T*8a5OwUr^hy|o{(U&&Q}9Tb3a8Y zLYW#xFr;v*dW9O_O?cDErV7dg{fdir*NAqj-ap?yVAlI&e;Q{axg?5kZc=z>TGt#k z*(C>M4-P56x6OU`6xn><7pmM~?hx|;JnEF_J@YnND1KY%OQr%Om|U74_Iq7A zrB)g_IX1k|z)euxg{3@(9e?*cUYf7oBtWstT)&{&f+0Ok5+vlFl;gIy^(f2yFDW>S z%y-tVo?7IuowY1ZN$l(PJMwYQE*uxfc+&6zD-X{2lIZ%wmtGlnYcsTO0o&9d8%czf zGwXgaT0(b5r7J>v#pSjFE_hMcBWC}|UB*I^O{+oML(}f0}9V_ z8}|Xr!n>-D-$6MavwkfCI{PTLGhCrp68SP65Fo=Nf%ttNpw&YOCE33_zFyQ&Z+ zs6Z(2@Q~lsLmO;288Dky!ml_QBcEMG;KkQb+_O(#S58H{geI!-awS!6P@Q3eDT|!c2e!}89m83mpZ3jS8?V==22-{nB-;c6$cy99o2 z7>BMJrNWf$r$p3LkuV+wNp}m5%l;%D7knFzpL5n6&ACP}#{1vvS$*wls`&T7hL$F( zb#!@N!8H_3@*!Q__s2$<^wws#MGno~_Vq2BE#h2zVvT^B4tjC*yM<{0 z&x#XU?YXh^%@*|+gx0$ts*sTG)Tt>Xjh9DQxDC}%O-Fl%CEcJ;4{LoX zBqZXy)5;~;`gZI1X;oi4P60y9Jwdl8P|H-Di^3x+V~r|VCY2X{EZA1%fvnDbpT#|` z*QB0KruXO${~!<8Zr`@7#C|mQUH*Du`wG6JC)ZAfAV%FQkeQuV7)($t?qFRk~ z?1mDltFlc+*ONg;M`E^9r>}@2zIB%HAQZ6{b4YdTC}yheK1pWkYm`{4t(b+1671Bj zd(i4sF?-DB@z;+YBAuMdABR?3+|u_r6S;FVCHmHyk3k%IJ04pf+Ayk&JVMT#}eY{M1;VVkBh zK|{Qmypbd}I8v%fDsh*)T|y7#R$ISbm{wT^xW%*aTge-XSw0tCN~_V&R?yD7gW1|N zR>u?cnR@kP!A-1Tt^OGt0$ibOw2kFzL0_n@S=^)ZSZm&l=t~&+HfqQ;kNne>pUMB8|AxSMpWJsnO`$$S$9M3@Md82Tbjjd@+fkU>OW!vs7)@XOWvXkLAF;c-Bk-+A1FdS0~LFniYM zdjcB#1DNvR7^w|@VtYz77ArDeXw_muAFLyK-eedmswrehHv4o>q@C6Wg^M6--LfMO zdGLd20zc?Rk_cg}p<=qly(lh=_*j>i1$l_0DwdZ)B>}+kIZ5HZ?=HI2mgrbfNJInm zaH5n7KWVYQGT1~{t}WXXM=H$wspj+;8;Tu!IrSt}%z z)7eF>qhMf;R*dW@K=_h=_Z({=WSw$h8%#XD9Jr4^S|! z^sT$`jVD^B=*EJ#a1#1WiR~3?Ybi^uM!)i3FFm9ui^8ggm|ht`s3pK9XtA9l(J3)~ zD$H~u8hzjrC}?Z=YTDcW=kvR8aF{v*Nxn!TuHD$1DJUQl<3R$oxUL&i^bt-gkRkR03zyO z5K>t?GTn^2B&VU1cs=e>6@l`7;3AO+eMo;Rw@E6S=@9igYNuh6RwKKg>qJCElizEu z`0|>U8T={OR6$h3b-ktC#V!?LJ7VoU2era4G7?Z<1B(VCAW;99!)HlYt)-(xN zR+W&(0xRy_4v_cF{Ju;MH9%wRrf&B?Fi$?wcWH2@8<|vA}A2f8Ly>Q52k-oF0gtwWXqybx$3 zPzpemZ#MHuVRdIHbp9DCv}krfqdYbUoQ(#bZ11Ar&&E^-+8pl{vZ zO~JuZ8!AE^617bq>18J5r7@&dLauTBT)lp+Lyo^1c&lE3NJ6V~cv59q?-@6swm8a; zAjsT}z}nNUZP-!Vp#Y|Q-If@)ve7^n_^XjA?xsF&ukWHJ92R<-HYBzll$@`g=4;`n zvpo+P?_K~Pu-Q$KNg2felXWUeK*zO&Nj-)23-3xVm1z$E@B*4dAJ7@m=^ENYYqz!F zI5xL9i=o0=P2(7{(cLzu3!^YV^t8?IniJc-!BF&*Kaa@MOy-wgg6SEpjB9{H@znb~ zBUHM9h`i!=sduv9(5{&SAN)Y2fK8gC)W;6?O}wSuANw}TAagY(#!+j(b#z~TzaF_S zovB|XR%kIq9w>h3JZxQad37}qDRM<WL^kQPtr3F9Y;4 z{D!QYFz8zi))xyg@joDM@t%J>f2#VS+iu0R`(Qpzk8FTk%ck49c>G48ywC7>HJ!{T zSu1dZD7@Nz8%<&5zNpP4iUB+6*UVAI21`^Jb(FA^2eFU@r;HsX`l1tW0sX`%Ub zUX(t#HOXJK+qznW#1?T02nfu(f|wK@78b4Ytpb#P+`*DDX)I#BmA^hIOz#Ff!+Hnx z0Y6HfiDfG!V!#mY^$TO*y=|?lqA_YQ{04VN>=szLv!4D6vmykiX3x=TXrBeb;c4AC zV&d*e+ICUKE84te`S_F>6wg)wB7^Xj9(8?c+@ojb#`ViW~hrMPeG8sGn|+(_cAt*)+q zHw(*(*m^|!H?1Raht2w6)*7j>(R_6A+8fe|sZ-=H^)j63IsofZz#A1)mE2o*Zj2kX zvnX^#tIipSF%q#Xmo8@eMp>4oO$&zU*vhm-3-WY{Nz=Hz+&{$NJeuubv)BLq`GaJ4 zcy_4)B5yKef;NWp2ZM>jX>s-|tOg*MGz{ZTcwZ*Z39IOwAoE()Z>hr~71g*WM`7VZ z5H+wYPxx|Ly6gjq3E*iHpbM+uD4qLyotir4&(7ZF;w0v91!FsaSFW|`-_m-rYv->L zcLx{mQ=?k+o>0vMDl|J(lw(&H3+UCBB9>nx0dEl)$t(pGk$q?9daI3cy??~TTmTn$ zReIqreOR+!xwO&l|Dc^J99Y8RSE{Mq^X(076l zmpK)!*&fGi9qp$*UpMX5@mKy{+kp*_Oq(KB7r35Gos!&X!O{I0emgXb zq&$PB_y`2B+`1MiDAQ91<&Va{ys-?bPUk!8~Z;k3pA@2P@qXI!l$2v7n2M-d~4NieG`K&qAzyzqgwF2INsF_X14#ohGF@PY1-p#x{0GI`^IGQwFz2fW7JEC0A;{&rnPV)Zz#{g% z?|8HK0EhHMM*MI!P@6`4qvOFvG;+Erggp?x1qVc`l0Ie3geIeVt&yatNWGTvm1-uy zq;s0BATD>zu5WG`Q(Hc=1yE@koC=yOnG6utq8UZv4nSAH6R-y=s_ApOj=d(D03!F% zi`GLR)_rT>6+qDg$>RiH}3mZkH_&ikwNOzy4wyX%wQbOGLzf#PDlnVO_t)Q%byEU;MJk)rv5E@#|k z{H*w?n0iwyixr#SEWruLC}|&pYH%2B)7eZhKIlsDEbs~Hurx&jJxZBgb*-QQ<02CH zmMXSK;58d?I&b`zo_uqW!yCL`>}wWyFUv1rX35p{TnzVr(;hs%31*&yJH*zfh;61h zuQf7V%q9oD{);R*?PPahnNje}$Dya~yZom#YasLmF;LK`!XJ7YB?3;iPy#YZQN& zE}$kMiJ`SQIuyfhW>@P!<~@wi;w&h3b>me&<9YE8z4WG|)HOUHsJ^C}#X;-otx;sD z+dO%Zob68e2gj}O%r=i)kAuCPY9g_JGSsqsfMz8v0sakw27?@IEq>YkK+cCx6dPD`<|nK^b?OusFYmP|eyi9&pwfKR0$s{Cve#Qw2Q>9628qKq zbEL2%S1FJrVS276t{VJ=W65l zajOjhawx^y6Om@wA8~H45HngU#ghTWhY|WO^-{7bdPivb%x~iCe0cAPh^`vHT84$z z5ElUTboq)~L35%Nd+Rf?h(d?`Nd5hZ?BZk>{guU;>9Rh3imrwG)z#hI8SrE59wX33 z;m1SaD-t-sI+Zhv>`t)GJ^VAjZ zfjr~-OwGI(_V&E7E;AAELBgB88i(7BvpLx8tKaO?7k}>QAVQ(%{M;`fpiUS-NW!Wh zH<7J=1DnOHqR>KIf4_!#|M!IagEU4YCp32!p3w&uT=_sg^G9#jg+8X=ewV54{hIMx zl$10d$Q6urNv1^a^m{CZw&py4;Pd+#X@5>4&FAN?HhDjh(w-wvr{nk`Icim$OP-+_ z`)yO|3ZtP=cJS!psC$YgKPOe33u9qu9-o9s`XSipv>)wMo+Eef-BWWs4}F1+Y;=}( zQK87lEBje--QZ;&%@|cXU});#7|X0T^J8M5n2>3~N2II}VrwZ}6yeCGUC0(7w2&$= z8*O*{_QVG&OK(ND3DVV8D-WK?*2XBw(SsGI`UEeU8}+nEH$8ng9V=lO6#e1RbdJJR z&D;4gjRk$~xozX52Ao=K9V0v(v=`Cd__~RbiptETTo2`x6wtUe zkYgaNzR)nyDa+~4iQH|r>6BrbE?r4i&6pq(-}w(l=E1QD+`)Fem-zm;&Nk2+sNq5H zm`QAKYS1^tfBoqPFRCT+Rxka0^>Wtm?oUA*5QKmxA->plT|S=OX~f0&rdr_;3uGbMd&)qOE5x? zCAu`X`3`z)>{;_9`T}G%RG2lr+PJVp1aP+gL63gza?vOaFm~IFB33{XY#JHDeo2e1 zedbW>tK40mt@j~gy)ZhPUAE%Gu3cEZ)NWRw1;m}aQoLsa?0bOlZn;`UZ9~JO^JD~f z$#z{%N$_t>v`5WHIZ6KN?M5jE(Mw578|(}$ll+?w zxo35YdwWIbj%CGWZ`i>uSWdKU6Z3nFBA>2Z zD__p@nh#+IB~=vAR3jLwG=Ty+LSH0)V>J=*p&rlTNm8P1ADi#ZKOhl5c%H1KcGLM; zwEbKxNuN##SY@V=xnXp<+kcje2fG&hk|G6Sn~TP6H~p0r1aB3&dZuN8-k=VI>*j1L zpCXQJ;t&g{p0!hYBq`;#HqCY(_Z+2v>6-DVgeoLH&Dg+R{-laJEGLLB+HpD6F(i^n z00q8*Sd0Nz!yXv8{huTW5Gy+q>4=|kj1DK$Y7zy%2p%~h; zKE2evbNhCqNzA=&(_PCieOQp>c*)bdw9h9)1ze48ZXX&DpP+Tj!k9IJ$5;VK&^gFz zxR}dvssHy{G>{^G3LWbo-)40X%LTfra1b9ay3AWzsj~~KM zoZm{Xd6HOs-+G)+1VFanSUPCmmMO+wsd*Bnyqxd^%Bu&xCQ8DH-|N>OhtTgTT(e}r zK-OFTI&c_*EgKcK!R=DVi1R-2RmHY|)bCRI)}Pz>G3E+kl7tgxk9eb6VNCa zSy7Y>IL&~BgoK}_&QqVIweW!B5-~AFArhrkV5-_Yxjllg0$+Mm+S3Y`DsUPiNixjseo}W^FMQN6G_m{SkCvM-G|9Trh5erhqn;zK2q*$0|elR%G8e*IvN3h zZrenyFO%qOC3b~1{{uMlqUluz+0bjHNL1t!qR6Bx*?A_yxKtUA+p6i;B6Xsq6B2~k>KwGds9U#Exp4^}qg0;$VE_QX1bvtsS z9OwG8Q^06`xUg65vFj^Ebj=(1JJ6gR05lBL_8tF$FbfFp`;{uk<-yQ;rVNz+}$yS)`F#yfUucm|`c=_KdAsmG7^gbYSH*V|z`58~vgKRbaQ8;SR~apT0u{HG5TdMYIk&7by<^vCP6vOHk zX=oh^HOyLxY!6=TBI>QrcV$;w;$u|<@4c~;VnlwoBbz!n5gk5w#aUVf>C>x#G$MMx ze9-ZLxb^|DX!jZnwL}3I3&sXCEQbmlkKHZF1o)5%lD>*=`q37}#Xfq5r0D{aCUa~HRj;Sw$jt+va_@KTu#TVrM@b(Yo6I<5}Sb0J&{lHK9U+7bmJ4y_zG zIGl$hs$ffNGU~qV4;W&3=kft_JXdmmE7lwhRG{FKd&(O;0|ASoeHsj*JsS;|8IT@? z)>q``0UVY287#O;wr;1-gTjpE|w4qA*=uB{i_$_cFxrsooc z>5tSenOReBH?_nr*4p_mKP)WNKZsSYU0|@gFnmiC-m>_?rl#>;G#h@TqjjbCn68Ev zl_yOLBKJ~|H-L(^7*@fk-Da~#y+{PWy0%6`RN4$JZk2X&ZxLnX(#BPPlhl`-eL?9V z+)uD9w_^^f-_A%OL?rAMM|#>Jk8zftAl=(qHX0W>iQaAiyUKNrUKR#eC zi!WC|EGhtG>IDb@+1s`AUp?Iizi{iQZVId2EA`OE0z~T#AO4#;e@Yx|A7OeuHcOt6 ze7FD#^V!SPUhaX@nbUMoya+!H#ka#G-*y7AJAfQPkf)N(3i;R;ah z>|%dj6X%NfMCKLW-4Cbr55awKEixydUf*Ut z0AcO-`t|Fdrm);TqLW?O2)5FoOnlJpKJr;s*7ddf@qS;tP-9rl9?zLz*Z=e9enc~$tDq$@wCvJ^%5(ab2Lq&?t3R!Bt;<$Bj zOqxE&N`DTW7t-z?BECQG*L!14>bz9xM2F2J9XMGM-C3*u}bLC!uKp{DM+(#UK7Y%4WAThr2 zZo7O|)Mnx%Q=!N#7|xqiLEsjUB&XVg?a|S-VPHj=6~qrVb}B}(6*6ygkUL(;>lx~( zmEsu|z>chDS-G>0{Q1ED>&=;q6PbB!KJ6Y`dDMz$N6KC7U}9{wu&9DPluh$045)$E zmC-M9UY*#Ppr{Hjbc3gRzekBtJy4H(n*oQUY4;z}lqG48r=npiG!ZlNEb@vi1Hj)s zEz@f&v){~!8H+z`2~}QDxEN2p=_-0SPJ4I@KCVEqy}5U@__R{VR8a9or|e|7K>$9u zB4^jS1{f%Of(@jYCd)<-EHib>3bWkxH`CQ?y~H*W$}9bpL^r#YS3^*43?TSHNlN~L z zPAgMPFe~xpUyDEaPZ9GM*I#`Y)s($T5-jeR#q+@5RI&9j)h}=)rHPrcTOk*X!;Xu+ zRo+2&J9xH$k0@SiVx9b=tnhJjv9CzP$=sZ+5`-kR+u-kREHz+eR$;MT*fiyTlnf@X zSS!zuzQ&KXS6(sW)G5B3UAmACOZN&sRW!w5L5gtigRHLri>c7f;znp)*J%ddO-{sy%}_fyz_)h`Xi-Wg5{RuE$L00}zq z8@^zbAz}CIhf*;@1OjC-xB9<%{?<|jN#I|7z)fysC%o2j+sgzmyE8i~Rfwoo+=eO%x z5OO*>^qM$<04sbc>{-hDvdi^FZQ{4KwC`%clqYCUz&lgonU(=5Vl(N_U&r>)?)^zE zK#KUm{B`QqSqdafHUaAEHf)~iJ35|ln1wzE4jG@Hsjik#-x{(gLQhoTwsADTA~=;# zQe*Ds09}XXC{4ucUM)r5Y#X2al;7pel;;*0!PTF-g(5T+Qv@$odb~J;@#I9-=j7NQ z`eiS}0W3%{sV!&IdXj^<2p?SnT8;_0o4{HCUxQ6!dNS1OVT)A^g9dQ67Hz7Iqc9r| za{x?nZrt!`6#w~oaq?TRf)Cnph`mS@z(6t-0=+mPtG}lNBkffHr3CsmVS80drwh(J z46>#fN5{y{pw*F66BFWjjW^Cd68;G6XSgfKrAOc=_ACWP)Gzsr+oJIU{JhBN7q>sf zWYeRnUJIw6c6Qs5G{mACPXM`ctI&MlYFCP4AP7(D0P>|`Rm=2-Cr@b{O>&WfW687v zM*2YCe{NG!Qhw}G5N1~pUe2GzEy46EEpDei2f)l?KrF`LjM1eIIX07Z{lzv0=7agn zrUhD;E?=(QnC~*!Mmq(<#A_(KHo4bL+eevN1uU?%r1mYoM}i;(f*v-R5n9tEpkr*mM{>N3Gy0^YC!pO-Mxt)k73>R)ug^9K<09n>D&O#-Yxw_3K2rXyuY0kB3I z<<2%olCN@qaBM!C)N}obB{Di>=|K;wFN5p&yY9 zG+}0=@1d0|qMasyl~aK0!`X!aSySa+PJJYBzu&vEiFNRX5AZh1c1PnY1#w$qbI(@` zp4M28OmzUYg}RqRvtsdIi`>qtVUhviO;F zU{1JES(B*##Z6sCXtpCUR^7Vj%lT?b{^i;Z5Q==NdR=<&hzoM&ii^gxwH;xdbqe}o z1Of<82jjE%%*YEVQs!^00p059%^JFN3`fV3{&)9I7LVKWD8&|)4D*|fvo!<3?))<; zYJPksQ77A)7Rv21m^zL7?K-ICs45kHZ!y-zeHj2}u2P3u%i{z{`InQ&nJvtAvqk4! z@>4M_)r^!i-z%;sx9;(QSt`FhUyWboAMiF5{D+N{FBQ{eXVuoveHWvJ+Da8>9+y^S z&>#U)Eani+PtkKaIv|MiZ`s*nTc75coX2{>2!u_fC8q*AF#2nKsU`+TyG^m)D2VUc zof*}b=K=t9*g@cz#V?;Gk-WH>1Ea(R9YQc zB?)Hxp2U7QUR618BPZSVu8G_)a(Vx(c`mHIGzmZ1LQB!S`qR(wPdGCZ9DUeR(vx3u z$;`9+nEBtB-pyp~#ad8)>^ThLT>OKaC)dvPo6Ht0X&ifl3chjw%-1Z+Y;yvWyRO)o zl;QY)500z}CuQlrLbewJg01k~fyB=;17Uy7up?s2WK-u>fRn@W`=P?U53dqsFs&m`D)vc4phd9bQ1{|Ev? z65Sf!>rJ8L zcMm{j+2ikkJ<}R@+UjDWRBztfXxMGRO`>Xu za=2AUBLg-&dS$MS(ft-L?-pqR*sxFL619pv*z*yXEoL~gf`1&UXg-$yhJPDxIYdou zn7C(oorU01gd^=@iUgnhrqUjbzG_t zxP%+LHa=|f^FSngRJJBdN~hdXbKVgA=X?MBn}EE9A4}UIr-na37tFTq47XnP4vvlZ z6U(qJg{TBlA1{7#D}dY07q0~nZadA(NLPvs2(>#O%TevTC-d%cZ`>PS z4c(V%O12kz=*KO;$x-*he1`kR0+H_^rHNoEOke_2yUH$v|8O&jG$5iY47fb0RlqIX~{19zVc&=4ev%d&tag1MIko?~gNAE)36{%fL~reOWcRvGJj& zf}C$>WdHKPkF$_FjkqjqE^o1npJ?bgUVgN~lD}j{eZpoq;w`RiTn}aaT%N@IReAW5 za_c^4ciXN-%iP?Ur_diO1-NUd>RoQev6DU6A@ectpL=$fw~@k^IotdCcjnSryxWX> zaQfqJCC~kv{<*iv)pgDA^3LEb@2oXe1t~a=6;ONA0lTjjL9%*cFrA@Am|A?6n(^ks zcQ!|&H@8}_f@#}2bIP8LssvR#%MUcN#wSco^9fSt1!pD zagr+9Tw}3){?KHom-S3~Sn}D)d2b0k%6Zo8L;o=-L00WdU#VsLW6s^SAnDxq{oQ{& z(90_5Q02wx-%D!jol`SmJEE?)6)CRhr*W}-2bGA>R-e1~yR{!qz03;!{>1O*Lkv3o z3zzrw)6827)_)H1ky@rFS94Bd;5Zh*Vs5+9Dc;(&$Qv>*%o5sqqcJIn73`>*A$h@W z(`Ipaeb;xs$`EB9dxtk|VQwV7HW|t_m*+1aBWu1@#q{5w`kR^D_{GQnvSwC@Hnwl! zFZ-C=JQ>ulBg$r;DpC|Rm=k+wo=BY>IeB$++ig!B;!5kMNjx>ncT0KO?dO3`^`ZRZ z@w9eBHhf2X94wAZ=Bn(`n^ODbIQCBG$lw-3@Kg^)G_rfX^F(@S_|V7?1ikwHVE;jk zN^VLP3HSz-P z^PfvN`9-6IQ)5>rzd+K~YbIp;U$3v~ui)KjPy)l;c8FS3q-=g`QDRJDyt2myS0V>D zJV!H5#n)h8ndaliVamept2+5ZwU~?c`Tp=))?aicmT>C&UggY#J2K75uFDCljL(p4 zj_98B@ZuK>otftRnCaK*b+zL%d${ZFFtp`ko||`;k8H71*vF14_yhaFxUaK#E_0(x z8-}iOUBJ>B;Olw%59bSh6{fuPep5#ubJ38B870&6eY|sG7F{*sEq6@+an0RT<3d+G zynjwHXmN${qj4YjnSHgO-S({Wf5^a!8y{_p@&tu$`!D5_mpe+5sa4nUpA+g5d{PRs zd39ikfH?QOn97@O*sy?KjWw1lb@b}Xc`9P^3#)%M3gt;{&S2;Ij}70l?~c_Y);`Ae zs2yZ8sxWNa(6y2!ebuin=9Wd8>$s`3sf*P}E_!Nw)Zo9}cw2Vt#~n^z(@oV93sgI# zl0treuc`ksblr^A`M-SNzi<{yw5_9wnS1TOc>7uWQ|xw+s*H)&UIIRsZL=*;@AgXW zd#O{c)1;40SwEwTxt#tux?&s8#$-)Dq--uRGp(k#vm;|<^WS~HRzDTg_a5kCyR*|X zP8`%csQX~4wI-Qdjqb-?FtRp9fO>cHob zJ72zA%jvV0naov{c<75QiEUijbn6cEY#h6sEH#m1{zzd9tZ`Ct^$%cm}-Bm-Rf0XZ$6DW%UnXUv-cE%^hMr zU9cd<)n`oB;FpHnpY~ zOMCj@vJ9%(^%tf2bh&a(j~evZaIZ1T-N=L279Bs`o_@tz_y=#?5t}Zt%C~VHO8i_^ zeZ)TcJ!{sxY~x42Ff+&en{{;F;Iz#j$C}F3ocK-Fq~S>$=@vfew|y`r|K)Xf)JS|o zwTY+YXk2sMrZeC0QXBN}#|#cY4^2%%;)iBnvPN{*O2bixb{6B6-oQ!LPV^53RKOKV!1EFXVBmk1IR?qo5eL zpE3)cO$z(h;Nl#VMoSGH)xj%R!_U7kX4K)w|ALu{8lTFGCkBn|yiLL5m|oxQ&gOib64-%V=d>E zTBW3~mwjgGY9=(B*vb4} zbx3mFt^I@V2WcCOgH=C)AS$rM}=wlfG!dRL_~sDFrLy&ZsE0CY$R{8k~UFLA<*? zxpTPi@VD+44{Sb1uhY@Deg1iS^TeIj!MWQp{&ZjIfzlWIm@hq%8?;WUeYf_mlxiG^ zxz%j#)8I4U^jWYu`_I1<_LUrlU7A&SZ~wZ3yHg|D_%Sf^Ygi3@+?;sh3KKiE>v=LF zMf(5CO?b$Oc_x9@kN?GcN{K`|^Emor-{B`b_c@d|TKv!~=A3VM-rkA08+*`}3he zJ^Aj(2M(e`KaOJeqE}8qq^9wCGAI}L`w6vvE+F#L#Tyjpu4qeXakWt3%9byW#WGOIu2RRBADxAG1(9Jgl4pH!pM>&;9q%LgAXQTTlH) zydAfXuK(#}$~NY^@=&fH$9>mdnx)H|*PmXKY$~R2CBw0H!* zi=F(#q+P%J`K<$r10+Smimx4>BJNM7%o!FT<|l5y@uI|`+o+x#ULNib!~Pha8tzZDXaCO{&WmL?Z)4vu zeF6T54efu2GbCC6^X2IO?qZ$VD221O9KhkL%2VmL5mB^XiZXG7bun+wQVqfR`J1ZH zRKO=8A>rkwAs>TgcbYD?V^vpes83H*rV6p(h$~&?zf=FKeP2sWLG?8c$+J|n9GBLT zkCK!QnOod4V&2m1`##3)&p($gTQ*6hyV$3SIDNQ?sT@P`gU3z-XS;k3DC(mU9660& zcN>pV>iTqnDk~&2n!T*EKR!O~)9oyk_Wh4kD7P!%`x^n@AW>37RIQ5GXW)yhVB-ZS=|%xp;Otnz3+ zDdjXfqx(&KuJ?>pRiIcl6^rxnZpQrQzyiLd+747B)$|9O#?Hwc=(9)7{YI&nqzNMO zzwg{@w;dI(H*RqHi1;Fk>M=u3V+BJH1H;hqgzJyDbGwZAaa$$PUw)l9QzG5-&+o*? zqWXO>jkJ0?JmZ}kEExtG5ihCAhaJL=a0g#8DiE2RtTuaEO-z5CWp7VlMe6aqj)wQu z-#4~D=G4UBIsaSEYeyUSf3np+?6>5XdqGDTF-?{ybJ(@gJ ziK%pLaB2-=d)A|*Bx*sA3n!J$6qTpzDi7Tgf64NcCJ(TUEvDS;{x;E6E6?)O>C@Fj z7=3S*x&&OK_EV*5YHEhyo+sd6_C=1B0>4fWIRo;f67e~`IcYtOsnx_DBGO`y^^bRF zU0MY6Z?q=llc~UZ9<)g+lE0&|VmhbX7LOvLUMf0QX@PZVeb)88-h(41<)GBtfCnVn zTt-~P2{TrrK9%tr2Jd|7>n~ZVw{UtqaY>0(?m_iL&D6mFLlDtYY+hTA0^-Pkonxq} z#AbZDy1#reQ|$ckcLHdlaZSzzOYUbA@5;OM8#_~ls9?vPe;T>lWs4|4C@J*L(?msm znwy*L>vyw-LFLta7OIljc1OJa;jf~eD4)GsExYR2w==dyN^)I7_t`FvRM<~ENy~go ztZfK!y9`0)>rxne0p`EUPoh#Rt;p%~@&wc>(lbC5575`VMWuZ+4A@{7Qfbz6m%_p; ztEy>%*PNbk&$;i#)inv|5YX9nL*+`J#E-XhTU`o2+ih;w+dSo|s6=<~yuXPi<6C8V zYPBr5nLBat%Qw?ox(Rcr00-}0{$ROF&wKU(m7g{rlSCQ)x-_%D-8PoFk|N>OrcBto%wyvp~ik;|4XD{ig* z`D^_2wG$Y_s*DT}$U#xB@3NIjZ+kgSNa%7)JJ_eoX1ew^hp2E961)d8fbQrQM5y$R zH*jjsadv17Rg1GGT@QWO@Se_k8vcw%9I`L#+xz?R)%7v`KIyA` z;!>1bf9?NgUM&9#6aVz6g^kHZi>Hi2Ig(}lAH`M5VLFQsscT=qm$XtRAbNX(q|rS| zyVcQ2v$V(7C9`&1mAED$erCjMlPXoXOHCU|&aA+D&;-Lhv-Z~`~yF*rcGE2H+gojCCE(Mk7O=kB(rW&@2C zsp_j&uQq&+tr<{^blMM}I_a@ltoCQ1I{Vu96FW7$Z|rZsUBhd;%iiR*JmXz%_C$g; z^7Zmf7bP|*HkCiH%{Be+myCG9|9BT z+84geH9O+^+IQMuK`9`Zp3;i_9!rXxc%3AUld7M2ft-L0B=6?+6Hw#Cc3v60| z@=g?1WDAeYGO$BOjO;7ND=#-Iqa%+brxt8}&zm|o4y36(Ft5(_n$llBAjw)U=rB@s z#gpl*JF6>MzT;a)yB+kEV;TRQ#uxQoyc>0}kN5LU3!Ay&Uhnit#c2+$o<+r=b!NBb zKfA0E>e6jaoY#`>fQuK^Hf-2%t6fa4i#>|{%fW4krx=H`cdSgK1bx4j?9 z@>PZ)Zqn1y_U&qNS^p+n+V-c-A+v3&8(-ZdEX3SaBRiS15GucArO&9(fl1 zcz>4mPCeEskvlNUy6GqE4*9H}QIc#^?I-(AmxV=gta32<{Ome$Sc&TF$+?We@CRDv z`q25F!m{GkeNQzuXf;~Bj@mL+j4w?20(UxRP5(6hr-^Y(IfPaKHT_Pg;@1oL#jVVc zCi>>H3wHMpy}#J3P**nMyGg*_sR4VB>E-sw94eCmk-pnM)EW(lE=ukVZ2nQ&Umv=u z96wRD@1vz7tL_}kQAF&bMT?$xiqx0JYbmmEA8C}h|L{@WYeJ7(v~b~>YuB!22OgAQ z-KZ-@$<%+D3rI28=K=Qm*kjE?Tie&mazQ`d?Nrwsz^y{wLEQ@!?Tp)VxmjpOtnN8` zD@xN1f5Hq$;S8AXnH^=8@e3C(j%ipHRShcoRO_^6wUf1>PAwa9O(6o0hwm9`)kU zswzPQd+>Cy-1GDErAu5N{x!PyIuir9%6TQ8y?#<$a&$sSZ=Iah@J5JR#LiOW+e1f*9 zE_BrC(c`B1+ABjxdbWqGIJB$EA^P2qSFwawl5Ttvw)$`WA~CIy;By%?wd*{l&M%1w z{ON{aR})#|v?q=imRZ=+(ju^= zjK)n{IxFEb>dx>LI3+U8y}Q}nJIc5{-3Pz(T82gJ!-{5NRVH1w>|aaspC*XFv?O`r;OOYTs%!S~ zO`BD4T`P2^gM)+nfCCEWU%sq27-%;LzkU1mqgE<|ftRfvKGXk!QG9yGS=9GNsyY97 z50>z6H1E0)#cBhT_wZYid`??_VDr63Hu@U`A1gCYfajc@LPboNZ>Edk@EyXgCSWm& zyr#=ZuC%N3(`_v<=$Dp+YwN7Q5FHaej=zf^7~LQSBVLC+hip)O&kURCa2@3}F)!lPM(? z&7b2YPFXOP^ht+K{xn9F3=B1G!K-?+uvYzaB$n zA-yQ&*Qmb&g1#qJKH_M^@d1 zZE3^tpX69(GUQP>Y)iOW4q}%XBY&N+xxm>=SoZ9>x$3#pd<8;wVpro&VY68jy^gkX zPlp#gfLu&o6;|#{3CV#tAVA$W=Me&My(27ISOBW5k4*gg4@z(Z3Qf|AJ zLPeC#oPEe!;qxV~3h&RO`oBC8+s)L3svj-Eve9VE5OpZcu#Gv;@7JIYTUuMgG2_K? zdsE+{mh_rIrVCT1;>I`f8a6|c>rY{k+ld?yhbK+ivTfUB(-4OP!RV)PPl=m|;EhW4 z?-H8hpFjNpVn{Q*zP3p!T}HXD?NxlQ6Y8~NNbkr0o9!L)c97&vO1pzk+036j4;<8S zLydQ2+3-`oXJQ(M|B1h;PQVuX=_f3OY#!}-=*ORa$2R`yRkeBgV~k zJ7obSmT>svqfYph;gE0GhRLu%KB)G|1(q-q#Zjg*R^`b_dB3>%84Lg9_WdAw(glzd z)v2fxvTR1wm5t5*JN3-Fvg-H_-5}_Mo^Od-!G|A>vB_U_BO973BxeKPtjn86J{eE? zjF2(_7t`r0sPK|gM*a6fNlEXjsw!$f^QpF09d5!k1WLsZY-_)uL(Mlt^)^ptpU#GP zz5Gfv1)l!B_}EwpDsx1UFS{Del{~OfbAY57!7U}wV6eD}-f`5ZQN_?5W~h5Q`t9wq zl;e2Sru5??D8jcvHzv{?7Cohl0)BAG>P}&E+4nTuH-g$-h9F$`_P*8BCuZZujfRg; zjo-3k$5gbH+XMw9nE<3_UA%t!wVm<$#rLh*^51ShHYC%SmX@|F$ecqFK5sfe zb7-%ieovWz$_&wF>P<%VhrcH>kWxlpgY^v?Y1W;qc(tig`Xc0ErgeP|LiMV3HlQ&h zJa6dk{Z#JX13)+q>H$<59CL`XV^|K9nTjc?E z6cr1xH=I2AQ|@uK{ON9GiTM5{1=|DED(^s1$c(0p9;+&q)NMQT_4TO%l}(ABX^unf z6+xgi8jtVF&b4OMWuS;yjh*3Kjh;yx^c?%UYV$@;RP^n-nz6Q$_1e2^&)KtQE-5-3 z83!NAvhUM))rzHPuak`W?`rh5^wd)6yIaP&YgMt5>dB_9JZd&>`U;5??REaSixw{c z_A{%8bc^u|G6m?f=MD5D-aNIHYD(Gt9rqJZ)_c7{ll9UP3p|kcr3Yw8F8l|foSdBP zDRWDwx|s;$0B$t7Nkb`WGkkuVq8D>jf>kix zEoDD7jy>?~63wJqqv(o*x|;)K7R^1bj$<)@l1o?xGHzwdjyIMk*Ie9P_4P)mHwyhs zZ#Av{b;e|JKrrh|EtTeCh7Z*PvPo+%*{#=rNhwJFdOe7c%=}$i4kNW)H(yyP>#fxB zc4MijEuSvlB;(X=mV`Cy2%CCAoZlqr4s2IE+_?i?*)E~$iCQCGj-{O{{05E_tG$@| z)RG-jtL*eVL;VwjZE}TdYOfqW@X3WGZvFkkLuw(E)7e~I4GGgKXt9<&XU@7;3)j>G z9+t6Pm)sl@ahvQ(>e=Y(bLC!0%jmHE;)@o!dq`!-Q?r4$C|b_#c{<&#+Xx*3mL2)@ zq-tRE8Q~*0|t`;3ge%apD)s+Bue=W9MxM@*H0>ET7G%YYByaZc^YK@;= zS~hp8gsyg^f=jc9K{lj3dZkO`lj&~d#hI=H_UO>XZz(KmF&Vng1Hv%(1gCKZ!b)#M z&kM!H&%S*5l9VoaK?DZdetzbT4i?+Kj{J*hObTSbIBLs@%*P}@QV2P{(Y8YdZE@gF zUvcg4YR(!t(fB|V6!L=w2=#XKXoV;$j2fS$xgFe&?06e|;s^2>hAWRj0BmAhUNqg$aIaLpFv=GCg_9l51Ln2=D-20g3j>f8#y`~{^AV8!8hBkP^&w%9i2y5f6l6=G@YBJo}wzsad@Ek z^AOUKQYcdQq-lVG+Fnz7;0W!@PazSbK2UMDrgGOO&khxIF}ViYXr8Wv-(}!F%c+5> zpB=0iHlS%XauY@$vi|fxQ3UOLs2O<_r4TFyb-gj{`1WqV_G00veT?9eKdKt&Ia6sR z;mz5BtN$LI1MMwDy;$1PG4(dxUvK2WGV<3`-l?+)ePIztsh-$o$0si(C6$4`wCiqY zUa3M4tgsBn@}V_rjKvV#5Z>Cb-ZtNXDF>ivIz4L`2>P zq-Q``wj9~gJvxngFtk-@l@R~^-sL@{jvt7b^Vydt+t?s%GqJuTa}GZ`MC%6UV=YiS z!-_>Wg83;LLxJ-RwLV}_!Z1qKc(f8Z7kbkI_uVW>G88TXgV{q z89r(rd;z0RPtKX|?e{uEowBRY%~MP7IL4fZK3cC{(hdnh$b8@^Yz;wc%}AQa?m|yn zT@Jd~&4#mPQLaTBPjK(iEe{GZPo6wUv7(sd36t}KN?&~OVh`wjDVwhQ@R*u0(Gkvc zyA2l>nCta>Vc)ZSJ;*nC{el!bD)U7JEa|n@mB!($>Kjns)G1M{glU`z#q>IAB5S*C z&Xk?m5HZ2UJL5djm1`-rmhJqin zu3Z%C7URO$Zsi>`k*{y+ELOAzw9DkisIQ@i&h{(Jx*7xS3_C@6V3NC&lyY!KNPa!C zlzKs=pJM0_JQ1gw{0YS6v28s$QZDCO zroRtG_$$o8ZrtP2Ra1;+x7mRK1}+cOlxV;S7H^_E(KbPs+0TaG-X`dUd~xN$m7n71 zm8k_nHri%BSU`GFLSvgVV+Ssf9T29W(yO@3QsdOJkk{L_wSNy+^V%2-Q>=as82gew zmYFI86otoq=^5-$}u_`2v&`f}P33M2?ig3WVCbV4oSApAQ^B%kq!UzUZcMp%Zbn={vw^4E$c`; zzvnNG&)$2yVteB|EXgEN9zQ*q;>^#_E>8);>GO((E9+w=GkgbIs<+rSaZ|B)II;l&bo{%=7R6`1wTYm~Ze?uC03SCS41 zXzU?62Hf+-oNv@E3}cWh5ODS%RG)!}`Kr3chz0vbZm`g#VAl#*I!jvvzT^f)wsmHo zbQ#({bF>sWpT$`I^It*Ek@DrwOi*T2_M41V?rD5x@)xBHW}@$N)c3Touvu^+x7|vG z3t6!Ou{ZT^Dp0D2dqGZnfq*|$I_3Ok$u*#H(}BX^%eu=Cf5?*1(6MDUH~73oMAgqYD(F8m1#raeEh|%79K1gNDEX>Kl!Y>h8$Rnc?pg z?H)r{t1n1HVI3su6A|i^%U}Vpt8RWzgO^8PgCFN0Tni*^n655JmZB&H{06hqR zk>Z1#(mI6nujC!@#G#eF3%!xuN;DUGy?!*Rniby17o`HFH)){vb{}j;i0<-zS#D;~ z`}Z25G{UOTlt}~-xDPr0 zxA#A;LVUYvPkHnhhmpRimDmm0t@wkpSOvX7OARp>bZA75mt5sELRIp|y+b(D%W)kz z-i!8rXQ{(ecSi%mzoC}$YOSuw1j4;S%8V5zOj&n7*%_;jJ^M1w|3N15$}et1UCo(u ztg&1OzLiF-Ib2;QFkzxgXyHCmKYT^tZ8lkazh)y87qA2!N~BcZ@z6a)y>2P>)b98E z`SVALtdP$50zcrQSo9_IRfUP9s6ig7fpBuoP4fNjawx{J#DcrmraN-_LkBXDBT4@7 z*VrmLQ-kYn2ukSwPWq5C6oi|<{t{ONyUlvyO#XB9euPf$wd>ZcD@KONv+xBH7jKcp z<+t4Wd<=`Rdw~8{)yS2E;^CCHwWxsQtINc;Q?s#QHW6{Ck`d`v!4vaDjw25cN?^<1 z=cxCxBAVnQ)1ccRgsoT6Mn2vGjlgY<@AjXbF_k)=T@>30Fsbtz^|G?bn;}Tx4R+KG zWInK5&@mzQm52?`oY6)1JBt3A;W|m)((*J&KD>XNkn}t_qoO%*{w3B8)c&prm8*4Xseb_1J5~ zN~;DI;063ixMDuuIfPPaQCq_El@=qLO^vC9W%F+}C1Iob)uQ#Y4_0vrx;H%-X#JE| z2c!SMGUx0R_geC-M~$7D4gX)KWXDeEit?kcGzizVhvOWb9s%RQn#HLp$(+x}ike#z zw>QW>c3^02inDN=Z%K?)G@;rtRmAd_T( zlX`pB0mV2-2@#@BS)}WenP_bNg={6YajSyk{X9`x9U2-&n3>hE{qRBdYz|dcO1KWM z%m$mQB+7@hG@;a#LbNGVsLiG}UL}m7kcI@?Bffy40KP!2@ZQacI!|JP<5x1}!96pg z{+(pLQec=71E0k!kzO?-ZXLlX=vJFXpf(bVdCx8{r#|`qDFg5xJt%U%w_Br@&r)9G=UQTWNiFI>tZHA{*F^?FFK&)x1uIEK(Wp*(xPcLC~3Fm z)HrwYKTnOHJ{2B{Mr;#UZBXH}i5VjQ`I3<#U?oa6BK7`j74gmxaNhX#;7CnAP`l-1 zDZF40c38qo^$miF4!*;<*AG;rAj*`;q9_q~d;88paPy`?p?Qv+AU_K$7EDlof>B;B z+^Z@0-TH41L3p#Kd4Nr40)pRFMt09G53XZ1+(jwQHzX`Pv3cR!=fh>R zTSM>$ZA;q3P+3)go;4rz?mmat%gqrq5TV>HoykP`%@$e0$EZo$n>s;kj3e9aLf5`W zc90O@@)Py9Y9t3P-hk}epobj+@r;LCukJ0PSHrd3%8XCuTeqeK(4OAqx!Xgb_zsv% zVAT<7`P~V43KEk>^&j^cs~J$4*XUR&~g%_#0#g2rQ}l(Y874h z$2aszpN4H7vjsb+LT)Ai3W5a9vg&*N$k425G$q=*#n>1D!PuHPFZ!|*=t_Dbi}rznaTw+Cm!2H$h;p5-%dw_JgG$Rx$;I0KyOHY^7a2NP(O(N2c0? z9)+fyQ*>@N?fem2sDaV_xSX31@@Y0}@nfBzoWzIO8l6_?&lKdpv7;NrSpdl(lnqkKS4 z4ClF;foTTQ4BA*emo}y)E5>>v?1Y52kn6~! za5{-to-GW)^*y_JWK^b0SAjt;oe|?_M=ehG*uB{WNEXa`JE z5&bfqL~bvjDoRHjDWdF@JPtxhRNV3$vXXHSgfMSL0}}gu<8j)h{&m(z*Je|vTHxG; z>j#i(UK^_H%x_6)rJJdYka89N3tZqQOI$%U)2L^C{+9*ZPH9}{d#y!{`C%s(m{icQ zY!IF2or<)Cpg$Toff=qDdl|dizmZg)DYk7hLY#|^JHRlZZ^D&Vfc1Bn0GdyBE0ebY z^x~T;-g@5}<1PF$?q;I_0-nf5z;J_W`xx1T^DRN6U=RX}g|=2e1^0kgwoc8I71nsc zoYh`LtB9~vQ}6gYlYksL2vK4)(r*jdHPyS8c_NOx#o%x(nE3(w;wi)ix z4*QIK5C8J)pdg~Ei+s}Jeq@fJL0v#k6RQGB=8`WqpJ;Hz%vVF2{o;ZiK(tu__ux1l zL+T=1Y(J%CHjd4L&9Kr%o@>w1;&plrT?9p;`TKcYTYxA#83g~k2>?<}MXa2oe-nwu zO)!%dSt56GkybPla3L*vPExAtoSP^d=~jkf5%QJ#}T2okxDnUAD6Km#{ksMJhUKRR$CYLG#m^Bm~P# z#|mxH*7l8j%7BaxXV0F6_HjPbUx4jI{Ory<{)=}m2x$WEVmq_6*NK+dyEPRKxo6>R zY~JkF=uh5EObvc7D=e^^(G{?6x+E;2?!F6Tn;a_cW}se|ORb))~NI zcJGiPs=oV5(*yf;L5VZf?@*4M9G1wZ85sL$}%UGC8G$+Im)+GJx@7rcNg zow*V$r*qIL#cnmirJ?{_+7hSg+}+bWp9QUIAP4rlL1z0#(o7q zfiZ)OXiyQzRt6+GfXx|0c+4!h$XzUbRIW$>keiz>h*RAtoQ{15TrlP+rVRK8Xx*%^ z(S-=`vs)>6$M$_$W=n)Tpz-rchoTJN~e<2m>UPI$bu=s*K)6= z6cM;a+v=IvhM3-fpzRGcqB$ASi{GTfZ?{2|x$`U6cjAKFZHT>Uf*w%u(JsfzWA6{S z*Q(F3+tvoPcT0&cYJepDHUe}?#pU0a-v|x649jl@)b-+m7!l|JK_xIX-D@E^XTTZ~ zXCsDZDiPLZ1Jm8Aoc^8Iks#CG-Nm*1@Y&~w3?N1Kd_8*`X9CE_y8vjA83lMINl}KZ z3{r{Ntw>p^5Uu^9zNky*{(S3+aryUO;dxl$@+8oJD0j|KdSdJ0+k9pc&y?{Gm$`VjWPL0Z20$sNmchek_J?p1k&LIt+`&>tEeYZMx3)={o36G61nBQ)0!ig2;8`9V1jcV1B2L zo^AqjLx)zyw$pZIDADMQot?tWqNx04_$my|)Zk{`zzj!5*B`w5Xm~4rU&!9?UTbG>yCdY!kLF~%5n-jJ69D8SCvra%q9>$U3 z0sz7`-ha&%L`EIr1}-@c;VzSdekNEiv!xY=o;fF-gp*i`#LE`1*u8ZtKk`OrC=1Qt zBiOs*?J0kb{5AK}(+hJ|;H~$a2OsLx)ua$sFZ|_Rm5xTGCv`0uqMfDzHAw|~KP}+f zvbJ%o$E9m?#4YB(iCz;eJO59^`iSr?mdiG1#5S01jB)q3zr5f=$+asl!~@^Tte!l1 z+cwFu1(N@YTKwA_{waH=>gfq~a6n^!dAn93UxD2^N)~A%qiR<8*3oWskPK zT&2B{M@{+cHK(!(SVCSzfAgiKvmpmIPb{(OsR@u^;!95aDk$t+H=W(7*8BamisGl* ziToBPb`gmQn;bl*6nX3Y_q;9h^`?25`pMSr1!V zxl6530x#FV%+5LuKTrVSxDT9}nJ-&$trwkVO#14|O1rb&-Q7gYLqhADud6^apg|*4 zd=*2fKX#vxwf{-m#Lr_tQt_?O@&h6rD+^`Z9<4&CRE-@ce$?}CB0++gd;Y?`U^&*w z<58}mUqMr3&YXuYtcD1w3V5Ukf+=;V?boHH>dwy2sF7VoXB^P(C@U)~a`N~NXq>5- z$11y2O5IpjINi-?&DF74`0t~FZLI#iz~Py)a};iLzt3bJZK_l%L;b;|Nr+z0Qaa3~ zuihY!s_SvqV$U-LQtfp5DyYw&Y@KJklecDZD_g4L`|IK-e0>KzTpsq!5c#r9B@eig zQz(V=`t@su;;f;ear$lv0PQLeBhF&VMKyZ|9#b^%^;}QWQa+Z*W0b2*Ccu!8USKo3 zoLzWj+ePVYaK;Q#)0xpcMzv7k6>I%pt)o9YX$GMs57FqA`|U+=eQV-(zK!RHCWH8dVnxt>yXk@5}6{FJoSmjwkH)WGRoS4(Z-ZzS6D$Lq&xRNCjlwVL_ z)LfNA6hLwmDmk`;k2me@Y-ac)@P4km4Z&dBxrKP|W6#K4}!oC1Ck@w|SWO->T^V5b{H* zcItgAb#(|u%9zpwM0yi=FZT#;hcrnzof1gyI{*9lYuDy{E(#Sb2$1rDPctv6=>{(N zYDefBv=W0eBmVt#umWKXowMHiKC^E((j=b`Rvg5YEN$K2;JG=h00##t7&)Ag*yIDS z+Br^^Y$u29>Pop#qUF`d&t{1T^JZ(FC2R$q*G+{hRal0zqJ3Y~m*Fl1X2R>KG4?@t zv`|XQhYrs{Mrb+>k?inUkFlKajgSzU^?8qPVzr5xhxTQpjA+(aNHw|?@=6zwN zFp1-2wJo;zTwMc^+{83Zz)8nMyQErtN`F8t zkvH1yZ+Y%U3Oig^S9k5s9cg0w({Y5TYRDsUIPoo^6Bm-g8$W(LF)m1&C^JQN99d3p zCJ%zrues{po}ewS1s&kGz8d42G(P#3B~YHE%50S3R8g_f`LVA@;C1)QtXPqYxxSW? zvJ$?T2oZ5848uH8&x+y~FMbCr%nQtbbp&!4P;8~<_Dwg3Ie@FXqz-`NzxA6Cgi|_y)Ox>I za$(`Qys!F}^xnz?*|mAWyeaXIhcXd$HFS!>RlJSm0=Tsr;J&%dF)DKb;&JZqwKh`0bPDj2 zLJLdFYBo}S0-A&KI{bcr-qKHBS>J0W&MFE~T2)tHzdN`BtRn6_MHb*pbx~w@uiE7**Kyp7_$olpboNh~y?#H!Xk3N?zH4g48$n4!jjd&i)aA!hw_K<8& z)<&x+DxDUpRo}#C-&C2dXB|&pDEQ@7#QQJB;nf}ny@no%;Kwc|s_H)iyml5FbPzl< zpM_yaiLb+LFt1x#A>d&GXim&|M^QhR2pikkN)sIDtx*kI)2m#$P<-w zkL(b04o zEY_-ecKUt7PC%<9AF}tMXzyw#6c~9DmjIlJmW%h{-PqtT*F5lbcLl2eI~v?bhyBDY ztgNggkMgvYTR8RD5G42Ynqvmg1o9-;at=O4d|rLoGz2@05>3?9D9x1WHVMi*LroMg zb4QY_5G8I#SrJ9LROm&mHWYUE=+JwsbX`y}x1oHPHTow|4~AOqiIq5JXZx_{qn;Wa z9le&b81qSmHpNQ2?;y}54?MREgJ?~0U9)D56Se392eI?1mdp89E!Jz->gebYVok^4 zPD6E{W@-OxDvE>?x}-2LD5x5Y!6yY7+*w!MKO{7t$hY0LbEjBJEt1HfG<;W?;DY0J z4MCO^s-+HAl^t=nZh0X{X9)jh2M<1buN-P&VUb^uqI9C|4A4Z=U@07IDK-2uouQq) zN^g-I;%7z0$7>xeI(V{pp2^}H(80^qJg1!ta0Ve+gg^p>Xf-B%5m!K#5;8@{ANNzI zPW|$VJ5<&N?ZK`2BpiO}f{a?k+WhQRj;x$q-lLOamlukGorKp^U>}FKY=d2vi*VgG z#Vk1)nQZh85*QNrt3L?*f$iJ3yEk1vHQf!Sr3%>lb9ogohFb14p++_Q`t|E? zYDst*@B?eAiIh1*L4*fQCAIVC&!-M{QLtGlDJfByB#1!N&71Dj1OfJ@^}Nyrlyxqz zcS0y_Q@l=az8_D?tRGf)Gc~9PZQQiOFY2k~-LosJP(k z

J(ilXyt@F+59iOR3wRWntWgtjBeXyP0PqcLd`Q{{=^-rAJ#iGi-r0W7`!98`|j z3MhMkJ1Ysojv%pPJz8rD0&0~8?WDwzl~N3pG2aSk=6i8Au*TlDp3QXK*vr${6U-8;rl_uqO) z=(DK=Yv=au>madyew|=NFrUMB7fK%G{oT!|xb98N@n&9S|13hF!Z zyF#cMS-KFhM-|d>UHb!EUD@E08UgO3Yn{%J89s1c z7F0vo*o;~5G#!e80#WJ0RvS{Bh{UA}nbv>|5@5adQ{;=@RK)j*h17MYw2!MT-HeAe z(7f2Bq!m;a?%4__;g?sRDyc&X(`v^d&ibQQ=kq1Wh^30;Gg0bmn_+r>SI@IMQ{s5{ znd>t&u1D0N%FZQ%&FV!=df-YZiqaL>iE(j~^-jpFDX^DsxaE9+$Wwo8;LelVydlds zPhvM;GAJY@qZot!?BBA0#^}`oWuY%(Dm<#Ho~cw>H!S~^`(tI{W65 zYqjUX?!7m|$~Iz|N*u613OSp%LZ?xeo9goMS={d)KB{oX)nXj)AHVEEwk#LyscQbs z=S2~YKV8{`H!kFWGwck6dVX~;fbcUTf1U8ji9HXXu2l6w;KB*8Fhje%D`GIH^9`fm z6vjWmMt{qebFc&0UD=g^mDk-bQ|G0-HutXFlyYWmS|6L#` zo{1pX=7LMjzxjeFw)^vyMLYTIK~JF|H@1jM*a-eX5nnTk<8zV13Js9x3LAW#ya_|Q z>K8ak0RaJ2!B6)(nZlP$WM(9s*PQ5pf8jysIw6k4YA5Ui)QoZqhX=m9ddgo0&)~jc z=fUCO`Q2jep(#4w`wos^iG%W{LaKU2v0{yHC}2!iqWM#?lsu9V;m`&)W#%_>$f5I5 zY*~-hQL@%ki2;xp+X{BjysPuLk5J7R7H(shUcIrANIh&?s?mS^J&olY{z_N&4wRdC{MJ#aiYqKaI0SJnk35}_2JAJlsx942E7WD?ENC} z0~L02h$Tu88db|8i*pvhb?~hUVL4tDk(EGTH1EFetXL?LIePcd`xUsW&X?(KDsOJdPYr$PAEa^u%TXhh-_W+gFt~mJCH_e916Qn(fVw*G*Tn$a$eAcSo*_W#O9>Ds z_3b~N)J;05M-5ZA?A*z@Tp9~QN0okr?E~W~T2se<((%Cg<5+_;Rfd@(MYzxPo;s{o zo*e73&Mvka`5hMMl3hRWV=;kbLLRgwM9oqfbvrk@FJ+<6+qIeh_uJsh802g^uH?vp+|sVc>34a{fWEa*S5gO`C*1O2x%(3(|v9sEpe z&1$MQqr@G7&nRv@yg69D*|#ziBp7?Rgstaq-7AW{_fnR7qr=973&dKl3V#}q>NVV# zX6)hLznWg5YSXLpPTxSpMs1gvhOESg1g|iuJLK1y_Oqn)cBRUKp`cYb>~0O~=`a9) zgT^Nli6$zSUtVb7P~(qb=fc4h;*nrYovn}~ba;o8DckjG)!*Z&I_7gYb|~g}l1MFJ zk+?d?Qhx3Z{%G6M8bpE;za z6ye_Nm64M(4TiE3yR<;)omGAX%JU~Vj72Lbm__PL@ud41<78Q5im-xI@UOrY;NEMY z$nd==UtH3KDsX{~=YvbEB5vKhxnbdk#w&pF^=c{KtjVFU9t~fOgH0Fj9vsbr;X612 zq+MR2l90OkU;rD`GUS2}Agx+d$5Anir zm0CkPw+P&yzdaL)u=Q}>)32y>BC3W^EsputSgK)l@7QB&7$(~kHnQ?TcFIUI2RHJ} z<>Zi|-5LU#uDXyZVwy1vHta|;v_K$4Y$QzgtFne1I@?;4v-^(mhTM0=6i4p~g^G#1 zsZkt$v4UfBzd>s-o!gdb9Jw>aEhs3+_Qcrls6?KEl>E`cl7dfwWxR>1`&_;WZfx+8 z{6z}yn=s+cs0cR+PVE!q-q%}mXwx|yLv^$16*lz5nE4xaKo3!O8==~FR!M!a`jE3^ zoDfcWgL>dn)BrWL4e_p1&0+(0Xg$v&;&N@-y7hdbQcQGo6>>Pw4l~O^Eh&cedCU^8u5C9QE)RfY3om4LrDGkkJH?DWyuFNyh{`#iHMcU zQ(Jo!Au<{BX$nV-$xT5u!=+|QkD<&(&HKVRAsDrY;THW6EtYB^ii2P#ESz?kNKHDk{97_?Xfmun;N{eaIGwV4T!BK%_CCWj72D zg{q#dpq%BJ-?(xyv5z}nZfy$}4LjBkRr;${a;d8iwOrFIp~4l-k`0fj!2go0) zb4aSkbU^|qqY1MVQ59hPyd$Q&!5f=Fow#$ms3$b^XQ7_yl_``hqL;)iG3n%fOf{uU zab~AS=98`v?xd)m7*@$&sCJ85PNQI$AKJEOk0nOC0KvzFYU3`uR~m9A!AfxOn<)!Z z(oN+Bzl!?p-&DwA{p;$6wX3%|ExoRJMHn%XLhQX=uh3NK5?~{eYif{?_Ko_Z$X6c( z*Mt%)Y2SFW7O`e1t;CE;#DhAELlt=m>f6tbhH(eWA^~0-0xTcO3*pxh z8$PC@+RYF~VoBjlFbpoCHdnKQ3=dWPc|ZrQAmS1AT|qcod%NTtVADNEp3ZN66YnBR z#WrLUH18xuT)jG*JT`EyKCVtg?#&+5j;e?Yn)&}{xBo#y3p^_cW>4q<&D1XQnR)3^ z4rq-pupD}tdLP&va0hlZfHOfZxw*M}fGc3Y=RkpKT;SYmC+G-u=mgoWl9xij`m`6c zR0lL!4;%&E|2H@+Y})ji{rSKZbfDcHV(Gx%Zlw)ydtv7jhyxh7++l@y!x2y=2b`n3 z`Do3mRa(FdCG0oF4!BXG3fR-!bo3^$Z<+*Z;;2Jg29v@NLn|`CGUIVy&*u7H%j>-i zJgszrjrZiA<-kQ8r}jfED(ER-h7UMf0rx6`jtjDX@fA2%cLX#m3JhI6hgBt@eTJZr zXWt7vuT{p>)D*Nbk7)_a%4ci|P3LF-xgs`diIa3k=X z9?&8^#vo|hxAg(SkaFN4p*t{s`KxL{qawg>+i0#-1fy*{iSArhd)o87>bKlkrUSpzFNj?2MX*bD&%pdA3~ zf%TB?InYLg83u_?hdL)+y>mwfxK9Y!1TMXh^XbV+$?k&?S0A{z7SX`9D2oLy?%oIt zuN%O5Qpe4}2?!B|z)iqXOANH0CFao~UU{XXz?AluJq|77<{=+qg5GJ5{+ u;W&WeZw3P;*yJNr{6Gh+fQ2cfmmxwMX1t&AZeh+lkj0*^elF{r5}E*{O^u%b literal 0 HcmV?d00001 diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/cte.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/cte.png new file mode 100644 index 0000000000000000000000000000000000000000..fedff63c41b1e5d531d192c4ae0024045a9c087c GIT binary patch literal 256033 zcmeFZcRZKv-#@OapOVnJB%gO%}7WzB#8fQBKN*1hA;A)Us5wyG`eg4 z__nDoiNS4iZJ-dZ_i)3TZ9c$2VGl1cOQYWZ*c+JPJS*RP{H?&(_p>(9h*yE?bz{ogOW z-oJ_S|9<6!ILYq+`;{GJB%A-wSI%Gf?_>U1kpI?ZV`u!gZ#GuqzcaP568{y7jg=tz zuTX3(#eaojV+x^I7f7Dg^PFfScynHx{Jnek=mbnp{Q2`IBq4#_R+UENJDB2@Tx z6A8(8t-o&Ja;Zr!dmeGu%z9L8WWU_j{LT9DNXwT~f`Woewz(#~C70CI)vE#pxJ8!g zJWFub45Fg;B&P`FhD5S-s=qQcK0dx_cHCz0+@Zj2$-O?RH(i{LJURVnto@Lu$kKhG z`F69q#>U3+q{DmU?>X)khRxqS7R%x@mcvoRV^HR|Dtgo3^u!Q3(kir1UnN zk4BowWMyTImcE5bxVyG|xmOw}VAfN?lK2YCzo#cG@b{A^PkOrYpC=i0=J4Ar7_ZDG z+PfDz?JMmrbPC1lc+iWkwGQ`{zfC+mW>X_DC~jh6LQX|>Sx--oSRyWqKMj8TCfYwY z&p0?ZsHN&Fv))J>@gAO?olSZ&`)6S;J@-R*Ic{+%F)#?f9`3_>k=zS8e%V7@Sy@?0 zS-H5^Q}oF5MY$1NP;s34m!6o|1Xru+0fAKdr*|l*s7j?dzBLT;5=-0D)3aN4W-i6F zzk++pHzgr!>}&Jq+ZWSHNuEA_@$%(MYT+m5X{BWuv_{!nKNGb&2YG#bd?p<^Y(CXK zpyaqohd*uRKlI%WA3a*o+qKh^P4= z@!Q#V99lA!%u6=SEr% zTF;NUi>^(2Zl1a~s)f7jNv>pf!+-tGJvRIql-$OJChyP9;ou?vR_;A6SZGEWPhu$bA4^zaw4Bprz6{{BgOk6tt*v)HcimQKs_gjWP^f2# zj;AnXb#?XguY<%Q5~mE$idw|RlJ#abze=1M8U0EZDXB&0I`5sb*J|m8ni>|3%8?r5 zLqpCSw!fv5P^(_mY$YK%zaHo_N*skQ8TlJGXnk)!(Ze=79upIDhH`x^ac*v|Iorxi z!?c`{IAIyb48-JQxP(%OKWSZ+LycT z7cZA*+zYZgN$l@f)x;y;7v@EId3lRnDOf_XvxWW)50mQd`(ZX5pI*Y~t8pN`-BkKv zXO8Xn-p=*LA3qL=F68giE_ksc>0wLqLR;tBySmlE+F*KmY#?jR^~OXy3Y_;tf!on2 z)(#N*Y98(V`}duRO&lQ?e8f{|N;0i+R;lVe9|wE(L;;SDYFg>D$6-D!suEYP zUJXv<{>{Wotb)HOZgOGlac_aDoT|tq1Fx0x!w35v>q0?r%x~`?g z|C1grZiwS=iFxMs^4uu#d@`2DvO=@6&b9T<{P`Uj>`}>{#VWG;TdvfNBgb#lgt#A) zj_(1y4?^&8nr0n$QI(L2Og!6t)m!sMx}kgd+f$`4_s}K_SLh968&$vOyGPthbB2jd z+GYN5bW^pI`||DP^|ClcZ$?dy#-=@NIY2={QTOAASDmfali%Tfybn}X2KaKzhjOw7 z#_i^_blNjaT8`*k!@`JPx^&5Au~Mt1d0n8^pZnBFxuEvpB^<)gribO|t+K>8thja^dmu zZ131^P&R3p$^LLs2$I@KRu`L?Lo@&Du~u5CnzXY#7 zG`FzO)m;Z-K&SPHG(I(C7QCzxXgk+JT=p-ECQXysM%8;GhzVpAv*uoty@i| z`pWO?>A9e-UbeNhrQ)TUub6-Us zkF}p>VX5pA*IS(Qw5KyLFi1jAM&T)+<2R~6;ng1R_{ODM;T>0PJpOII#O2_rsno;KwoNuG0;oRtGrU9H)Inh<~S2Vmax%5t(=88G&xY~~2 z5x20gU{y~(VK?DM?7GrC`j1*5J#UHjWR z$+IU`k|iO70r17DbzFFPS4h2L!?(gq6=|E%rX$=%d zz!e%=+TMxoLZXq(Td(7+lmbH1r~i6H>;OFg028$Fy9VoM!*>nFJCsyZN<8gmLhGN@ zT4UXbgT$(l!AYEf!PJW{ce|jIQ45&f@%Hx4HeCJw>Eh%>;l5JrQPlCnd+8Y;pmu8K zJ8Z3MZ(oT>py$#Sw;6q)!x^8#1DPgmNxoI;C}b$NRJywO+`LE4kb}KfDLR%XV=hzQZG{O+_metsHiA$ zr+8q*qeRC`dOY6Iob}jfq&<@xH!o-1Df|BH-;l7f7@T{iK(f)?71sbXdCl--x5E6=6uJlNu#w`p&F8rVR`;; zd3Cirfi_e0>b0u_c#{AmGKLefLSkZ=zh-5T-q}aeH99^hx^6`*V4DsJi8`l#L)6gk z--l*w^&hNzep}w{)-$q1vKFbzq@uK6Jl{}>wRw{?&m(zxo%{pRBc7v4#m(BRT>1}_ zj_s5`;Np0fRQ46ayVI2C&nF#om|@oK*k|>&^hC1R_?Wk@K<;oW$5@NNy`R5YT6Ak{ z4MPCCvrSOa`R!IRhGsuc%+0+_Pfu^x-LDXByV&oGg=Cvw^EiC2ps`W8z*XcS4!b@* z#}QGxS7l|ATefXuIDJ~O+s?kM!iS}MY|MjQ^J|o{lhVrSYLZE>1T{6aWYD>@XDOQ! zwS0vV88~icU(=5X@%KMO$*$pi$&J$XbGJOj>~PcN)uq|)(NQ2(?Lc8`%C)sMe%mFU zsp;vh<)0G9eq|kJV7M@L#<@%-{<>q<jP z;g@^0mh=ZHDPQ7=X#Z)5uCikOOV&!%$J;ya=TAx|CZ_Bp1=)3rM~@^1Yd)-hg z`)#74qVhR8`7aV4qYgSSooyuK6coo!pWZGaBC>tY9_5&KxY}+&ZV4br@3tL`R@T-! zzkh^F%E_&Ftwu*jHz(tg@&oKe!*C{GJD-=4*?m&Rk3>^*NlK3R_P;;l!uDv(AQ4;Fyu9;{T&)ex z{e68exO7Uo&_^XDCG$XsyaRa3P3QmxJiNRPkj369ZSwmN5D;U&+56hw!-8QGb~kR^ zXl`k_qFA+lBh!>IIXT%+yDdfUxzj#+?fwcM2j2Cyx6ht!TACmC4882xgNFh5Ky^Lk z{xK=`3msHcR8DL+(m0F1e*M~mXDr3Lo|A|@lksGhneOmm{~lkq8!Co6C**gpi;|MtYl4J#f$|QN zQc_UdMmf-L$}7d+qLZjnf3aPD6j9!?u?}IERd*fyXGxBcykk{&KsVwnRR!w2R~uCP z=J@4np%Qz@SeDP7I(3TpX?%w5=biQ*K2a(Cuf;req4}#tYyndS9yc|Y_KO!3S4ulN zj+}cmavp6%zcHqGC1ZJhyceaFL8T-?K2#!GHqXXALmR!S5I=*we%tjGI&IkY5l?N+_@ubvV=G(AwQqt9+` zZZ3|W6QdNJW-?i|kp&1*5y3MG1X@pYiFeJmU8dBsnRL9qSmtz?-}ot$;lf1s=g*(_ z^Q5B_Ukws+NjK_b;OD1SjJ$g3gP_Hh>Pb0l^pam$kL%Knv<6DIkdkuCm8g_@GbxgH z1P2Db!v1o(`9Hg|Uw$*^KfCL-)Hnz#sNiNZo62`=WE2#R9p9|o)O@tr+1WE5jnbeA z?a<1r9xsRBaIZ#nU?zz^))*MX2W|oUn;RVz=UmYKH6uLeZV2TZ$dXvi+6Opo@!hl@Wh zD0n@M#(D0m#V}?49plZLH*eXpg_CzQ+1T8?2;JIWdw#sr6BT8bm+#6k0f9reZ{L0dAHJ;CYipx3L?E zwUNIMxB~PdPhH6O>FN#sbLVvHYwJ2FB-7#{xms{Fm(=NI_%wd>a_Xb1cHirW0H*HP2Z6qJ^dHpZ&na}~At<6TCv zdK-0c=XkF5JUc4%i7RXy&$Id8yTJg2Sn|r1+pY#3*#b2m&XGz>OTUR#xavm9W;{J0 zyZg`?@iB#epQgU&Qc_YAzaDooz53k{tr)IItdpmLwTYi_?MvHi} zmzQLtHb$oaepJv|!cI0QR`lX)J836 z9wpv*-(zWZI8-iJL?$WS@Ye+slcX|=q~DFPRDXWP$8t)EF*ST$VM94Ca zd~jgkq~Wm_WmTP>!F&>Oa{IXN)sUxpK!)NfPHK=|I4orOnrZBiaPXz;1G)`{IccC%RBY(26gEqyRMBzH?^_mP}1eEf2-r!^7i#YYJ10N<8!9 z7O5*&uS!6aI&kpd8!s=1loTFva`KN+QQOhqIC*&;U0im^$jaWndv_ZxEiFGkKk)$& zqFyE>+>NJ-G+4g)0<7mL8d_0F2?H-LMN3OdSxpT{_FfRCTMr-ZMq^M@SN{a9;WKpA zFL$d`#x8_ZRml+lo{4D(HaT&fc6K7T&QFn%q`P+QQi@jCsvM&vhGPCb?8-sZjzVCo zu^&5*QE2GtF=^}QkkQk778QwSTTO3UTwH_*{5&Y=NL5wUEknb-XdQUaBtc-i64w z59E)Nhvx<094i}JcUKq5<;#~-Ky3#G226e9xqj5wlN~q^!Wn@Q=QC$k`0Ll<{QUfE z6Oc4q;$>9q6H!uJnwpyEsgzpws}`AD0Dj=-$ERQDC<{HAah^}N%h4;=2GY6Z`k*1| zO_|SrhTu;7^}}3TT-heVPiD^JhQ#B;(F*T>|F~(~dKyheQd&ARH#Pd$xpTBYi1%DS z@aTD!HI^kpWR$7B{N%~kEsZ3?)^jgVngE6>+y!hFI6<{fUJ>3XiVOcPih94kTF970 zL`0w(xs^5EPxSMn*7$0^!}Eyng@+GW32-(t^004U0LOkmwl@y{d3?+5d-t3G+VUSb zdw58kKTlFnSZIP8nr%Jrv6zGdM{G%SxRrxh0ip%>luWqZ2@uIBQd zEbXqmXVjdxNMvMWw#3Wr#jeai#Wiftm~0yCdCzCGwxrR=zn55wo8JV9rGPA8v-CUC z)R!#^1z=^SUXI^vV0XgJZ?1q=%(DyEQ}sVd`?4?ey_M_w{hMh~>1@FONXYixyNjTx z8TXd#LD4upYe`BH-=F_A)@gPSic(d!YK= z|Miu({nxKLpepb%X9dsKXx7GSD^^>!ZtaFrTa2G~4Lp9u5}1NGwm45ueSN7~(+pU& zQv=4qXtHxFmBTJkJ4RHIH$!P~zfZDl?S7nc1IfxjH7%TjnAPRi3}8q*$J0^lu#GNN zY6W2rM`WN6yJ+ko8xQ6b6t>yYZBw$TkLLoE?ba&q) zve z+4hpu8*~>qn)AC{=j1tWExEh{4d$t|e zJrkQCUthT~(`+yU_|gomz+tRc)QFOjvK@>qWl1KZ62;o}tDhtJly zdpBapVuxe@>Yk_Pp3FqGhwqH}`0@N}oqk+dhClZ`Q;XrB6#e`oJv{|k@eoiP+bpLC z_Mkcl`qbQ8NQ-~<{rk0=U%x)o!#5bo&@nWufiiec!^S52mPK-NirzsZgXzIq)eM4& zkCoEf_dS^(tHu^)O6|01OOV77sn`QFUEkD1HDZA_TV!QrWsK3!z%=WWhT}r*5x~>SCWI5b( z?i5;DU(V{>jRYWXDf)dZ1&a}1LqbCQf_BNt$z@8fx_Nr;Gx`R4NW~ib?VGSs4%*h~ z_LBNYxlBAfQ_uNq z43feZq-A9K?$!jBE61wHe%JZ<piWJofLEhAs7%Kb5Pf#_|LIiZp*!+6&H(cVu#6z4n(yEDn+?`bWYUb1(bBpt zP7faE;ZX`N54<4oXoMPe-YayM9XX@uEjlQ%;KMA?Fg+Qi-${ym`-5ukCv1I|T`Pz6 zN)Gzk!s23nZS6kL<%#L(i+E03+H%rHJoI?7cNazH_hA&Pf6{oIg?>$4x4@u!L@PZ;D1t}w>SYe zegaPm86dy$=+RjrVPO-LiU>>ii3>|hDhn$*T#pYK-FbdNgO|%a+Pm*M$X3 zxF$|~W6(Gq2HBaJ3vjDR;BaA)k-KtMv0Gq%Z)!_3C=9ve_SyWmg8SM^b$NL{XvgP! zwMT%?$~E^!hbbs3Cf%=Nz-oUA3lk4FFs5_DIqY3ooF4iaPYW9Ef{%?&ISd&y?t1FZ z9Xoa~H~zK4MP?3n3c@2_&dQWD+@F0YUCc&ur?GqTycng8XNKgx-@V(Jvx;V9gM+U2 z?Fnz1;V)N!j-5dl6&X*QIC|!c!tJWd^tM|N0dQgdAp}}Pu+}HR(!9rB`=qDyp~0$* ztsXme%yM}y{`6ZzRC%|)zB`Uw#4!}&*p=hbWG^Kx{TwcQS>t|&Zw?NBt<1Fgt^hS!h(XofRuOk)&z@kToGJQAVL`gW!T% zlJ?f?X%Agqzuw;xV6XMcs zKEusD37CT34>@fG*^Sh9&(@ad+a)Zx^s3{odQJPY17efe6z4vJr1k)zElV z>_!!e;zRRm#d_%bF&_Pf?b!Z4@r&snKav1&i31jh>)``I13-KUb}(ROE+Aw%L4vYV z1WB3MVA=?O3G>w*7wh(8Wmzur>W2%Eo01IL&gQ47!%Ce&G32}YD&o3sQUe%+2YB+1 zfO(Xt`z^_gV6yB|)8otNUsALf`s5Dgx`$W~UDwLmTB^(g{gzf%`9(!x?aQ6t ztV!+d?d46E7Zy%u=K}CUG@)eVqlY{d!JlMbc~YF6?hl0jj0wd{)aT5wK|h~VR~ zD%yEG(rnAg3l6R+wa+$_`t^K$G|JpIsji=>m3!AUR{cu^pou3e5DiUDiV_^#-an18 z2b9JC(K*D){-qv7zi@KmPD~McG@|w?Q}KY z#KgpT^!bMt#4`XMDnQ6VH}(^Q^}@t4T%*bSm}Z9>ynmbJ(e#CZ_eLK9#KkPc*%3V; zAQ+*$BWO~oSwjlN`xb;FKhE0@L$Z%uu?l|?DH~u$tH`jOOl)j>02@lcD#eX5%4zDk9al5tb78#$+jkuulh^3YPfwnRPr=?y*+Oe142F3#QnLFEWetW|B zSRm}cGRzxJ(>}?t@NhIHKo9(cO+?dm^>lX5!%;2DF7rrcznSffV&s~fXw#8n>n38m zbZc#8(MwKQ*y0a4y5_0h^G2EIIg=%lEhG`qYWB2sFI-y2zoeuTA*Vx8;+#|_B_Xj5 zaU1dyOKa<0LB2kqfQo_SyGHge{vI0Q`~^zX$F9s7w+r<$!&#%eGu5E&9n)1sD&`+| zu%Vv^2h%H#gk5{e+A@7c89wLRQBHY{ulz9k=zUpM~v$&=eq_YT_rNn}8OE5-`(-hK8Olt3FC#EWmU zo)-W@D409H^<3OTUU08G9IV&n#6NlI<3nK-7^wJ^L-T79&(^C^ci*Av6Ri@Z)yqKa z9V+uHTE4xVw(}oY7duN$=uXN8yui6G*W4N1C$c=kjm(b3j1X?81W%N_gz$WVZKigh z4PJ_8M040ox>sCG>{*mm2i3uYn_)sg9lx0zxbFS>^;0mh2NrMT#l$uNrNnVcsH#$d zZ@-OVs4g<0n>He29pqN%J;#Urx;G>=bZhlu;XcvRD|;%7iniRmdDCG)>E(wHhZWng zBXzZ?J@<2cwo6OZtCt|2V`}#TR);|~#Fi-Ez=BgH$`EIOIeb4dESk_cq3%qUK>q#& z&~ZR%MwHc_)b~lZ?#7d+m)P^aaE#)os1jj>gW5BwDw@D@{RB^>Dptj<9~g-G>_a~Z z9v0AtBZS)D)h2A*MUu0=W}TnTLS@iKZ(s_0f%STdRf{h+I za>NptJI;c{o^|XD&TC5~FX`5;w=2AvyslpO$pik1_T)4&xI(fYZUE7a5#-Z1AY2(l z&-&b_r>EZ<(C|u6o1ou)N6sYGtbcGY6vBHl{qr>*>$!)xx640ifHP&>D9Bn+`F8{4 z`LcEbvF$%{WG#Og*XbnoeA|_u-qr+K3l`P#(%5%I=qc(Y!UZSFBPE|a5k%>TPJR2d zu&@w*eiY|GsHcbnQXb+IdJzx`2B!DPJ|r1KO7Nk90Y%C7Z)H0>@6EkFcJbEj+sE!- z)#Vou;3|e8vQKnvA@pxl0@3Kh-vT9?+PjYd>v})q4k^+}ul9}O5#^Ed={KB)Y2d2i zewR@EZ)RKO)6SQl3O=u@+FF?jiR!ktb_nN5LBW7%yN!q4^TRibWaAIw%qYEuSZhCR zy`@BL;2LoRA{8IvLDhW}+e}b$NN}f_nJ<6~1qoRpV_@mS5obTqwFxlS$8gQU*f{U$ zrp;Xg11}?F--kRJZ6!1i+zz3lL7+o-dGX=}p}9+$7h$h;!ziTT)z52aAjc0TSO0%Dz~PI zww^e1h6v|r2b|T`)^^yohlUV7A(;RRUd9z8YcT<(wJxIR&(KgFvTjgi2m$Xq!ZZzt zgn>zaPDy!zE(*Q=wU3V@fG#(1Q7D^bxgoFka_W1GR$UHEdIzgqQ<$o=|}xxA>(aGo}YdBAq6Y2jTD)oq*Tx^YE`}th>M85$G32#_23+`^mYv0b2vcQ>S{dZV=xSE3A|d>TwIU zU-RcPTv?dZ7beZ4uP-ItL-PWv7t<_1c9Nx~PcU_Wg(R@UzbnL07O|n$vYkaE`Sj@+e4w?Zm2UpMK+=KX}M&Kwc3*?#4Em@M^+3nt0~of3h6b@bWGoEg*Fop9xe#6C<{AX1eG)1?;LMxZ0ui}8?8JnVEV$EFlcR{plSe} zz;)rT$;*41S%Z>WgOuLl`azQUy36z?h@TVAgjo>ODO1RwQvFWGO^}XdmBNNarNI_4k4c@_Xc>1fh{r1=B9vB7sE3y_$*REgly=in_Q=uUP7Lj37(O*cy9EWt9o7qu6e$3dM4ial}iq$z}m zUIZpfs?l}7uaeaxv7gYej(8VEI%oqsH}_kC%V-km`i;yr4Gl`s8bIMn*6SiOi}ST@ zh!!{0gtF%7P?21{eA&r*X(qZg6VEiEVY&m3#28Xl8b}H&SRuBRf%?-i-?*F(GG&I7 zuVPKV4$DcjBQWdHXb*0Vq6A5sz&4mYP-TS^;^JhwMLM&s-Xa!xNEJyAcI1ja+tw)& zGQoN}_L!;f5*0l?ea90>iX3VpkSjWDK#zM6rcfALCA3;N(3wO5TcNuuE!_*MS_DDx zO7#39u3^1Z0wIGYT&CkBKu{or#QC0LH`52$3f=H#GC{IfERKA~KM1$Wm6t$eZHiOp z4i9>t|D4nePQ|r_j`i2@(+r1y#>;fRS<9XsZBzALeWwVjZ8hIkTPrv9RV6{Ae8!$( zMnKOBG5XpS!Sb@Q{qcL>t@Ixzc&ZgWmP}9V53p=bfe?Iv{v(&wJj#JnRI^HEX3Vc@ zX$3E?H|FO*%d%h3X|>|5Ch)|Zmh+&-+oYVmxXONZ<^8x|ndR8A@z*ivQa$n2=(O)z znV~1CaIFS|0&74v{GwgFGh(pl*DuX98eDtXjZUCC-B{0!szCqmyhD=BqG^O^3L@K; znlTU6g6JPS7&aZJ6*NCRKU8J&MWC1kKo)OHpwsni)XZ>y017^b6zCMr)UupKSgdGM@sy|M5hZ zSVu(XKHQDG<*|k34kMDE_*O^)RUbrb1AtII{IFVtA!LeNaTjtkejT+R&ON5gekrP% zYxkkPzFtQp4T#P3{aJ$pD^@PAUiBfoFx|9uk>b-PDE3cLf2pU<2D`iSafYIO6zi{T zHeTd|(@|4U5YoPU`4x43adC09ckrx@WB4Yuy2*461xNY*x=!cT1uc06Pny!AE2R;VD{+{=XmotusYW(dWJ8^wd-a4sHJ2 zB}EvRqVMj0!Drh|bi#bfM0$kF*7IWwe( zMb?}xj>J~YJ3~-1Ll3xi?jFPdKD!mmfo#}N2X4vnUWCtHKi`4sFLm>M1TV=v6sG7S zaDU~8Z$*pMO};Ujd%+l(I1Gl1Q~e=lt)$&) zp04LD(R_cmtqZ-Adz45d=|()N*+5qNZUKt>QiW(3~FC~O&SC*A6H02_Q(hYkH zhMqV?Vdd5YmFmSikES9d z+jr~`12#5lhk}jt{u#idD4#?jgSNC{-27{A?-$6keuSCGY;YM~?R%Rc;XNc^wnd=O zoVN?M3=I#neAC311e);`=m020T;Rfm3x8qUB+CSf`ULsNx2Pe`3=kQfRL0Fa&+ePrFmxMm@ae$!ml%wdkWk>S07lqYN!0aTzn|DV7!c}O_4Qz7e03R^jwwbM9YHdF`IYDBg z0_$sP_L7m2Q6o92Xaj%_gjuq3Xz3XA2}ksX0zagoAW=jGUQ~B+aaovc(z5CWHfXGv z{?o`(_2HZ^QyT2^4EuEv;;Ty{TUREJEUZk|PNFq(et1qVYDagkCQzOw@=S&GIMV#2 z;QkV5>DU^G49BP@CS27EJK%y~MN=-;sT*<=5u2-@_nn7wl-Jfq3sdD1z`SKIPGQ&Z zup7*`k=E2|&VxTh1Wn>M(kq}y>7rhxzcftRRuB*Z%;umUJkJv^=N8u~(hHiT?tYSNv zDhA^e;l#R^`9%5pT8J`d0a5m#D`uO(hpp;dWr>ND3ns)N!bDJn0sOvuWQ5gJxqlh+ zJ(fB>y}fVz{h7pgH_l+i#eZob?r7TF#qyg!n@B9VPw&c*B`ud(0|W&i?VKSVU^Ah?W~sF-U`A{d5(dlalh$*0~^I_#8=u zUO$R0@e;KABMPQh-*9u%aUx=i3@I#gNw50C!p&41H}B}*X+!?AYq2Ro(+!qvL^I^4 z9&qaWm{9Dp$gV{`82F?BJnT|+s0S=>^RagSXtA9n$SZG$X6tUGf3hbQF#@~QS=IlS zhpPyWjok(0XERw$mF@0wfv_K@i>(P!4N}O~@&|YCzJ$CzP~r$5Iq=-$tFPN*FeF!i zRv@4C$UuGgbpht*+z{`HXomlF8wc5ewLK&;aUX2UfpK!sk$mXZN;RtZ*F?}V+XVYU zLBJ{5#@5ysW?O?Ck8kf5oCRLGv6@G!R|MPGV7sLx40HmfcIl z31S*%J$sj!~u1*ri0FqFh+wr)+Zl;6@_MV@gpSSfo`Uzr@qESB2$LZn$W0^UYPNW>W z_%f=Y+2_LtVnP&kbuVah-pucMGGrRiRGqIe9xITRmDP2vpV@Zn=W5i5T5j+@8Xn09 zRFYq9m(OCKI$>+{036DAE{@x;yJ1heY4~eHf*4pG4eaHQFcaKp7CoP~-P-uQPYDiy zUr(QgUS2n?ama2KzkN;~vzd5S~;7w@Eu|Cz0T_!O+; zqG&Fjdh!88vJnzxNaHadl-v$#Sy4Hv8z8Tsd?n-v(Cpf`Z{Hgh1y2Yj;}0}GTv8#t z1Dr=kF4jRS1qe@yS)W9~`mN_i^5JG*i&bIcdDy%kG6U9w8;(FqkD6G@zTq&V%m6XO zaq`I{$BL#Zjvhb${I~T<5}5#=D}DM!pn^}4dx7NI>#Jo)NbDG0A}6xONKz9P`_7#^ z{nAq5|HdIN(&xH(=>L`PY!lW&^NosG^zVx42tt4%AMRq6m*qDvEG`Wv)@7RAyE2_b zL}D;%$RM=`AH9Hi9ps_Me!1bF`%EDT33CiP3_&qvy*AVD*nBE`Xn4TPNST!j!|=qw z^kX?AUbXmB0?8xc&!t#I$nhC05T0|mCyK|7cPjlB&M>3~wiA`wM} z@#LNXR$nniN9bRUvqPL48ug)d;Y`<;?%V)BL5Y><(3Sp%r#7E#cPFX|yslFX%U#gstS=$e8 z)9?OPd#ACu_!cBGDrh4OxhoOevC;vNBv1_SY^v#`Kfeh>eF!O}-fvMBHj;!Fh8S`A z^ns}y6&XF4G}N`AfdK4zgt9eD=#p`rUeX`|!g zi4$3`5G0j&Mg8eVTJaQg+CMPFl zO1A;CHa9otm6z{;a#{!x6r;!@2%Vl8j8Xq`@@lY%JEB1@8J8<=3s7ZQ48PmrvylX5 z@*G%amf47PZ|_0^xhe^QE>taHgm~Owq)5Hvz>5x|Cy`6tj?@`>>N^Zuo>>(W5*4LK zic6X4G7QUtW#sW9e?00BK|79rG~U71c1hJ#TW2f zgv(j`t5TqvQCoc8xPC;*_Y<-G+OB*0j)6gS!)pd_sB)Oxd%-k^=}5%~t*3)w8Qz{5 zs*_2It1h_EihTIA(oq9r0<~u#rt7-&AsU@U?encoigAL8yFir)#g(t7w$?L~>9R8G z;5G!~^x1OEm*))NT+R2g3#5q>gpHZ%4sER9~I z!{E#B@=0ThfZ!gA$`|r53+5`4W$@Aqffv6g=>X-aeS|TESx64!*+0rie7JhOe?9g2 zY)!?ioo==Cp1c*cT2;&zT{}jZwBHSaA?k+%HY)}r&X1X{z3kUu<>HceklNS--jP#w zq5l(^k3Kzpc?m4WMa^Xn;oQ(Ls!Q}DHhxToOEbS6MUVWbsKX6K?Tn-S?5zPSz7a1}K}4aA-s&LQ0cDsmW;;Pr{y^#spK)Xc%b<2D%y!u2A#5+XZsn15m_3EQ)ji*7ugW3^;!@8*MHq5GKMfV(uXY?f z`4QE6rw+sMHXf6IV?|Gl$^&ogr zM=U3_=HTC1Ys*knOV24^|7CVE31I3dKfhXXCo8tF(}Si2BIiWV4WPQ`cqIZINTAON z(PMF)ofyeS(y~yED&KqRv9s$CP@v49KH|wTow=!RpwkfW3DDGLeRV#2(BAZx02Lwo zEja#9@u2$G=m9y=<#eLS-e^IU=^7hj*Sq@8tp|vL@x7D~5^~6?Kjj;P?P57M;;+#5 z6LQjrw8$!@2bn}Bg5~EG>(&^o*3R+Tsw(jd7aUrx)Tp)+Ev~Uf`3<681S}=swW1BM zg)z)SG+4F13du`9q7_e>k2K4Vogt4=2;UiT^#e10v>7uAUV)H`yu1`u9|#@DA$f>9Urau+_2UjBhr(J;WU`;f4W0%H#TQ6mz<*@{fK z5iUsLK4x&FdeFqW+;1e`*|8hbfi^P-S^^)9%ed=2;cK#0P38bQO0C_9`?^45qNt$Yz4mH;a#G&X9V~?znbSGN%3NJc|J5FLv2csncJh+4*=HC)R%et&n92;PL9TMY@>5; zSfZQNBG;c-S~@@Rh;@Mqu%C|Z6{gv=A>+_|>)KJ7sfHW{>N#W7%MC@*>Ds@h%EbJ) z-9qUlW2xKAO4YmTH`EGe7ng4L;rhsZpq-3SL!K0s>Kre=p)veuLmT^Au-x0*yH!uZ z+ZEx$v}kynFo2mJA4=A5OJg&VF*i@SE&wJA6S0_f5Tnk-n5j=J15!ezAH|-3ems6N zVgaq88xx9AnptUO=q3_>rYV$n)1KW8Y1nJvjsQorX4ctlyQzHHK0)pWFAzC zAzVugm7K^#dw+2Q7k%YDMc5Nf5auAh0Z37pc~D@Hvm&UL4&h0wm?;5-j5~hawrv|R zGgBd;)Ciu{(R<6%GUG%lqEiwAv)Mpgdp@SLF|cCQf)*2MJODuL^|w6$I7e z7)ymJCe^R?`PQ?c(rsMW7L!-Al<&Ur!3b!_R#}`dQccb39P%3UYXGZ-$x`~;Iy%Rt z_W&st;w2y3h@nfzKilOgAN0m)?8%Ee*cdIJV-vSab`wP}pWr89L^LcMQ5v^S|T03t79>8xysH`33+X_4_euyS3CL+vJbTLhKM;SF)Lp zj}NvtXE9>7l#mFjWOs*6Vfa8NfSDy7IkqbS<3MAGH1Ha=qefz&=9Jhadt);*9eqxP z{y-@T$Zg&>J7WUj&JrVR9sHmJz+G3a)zQ=N+&eHk-2eLP zFQpp!Am|-E=oGk`vo~S5PL=?8Yz7upX7OYu#?szDM*!?Z=6AI}I%kfp-_h4+UTP2p zKK?s>fJ&;`aGm5MF+$44p_QY=LR!gXT;xoq-+#>~HkM^vpcF*=M2v(b>%pfe!;D({ zFRP<4J0>P3Dx{+(X<$$dzF`5#rgFuDTeqG9!`^~8@Ynbo^M#t*h%vnm3aUwohtYxr zm&EPel?Chp+E{OAMCFkq(p{GA1=Xb%wG$#@M#y2Q>mO}(n>|PK;CRCK`+t32LZ^dd zQ%-vi{x?{*f)>5OQ3;iE*{AS<3t3J}7{yMz2 zQcv4qEuCC6ccA4nY@6lvY@|farSOb} zWLuJk@e2B1s_6=wkdNV?zF=a^9IiZ z1TA9P!=rSu2QX=dsd}_JE;-Mcze_hHc)|`2|MT_+RK(8+?4Mv{ybUP-IX&Gs+ygdT zUUBhOU~L~p(YmW~^)>z1y}f3~pH^HoNR&aqxr}@suSoe(P)UNhGGcjo^nPrCmv;O5 zX(eVzwK66FLd6?1t|^B#>ox#?n8LLI&r0~D3@QqfNj#=IM*$kLxiB;lg=plK#+AdB z({KFz@Mj)JlLv(oWwaoeW-$b(fCyjZ&}~>_b?dS^^|J@PG1qf zuckdnPtT#h2QOAi=KZyQ>J$@=;U+?c&n8|8^rlZ({@W9a4r=Ad$iHp{7#m>}L1KhxPC;^+6plNz7mAY4 zfwg+f5E@uDzmh|H=6^g!ck*grnRy(g0vtyP&m*$Asr&Okvo}LwWiVx=FA@CYM|ouB zGcj=|BoxT>2=6apPz@CU&L?ErZUel}Xs9z+6ui`xlI?n4YwPuJ4Llz}84)2Nq1S|FK2CJT5`<}{G(Qpc`Q_xZv5dG&3S*fa?B$R^>A-hJK3>w6g4uN3pxDPAHD2h z@euE|A}>M49LX#eW#Sb(c;mz~u-}emj1U|_DgfQ51ZtpFWNDcgVO>CtRf%#r2X>PI z8IQ;iA-@Dexd%s^$TY$r!q2;=q;#U9SmzH<1Qi7Zm+UF;&`c>qRM8U5p!sp^6~)9# zoZ?QF0Hi>OD5O;^#Ie5EDdWWm5z(h}n$@OY0mjS>05*tZ`8a)-Zv+6+g~@>H+*<;$@?_mG=Hwui>(t$$)72P%4`N&*p3cGP1I|60w8 zQ>Ghmy%Evr)TyZF;racjZ6QCek%{m*&tY4YO$l%`as`JInMI%U+B3o$HNEtCcDuc^ zt||l5WD&~7&p7q#bu-IyU?&sv^BnVQ5O=$=raL{K5ebU-v$#?&Xw#{G8nz&TKZJo< zOsF~%YYC5!-+oO9-Yppg1!FnS1cHOldin9PH<=lY^#;6ZN?crAGRW8YVm<9s^=TTb z>5>~8SpXUuSB)#h<^;Ljk%qLj7*H<=zcBBEpLedm?g@tEjt_N2in0f0mK2-DK{B#U zM8kA)3PshF8l?2XiydZWXRSJ^8b~${{M4s^jf`y7Wk0DnSWr+w^eL|axMSxrN@k=1 zg^@98pi_+_PwCNhH)t7@tZI35!AK1ucm5Gt9GDy#cIOKW`?>qyk0%22VRmw{JvgDn zbO&*+fv7X^{wypWUL-_|enog2I9CWd9p~VXOW9T0kokQIElS3sT)Oi}o= z?@q+iMA}!fI`_quOZ;i&^1Wz6mO6cckuYK%P)Cdcn-5L^m=e)v{k^h-@Sl}sIlP!%)wxz4Y;3!5vIt^w(Fgn8yZvGqvQLfpFc*f`Wjxk_xF}q90k?< z-z{N#A9GE#p?}1=k(Upt87E;a%>xCE$+kUqzkur+E2}I62H>19bkrLeY1l5jOMiY|JK70bYRsBQtR1ix4Z|t$NQsT$R3{A<~b1o{X3Z- zuO*lp33dJkQ7D8E6%(mr;Z4(zzm7sakjAl~Zf>aT^QOY7)txmHzgb-G_HRW7rB7 z8ubP?q)G@t5@MJ8D8DOFb$JDxok*_lk#gj&oH}%_xQoTfY?Jjz_XRJgH0Xf5k`w|l z9?|3+M9l-3i1$eHU4iEX00zIqs?BcL$R2v{&hJcHN)FID*lfBN?S3I*#g8`hJSq9E zoC@f^>a=p>TSVyKMBW0tB4iaH|Kt3)`eqdCGgY0rdOV(;QnhNCllb3Zmq+@GNk{>S z->!*Pl&Q3dW>GIOf0F_+PZeE(oZ_1%m`p|qpNsuhK0uxgJ40l{q^Olh*>HQ?{cR`q zAhQ`6XgKMa8gqn1V}FiYdy%Dw{+BBV_Teu`7at#gq}dg6#e`Csg`B_ro)Jx8)7*@@#${G!^C zD({H+zG3hhw-KFm!u8*He&BGVu~&AK+n)M`Pc= zM|+g}gO>(Ca}SO(2*Bb6*L7RA6k^)X#$Gu7EY#L~r^un7yDo6w|J-#z_SR-(7^vTk zSfOzIYADl&KUr8FGf9+fNKw3zI8-Q@o|cvepg@;-^9GmBZ;;sxwB^#ly&&2nvf9_i z?WfNO3qQ&!P9w#3*mE%-Fy5a~%1f%-j9RmvX8PDmb&tR2iD@h-5boN$LlnrRj0&`k ze{9`)8|K$hWordzv<&B$Gu^Ta1*2;6<35i(8ElV=9pdHn<_b-~#tJR;aR66jLICO>E=s1vWji;c02R z1!uqAeOu^^pyzc&YU3*iDG9$%vJ%u34d={khDMgzkcFLnJKjZ=c3N6dHtLcylSIq# zrN}F#B^h*{XQ5StV|j6fQQV9E28UPan>Q=uV^uC+|4j|Z3~VJ6_-ReuAvvAP>y~-F zzW>Sb-GR>1R7Or(8XW>;4W!jq6=wt{`Rp=C{Bo)LO6k^v!ux?XLX&vWislj6FAb1- z2n6q;P!s|$w!X6o&`$604OOY1Yck3WAdMt%jU&i^c&BUktFW+hyDG9sbn^T9^?~>I z2C_q{_w}ASnUTn@otZ0yWdwGGNXyE;Ps%%c)k>AX%=lWbi3pysE)hPR0D^wsvZdSE z8x=gor&^ywI{V?~7ZhVM^i8ldS^GaJ-Y+PqK18+Z-~=2KA$pJRNKQ}Z!)3xjQlmjr zMU*@nG$9nQJ?F&4)=vzzlw_r?Ej0NyFE}xDk}vXx?aVjN&7wWDzuo?1y=_&<{no9k zf<-(-4R{~kV-1||4SXdX{J65g!K_y<O{KNM%r#&4^r z;J1>YS_^WlM*&qGYS{-JWF^(xcDn2Hl8$!{94ZT&ms%?h&~tOwhYvyRvXfD?VQw`52)eOW_IEx9k%YD^m$Q&Yq7C%>h?o$*>18!=zBwN5rA*rU!h zI}LHGTGh(Lt0ke}&KjamzWhAHj-)!N!OWLQh9MaxpGEq!o;3^F&1dyyQnv)J$yzw2 zE+phoN^PM}vGX$Pt&D)MgvV+$xb;>)Yfv{T|AfE<)L~)7Z0g<*TuA)2$ze{;OHjt! z4J;RPE8^y#i+Dq zT%g!BLpJQx2cV$LY+`{8=rLG0_DI-=z$(u8b<()c5rs4dQ+TX_bLCkLf03iEZ$dn*sU5rlR(scH{@ z1K1eDT7@a2{f9DaXHtN|#~}~l)eYn5vW5r8|G#<3v=HX zt=pE9-NLyhUfz_Q63mXVrrVUau>FreUa{r;I1MQkm!4CGN#}jAUQzHF-1~i#0i=Y% zFdb4DtGnNZNLvpK_PW|8FJ`C0t|IqyP#InXmF?`0lrs*Ah4PE_L(GQ{e+VCfIAtfJ z)rqP#8dYN=n^3{4`+Y_RN{3eeg;1y)nWcjtmS#Z1-G>*7 z<5Fnhi!>;D6^;Mg+*}QU3YIGw$-q3W;e|+*^n?+!UcBA|Ay_Ks?q-SGzpZxaL%EoN zi5uhNhYw#Xc6N1z05;>tN zxL|0V=B&UbGCMvG7MnR!9Aw`mt>9*05C*yZIA2$zIH~B}OJ`FCedUU1DztbYW&~v_ zQJ`$X(7rShuu-wUU~WsD7gz~3%l6gh8C}va87bhUNSB#{aeQ12+6H6X%vn{^E&{8U z$Im?l?d_iX`{`Fw_U_uHlT?+%`y+Q@M$i^oAmLRdpSL5-~xt(f0rV8gS3ZkTxVEK;lFnK(8pS8Q9d{_}gfpJRciGD=D|rH1>V{3C>^Rmix&`3QpM6@JD(qr`9i;d`j8 z`{Xu@TrfhGT`(*C(d)HZhU!& zW>d6JdhFq-wPbZ}7%m#2*K3x?`(0g~JTSE5k$_i1u;Q69s>0?F( zI`?(_@IXoZUX;)4A&iC-Wbii6TC2o}_UXdrq2i1~hq02UA?$Y2!#Kuarz-khq8 z!LTAc`}cfSLtO97;LP3cRcvOcqb`$v&^<2Vr1~y~x~5B6M=yjHlQ9P5C0yuzT=RaZ z7q(Gj_R9vX$j`XkU1` z<36M&y9ak)&(P1zei=)%eY=*4+k4bzNr8?-rT3qxX;K8nbJA`Ia;hX~xi(ZC@gIeH5 zrQH4z5VCo5V8A5|N7qoIUSzEWsa(H8R5}a~U)0vtrmd>yN10VeFz4a#?_ZjMC9y~H zve{JznixK3EZ7XQ-YdDsA{4F&n8E-j99!4y8O2F~lPwG{W6#YzIhP{?lxzo^T5|_G zlXsE%Q+oKLk`8*;lT$4Zi_8~$%IER0FCF_S?Fo+>i9lC48B6`b$hIBLw~?{{#nwx_ zjxpRUGA0?y6~-OuczjV(4F`=%P2JIn3C>$(h$fFnc$#5#4jn#mqVg;IF44Z0%+!^Y zvv2wenjp2^-9n#eJ$e1SX<7oLl<;|q!VA~I8rPsI5?ao(6-AUuslYSqyg3lMRl}Un z!uAari+f7H%sNUc#UX?^wZF8J>Q71aeHk7$YIfQQPi{h;79{4$yr;&nEvE%z z+7z$(pwtUZJw~VQ2IC>FA(j(PzOax?@OxqNoSYo8l0{bwyqZa!S-;_H8&$E%(s(qicu#Q=Ap{4A>k}s22Ajm`@QfG z3OC%1;BE~iPCN?+I#6$GNHI>q9X3TnYF~$$A)|car5~imQfui=Y|#kbPfBJ0fi}_u z`nB{464=mi7M{V~3_7=t%`-tO15@byHcuU81Q8-n4{-M5);nIe4HD&bdwV-)Kd6q& z-%UL-mE*76BU`U_^_n%2i!q)@!prMC+jj51X5v=(QswdStu$naeI73xiZKYRn9n~u zBAg5<)7AB_Hyl>a$tv~2VtODM1Nx&9mCXjVFTYsq0EL|h#k2&=^E zw6#_GR5}Juq(_T42No))SE$Q-(cZWXkga*LD%ZM=6L1@fb4CS{i=asW-}ngN)*jF} zoOKD2FY|H5p8iCL(d;Hxf4+Hv+ToBc+Secf%)SsR$fG&7N8SUTw38{1)D}T;k?$Do z>7nnBCP-+HP%wX4`goPDhp2D;MwF}6X^YFsdc3nsg^-ClCk#hW9= z%Wyy!9l1Ffsha)-M_arg(Sgvqe?)v{r^cd$ZvTd#kI#+fg6oO{=idNuH7DzY_Qz|YYmAJH5Cj!z zx4`lGPba@5wxb&mRb!k;*q@^}Ai-)slNjEKA;VA8oqe2R_ z#o=jD9=G>N!Fcvq8LzPOGw5q1Mr0gdqg5Q{cjd8C0SBGIn(bp_ki%f1NHX~Ydd6Q(Q$gj?V^I3iCr zbhUaSa48HQ0(|pxCLnmyc0Q>7oawe`XBKMM1v1#@QhiiH#5_-Aq?@B1A5-X?Rx$Xi z8f(f?7?(XU;d4~gfSu$;X(Ovh9x(8CaMgRuG8N897Mi#kEqUrP){7es=CEr%obmv@E7aZO=lS$W~W z>M{{q`gU>A)xU#92}GfDMZ@udGHBM3V8<(3AWaOS85nFwHH2`cKZ%qpb=59?z*Q@% zOF>NV?iU|bv=v||)OP#SY0xsuaw_(X4FHu!IGVp}-GXs?PLXygNl$KlzqU5m#1>io zCkO-$Z0=T|7(1X&&AK#T8}n_CP(+oS`rsSKQG*8qPv@;=gOf-&`$0%oBYav*FXnqe zZI|13g!l?R^dtHlhK<#gdqb;Tt;dPYzK=fL&eF@8=}!9sqM%@OBs}&-_gMWZhyh%ne>b6 zUPa&4PfAXI{49Ebb10F~UH>&)@u~fbXQS``b9rmT09#ZAV#XEOf-x(R+@X?m?I~#g zmYaH7=;PzmCje(3q*~Uzy`B&`?gNPv$-CUWhc8?gHrsK@PZE)eVXX>^rbG*G z$}`B&p_YHxfxZ#~!k#DQ^HIR}gyRZvz!5VaU-Jq_6?N!8l28(Vwalj>d>*i}9E9x7 zVfB=VQk>{T598x)4vL@>NjGcxNwhLWf>NZdid@u#Opqd;;ktjT8ahyna)|0f$IlWuL1x7$tx#JYB;$QG&O_ zR>&YvGN=VTsR);6E)-Z@7_4iG`>94gd5Z`@+4IpMfz`x{dNLgx za$?w6L71whX!N(N!;BmD29KjzNOkPR2g_Q3MT<}?#YJs_mQ#oX*VTd_(t~xipP$4^ zNWM9!$oMHoFp*a^<4dkg!}Xh6>FYp z9aDKOh?GOby=%2w(CSNicKc^Ak<2_ijbHuk7iQYZT)eKqV32SiQIoF%WsBx$OBAGZ zjw|TR9BBY+Inu$|PnKE3_Rk2NX$<|E!le%GIHK^$Z6j0BBB%_^udhF4j$vM^*7;29LJDE&}e?BdqsX`H{A#F5qW=>5SGSD~Fa7*U5se1A8 z>o;wxK|R{Qg!mN*2yb;db0OgV@p&cIX|da0tU`Gb*ygmN=;b1kG1j8XAxJZJ*X%%w z-9bNbd3*|T!use_$j$y{kO|ukNGL^-1WYjcO3&KSv%i4rc9VCnHWhB`69ltbz@iAu zgha*tMt7N^tRQ-wBpbE)*<0sr%bJ^L5;i9VCkXwt6aDgWj5x zEAWFCM-C&hz{z)Q|uS!A2~TC^-rUpz$dV%&U)fpK{s@uuBm|yc3y_#2Or50VSt`@oFYXcshtcH`%Y&(2FG%joO5yTUEvfkAN*|>3C zkPZ^MeJ-x9TwbqKq7{yZNcy+-yg-U$FaKKOFZdyZ$jDU?9Mkvy7&?rcVF`_g=Tkx5 zZ_3OxI7BH>eI&5Vq-#0@i(HLnKS7Pa-q5-^CxKh4SPB;=fB@2$lac-e&;|Ab5MRk> zqlhAEP($zs=4Gf^5#4}pmLG$M?W7R{kIV++n5mQ3Nl2RJYjcQ%$PT+%PB>qvpo+s& zK*etMWv>S2?ahIpp2Q>cq7Z4kR&0ZNL8}jNXz{2I-)$I7+TUZtmR-9O?}>OJ3KhNF z94jf4L$*wxpJC=$GP|9)e%=K61)z}@+Q zGZicv0(O+AucbdN4H2po+Cr19M2u{hy#P@+LdG{|RjPL$!N12TQ|-qxA)C=tL)gA~ zJo_~QMPc!OaDrWGzp&&MIssWcoH;stcqgM6F&cw%H8pvG`Ow@Ps;mop`aQ8xp8Ia( z#i<4$Axa|lpc*7Nwe{9{(mPJd_6p};DbGn}7_E!ak(F+XOUEE!#Ui=)q;G0wrXM(> zG(tgV|C9FfHdyNt0F+XXHMkQ8f{BwxGjnq&e;>pRUqHJwWMxmJ27$uVkO`&PaUpx^ ztM@eY(aw7CHhRqpV-|48a;UJC1(raFssI^2KpG*)AnK#_o73V)j<*cj%$ETPMKB4J zrt+bW*J4Igic-W-gv^b}R}|M3$LID6Nr$w4)M}p$^_8e??6jwY;#Kx61Lhe*k;BU1_ILN zwAXfmr$PFHwR05v;N#ch;$Dviff%VHMB|9e1{_U|bQ08=l24yM>`EvMT;EF_zY3V{ zy*UDuNfNeqPPQNgi^Qbz7=Lz14wz@a=M!rv_WWoJ()-<9Jt3`Q659TeF`YE`r-3(XIYMec;c>I81_N}yk7$#Mgip*uTiB#9j* zhy6Sb-$yMNhEN7{sK-4pwZZLtr*e50na%nwOK2-agkYg$9)QG93o-%~LAED_72(AA zmZ1gNb93Mt-@Ph~DRffjYrQJz zxbBamAr-LszP8+4)IYfmXfkL4p{3?FhQWl`o66S4g4aKnaJZ#js3fXWUI1yrfz%dT+&otgeWQm=nv}pCxe?~Rvpw*(O zQkcOcMPchJWtizE)cNvRC4guIwole*7bdZxpW!~>KETCViPy2}y+~f1fiq|K7#`3x zLS}Xe)d$XckgZjtlRa8%UP8{B!d?dfH_`=mxky=2+*}pO{Z+RJ^`W+ho5T^}6WC0I z(gT>RJ@vi}JD?B2wiJ4Q5@Ps)OPIsNk0iIK6s<`=7};&c=NtGy)f^ zM!m$dFPn&3j6jW@y-|oYD$z>IKRCI$2r*AG)YjhSFn|Su@;v1B$<~mIRZ#??TnD7^ zh$CFn4bEp&F{Si_=r?;FBr&o<0vmU%F_`&kd2T6<`bSf~F9OjG7_kudAS zzpUT5@j~^OcDY{+JbeVfAtiJnhC>~AMh@K}aikoa5n*J(C#N*U%RryUCXOx9^OZ}q z5#%1O6K2v`(2I^6j%r3QTakdzN4}_wQlkmwC~S34vfo!k&uF#bfh;Hl6r>*7Tii7C zBRniIJCm)}qih~YoB(+g{89GvDi)NCj!g>VR zflqKUl&@gm895Bej4P#Gkijpq?F1zN^AU&L4o2qNyn?DCnD;Y?H^)9UREnu;$CJD?$nwg?WiUqKcN@6)0fY zv32X^)Xq#Vw2G)f9F6k$Z^pEOcFlh|O5Z1o7cr4=GETSDsEXPS`L!_7SYV`x7tNk% z)Sm{NJ2-818R0sdNN~5GH6FnngY(?U-y88|rh)Og*%qY2PFz!DXoymv$Nw*w>R`XGVMoDfWO} zyM=6f8-Ldva!4ugx^BLQj-xZRp{ct!paxOs+ct|W!qy_c3;Hf5a^H60-L(k3qTyqE zk-ij^lN<=7LagFgQM~>PY+KU}aI5&Ot&7tkR43H|{amckt*@2@+Ey;UhN)JUidg7EzS*K7O84Vc&LJ zobrb^i~xMd1FKrvhz3B{kVcPw|1K*c@^Jn3!>>@;vwGDk9O1+ArhEFwkKJu)9#l4f zByrm8b0{E#N5l>o zD)#x8gb?yVrIY{gDSWm(k{>?>8nh0@GPp)$_-V!gsPA=3>?-qBMwgMNVPU2d+()GX z|H0v|d%Oh?*7Go;NgUX^H+~gVhxYFm!VZ@u3LT?RS0MCQ4(L;PnCN8@Y{(rd4W;oU1i;wUl1o1imBbeTJA>={B9Dy4b13fN- z&-Q{JE$ts)kXT`d6ISHxkn$4{}>oah|&mX;K`d zR8`8PB5q(1O`5%74~w~xydD!91@4SlDJh(+b$}?$kZr(!5swUh9ev5e0Bp3N=Md8L zD%>VH)M5~t9^k(swc5TwNGytVQsD=Z6ss^~Yv~uw#EVx;5x+w&lHEs$m7`%QSdJVy zQc<1@0od0v-zX$W^Hbzp*Z`!XEXe6bCnulh=H_Cxperu_Sz+NmfZEuV8@U7-PXofj z8VNWfejp8@!930{?{8a}PsP?Fs4WvXs`bDBei0oS(bF;le!L%PwP-O2{X;>z>JvB6 zxnvF}{gE*3fi?;TCt0_G? zWqIpX9~z_7=*MMi&-%cmGvORLa8m{4BV%KxQENWKaS;^=p@gJtLA1d?gkaZ;x~<=J zH2T%6SAuQI!=NP~s23-1lMzQ#D-QH>0%UlqsQc+&Ualf*)GaKOSKowV`ZC%h;<6hTwe_)cNF2gGu1K6RSqsNb5_dvqA_Kx9+L@SUv+gol+*%K! zi${)*qGr!vGKf^((aw(-p?m~7kY7(cipKDIEg8uxsT7Ctk**x8c$M(v>}ap`APy(t zMS&zaq#zS4vK9T%^Z#;O%)?WDqIG%OJdUa=A?&F@eisO|oN>ky8CMMq_~4Txm$5T1 zA?9RNFO(yJA0bMC3sTKBBU;si4ZB$)9jkIGMlD+j{LFa&^YAtD z)*_Is3Oo0${lVD6L@FGul<<3V=wQ#v4#-(Oq*12Pg)8$-MkkZ=p3(|O6}gN<@f z)`?E%?1uA!RiY7Z=X?qv7imnHW#GPO89=}AAd&!Ct_0Go14~ALQ9x_;M-_oclQ5s0 z-F@?v+KnWmHZ?#4H{GruU5JCUx#74}g=s(v#K`~B(b7g^B zBU6DD_dHk=7Wf=u%Ss?m13qQ^h+ZUsL{!6?`zww0$K~RAWmGoImy#G7*?OaaLM~*T z3w4>ZCw&onlffo%eP7*p_H}d^^H5ylZkF%dEsWhkbx|VBUEygU&b_+V*Qp2%U za9P^VHyUM)+(-W&t>>EQE34WP$uS3Ta>?AzGuEJeI8f>qc0qt>2h5QJuhJ)={@Rcw zOa0C4=HlX@sF0ORbZ-Pi>0(@kI;g(v$<`_`INzI1%TMvTyhD@eYp`>-;P`yJ$SFnO zf?&B{`gpw)Be#GC7ySdfZ))aG;k*WYaOq^?R9*Xrp!xSX(N*#8-QViyoewgo?~}Pd z1FUuvCy(194NX{hj~ z4$0bK`DttUNbe(T_r93a)*Bygg@P^*N6dZ=w1XIg%88x9A`8BM=r$^lAc@3a1SaI( z^W=mXwi}R6S@c+YS9cvqA8^wMIO0<_hV;<@tO#l0Q~3g_!>dGW-^F=KtZY>qlsv^v zO-(MkZfr1LUO4muijl83yc@U^r}hf7PON$26!0K<@(!2yPn{Y-*GmuvVfK@CsNgaz1 z!KjiOf`j~egKJABsle97CSK&O`}xK`o@~sq%|sBc*~=r^1r!-La}UbyC0=fZ-5|+9 zd3%4O4C3-69Dmoj?f?RiNU5Ov@biWyC-z?rS4xhAcMgQEgZqoM1z71$0PPO9CMPV+-SC zLO`VkIQkQY8iykv3G1RfxfLw#eF-^FGD!!aMGn)3Vy}WU^9Ilp0jN)+^vY^zWU@yJ zXx7!D%t{@O$^^mpK?E5EoBl?&s|6{KWtXSCSy%B6A_&IFOCx*rq3u1sgISjB1!B%Q zPySOy3>N5hC8%EsCf2J&a!#`S!zAg>*NN&PV1W$KEU3}r#2jf)A<@u0q>H5xj?fw@ zm>e?@TbV@CqZQ#6I`hGQ-MmOmwyOivkkDdkynie7a*;5SeTZWT7)KJ62Qj{gR+0@G zq+uY4jF}yn+wT+M@jhDrmJ$4UbD;JymeW!&zf4A^NB8 zKynK0N*u!5JvIJ_Ibm3d=ws0$1JbSo`!)`r7KxzdnZdQEFhHC3@hM=1^+5pI;<{x9 zr;k(t>O@ktj-a8~k2lrd0bn)CnF@v4`8#yF#ZU$f>DS*~LLxnSx`B;J!EL7Oe>z8G zeZXR65SJ1(5coH*RtrS4ebAaOrq)OnuK{f$3%ZJH>u*moJP4mq8&d_*TTQ4q%>%>x z7hegj7$0g;M({%7TQsaTFcrHlRtw0~ds{c^(7wE4XDR`?e~oYT58xmsLI>(Q1_xsx zkLO}NX#W9)C0E+EM6m7C$y)wFOn;O&9FB`Trd@?X~uscfv>|r$--bhSTN|t79%+Y zJPUyX-*K{~Ahss5z#n7fh#&_OTrhzorzgk_DLA-V8VLrEfh=!?AI`gv zpN1bJLKdiL!m(CKzD1Po2++2JqQV993k!K!qoTfzkJpfAfkh&7>&0WP=jMH44#FdJ znJ0K13E}Q=6`>V&!`JPB&;Zjjox8!eFgvD{pyfy)I(Rfapv?e3)DzTMuz6&zT?>ch z4F?p-3@b9RZs0UBuyK?Yd_W&~Qs1R$k9sBI;ecz(0rsVR@`tf40H_MYbLJBRiUf5g ztdlti40^h9DE84Hv#&lr2JraRv8I+;nyk<>y39FTQ_UHtOalt)We1rop1fp z+Z#b}F)%o?M0Hnd?4<&IZWT}ts`0(@e)BUHC}X1*ut_7wt3n|nhLW9Hxax6;3>vzA zAf}VUHkHF707iQb2#i_7eWUtkKod!E31>eEiyYX6MhV*i(@&^mV)lVHC=hpz{8-h+ zpWpf>F4A8AND58o8cfJ^|er*(Wcy15hDjdBbD4Eu7?2*RZx&nRj6^oN zS`INU+U>mSgt-JArZ?Q0jXmK(Ru17RV4aC-4TQ^fq!P$r$QnUw=%tksxLAgSbpTgky+tX4|kw50D1`wI5(AZDa+CX3-AJ5jXbuP>Zt7| zhyF}BE$DXxfvd3qBZ0xFz%pFODjOdib;H|%u-?+%VPZx{MxMfO6I};RLnD16`6VVP#VZUjuj zk#u3Tr293T#7zz6yeXuTA;6l@>RQu&{(3t$QHI@I26=FRUCay&U&|+H5b{q=O%Yi% zk%B^H5sI{VZfZ&aN+k~t{YyIjJD+Hg^$!>jq80%Xc*3qCI(#KOSL;i+lg) zbtn`OegexONuyUdiLh+Zof;GA17WteMO)!^bmtevYP$+nY5aN{`DQcpv8xH2gj>f= zfPlc>8(z8za_FyKTh1JA0uO~X>B%5Yy*6}-BV4o1VKHS`z8beI^shAtk5}o#DSdrK zb>!wdiO!!4jfM^OS=kXlRHG(%MiWjg zi%6>A86|CP5C#$1*UD`e>);D$z)*`aCjV&?)Z2s6V{ zNzL-rj3dF^Km+(06|fMFAR06!!|UL26#;~#Apq=7_673!Ld9?YV`i2wk$3Od5{SP1 zgJ1s|FUwtj{bc!@qsv_M@(-5(&Aay#`&<6OuYc42p#I-W^Vci8POtpmv$g!n=hHti zi{&5u`d8)m|JeM?uQ+V@sR3I4!LNV+`!N5Vng1`A*@A2Kj7!4U(cx9|7u>aqo;97xBp4jlsY>+z=bw~6_S1aUS{d*U{U19;_Wq`I_l<^uLEd)F zW@9$DXzlS6mEq-1p>6X+bSd=btA?6qTGNM}1pQ5IT*g~x=IzR9d!LyO*|f3!TGEs~ zm8}CSD4%<;zz~{%wvsC3<>9#kuPnY~#Fl>3;Yc6)gI*4>4 zpNLo|uBAAHJw^+c58Y!yE;zi2>uB2NI}8`j>_o@hvmw%Z%(Ie{IY1qM`p1#-!a1vr za*X!>;jfPdQ%6|&*NIMT#$8^eJO*K_A4cH_%@ zHrQR_5kw0a>$a^pMq`z`LW9Th|NhsD28i1@zYhE3INPLkRg_N~V@mh^$1re(*_|6jjlZap2OBC5xeDl2+raA@9xaXB|~ zcqzI3WDQ?!@0$DO>b41qxi8)X{>mHpbEzzZQXMU;IWv4Y|Hh#Z(dAb)CjM9=Hz|70 z&e*Q_e8YFemF3r7IImjDI~=?YnSZtDH~eEUlfugm4I)23@|u@e_PT%HaqrhVYG~S6 z<)!!h%Imdvtk77z@GITo9qX39#s9hemLD)PIA^oQzq!dVujLmKr#o{0O@K6xERS!M zN58@U<&MG?v!_}Te*5(ayU+f*)f;Dj`xSAxFfNbEk%+|K6#mVloEUz-!0!AnzOnn) z;!(7n%iY?=L-WrvSfIg4wLF5CjOo@^8M&N zt5*E1{A^(nLBY!oQjN<&>bLK5wRnCll?W9_+m%xyep#cU=alt*tSXzY>FVl^YAs#u zqxSMgm%4?={g$SpbN3iU=%6gKsLIS|mmg)Lu?o3if}zYy{Hy1;?Qv6=L3f;O6xeJN|P~4xVj*8bbhvR$H=D%Ka=4qE@>xgE{no!@665^ zHZ^Md8Sj$7>=<+EuvLrK&`8<#Ym8+hF4!?r9CY32MY9&B<+k0ocbzPKz|+|*Bk|B; zw)kFWYnV~+?*5yTg|&C@o;&J*-qcjx{_*>tu_|tVEYTBg{ZnP3y=!^=w8tkVi-7?s zj{2Un$XBJ=a$zc~yfx*xTJk`2+P9DHE~o6SrTt+)bGNYbepe;~--39#Afv!+#`#W< z)uy3YTuWn>=>Bshe`3cncF;~UDtVKpdsaTWrG+l@7Q}qRG)%QgYVkhr2m2@KwozJd z8Xs<*Wt%K~^JX@<^%A}704Hb2xAIZ(l%=ojt?cqb!?04tp7YcT$#^2};V2X>+h+@kbyQcYd zX>V(2|GTWt*zU-=I;Bq0@S4@A@k`U~8oD2&F5zN#^p=LcMQMMv>CvA<^5ECz4$hf1 zl4Ul>3l~GYl>Sh#b1A;9egp?%2%agwe-^6EL%V? z5mDSAM^bSGiF|E{L{%Eg{MyC{_Kw*l?C*C=);61`cf=~`)-s$2I1 zAH-MQ0LjD17rVG99^u8B>~~dl6d#rvy4KPitAD~kenY?Z>oHRp+L-Faxpy3TV>3I$ z-$b1wIaSor#@=YXWv#>cF0p~0JuatvuSFT_pFhtxmNa!dE+}TmcJWgvAC4~Ho~~F| z@fVBVDB*u$?&svJJA%0499!G3yqjb}rL;|dhV960noIeOEpt!VoaeKuYa6L{`C47c znk&{RXj0E&S5j8)Yu&bZRR;rI!-=Kq=Y5njx@~lJ#WBjK{p#r!)>&iTETM;HX|_t) zjouZ9p|f9b-xQxU_UT1?+dJ!+Hr_wza&*PB=1R5{1hk)SvHorGGEZ24IsmNC^OTi& z$KB{1=T=VD*YMhW99eDJ)OqKmgp&(r-BfJBvz2#8dgM;GlV+&suxJg1!5 zd5|m4+1{>yEX-Ve>CULn|FS+*7YDDX$fV@cO3)7e{#*eE6MLMP2qBK%5Q)OV`oM)n5E$3H@D9J)E-awgt}{fT8+ z5##$i>4WiB3mQj;2b|3_XEYD1^L))Rl{oe1QRRfgYBuu`@y2R}X0GDJ>qEp08U_Eb zp1D!Dx2=YkYQebweowh)!KtyHsV#>6j$AhFt(LhB?UPrvoc5^8(VUzA(Ok}%-)TMFuXm8YGdO)DH8=f;nr%Y^N8Ddy1A`^`=WN1}vNNtxnyc|QxKq!jHR_bl&c zT6f;IEKDxZ+%IU7X~a4|dSA|@ZEc*3OG<5ZonH|gy$6e~jo3>sF)B=x)AqhCR$On@ zZ7t0C?0bt$hM2~@`4>qW3PtW4&EdrzASC0-BARrS-STGJ*SjO<7KWehK6;_~%X9jz z>X}B?%{g}V%|CS59IGUKc*VE9{dmHIEx%2EYa0Im$8%Pf4Q1TNr-dJF-5MVi^+*0` z{UcuP?@w(wP{zyTIK^St`4T>OQkkW*)_f*Xp!=NuL_x~kzfG!mV;@=38g6Ty++blK z!HO8#f4*ost?zABXXT*{j9G17u{o9t7MIAfU{oDDTh4PxU?h~KaKNksF(?JlrKlm3}3K+F=XL2hWbiwY;4xY^n}u?9>RrC((n>*8Tm7dirhE1=vzxg-NSzF&rVQ<2e&5()YjQ2k^5e)! zNiUk`M-_K7miCJn#tG}{QMhsDMX@%8`#{H=n3mFgOONfqyu5=s&L32lxvnjy^V`CW z?q~Ha&%H;j1XWYnh8k>+sokvDv+2cp?O6NS-U2*B)Nxro$2geUYaPgR=vup0iXxe9| z0Zw7Y2%FOprID((Fylto8t2^=6Rk%t881#ECE@abQSj1}g^H&8lv2L^-E_rCHB4|wAvf2r!txQn?ZNo4`x`_r$i*tyHw`Rg+se$Q+GpEWelt4rex58ex1^Ir|s?wyXHn%c;WdDs*(SQ;w>!zT5 z?(f!O-_Erw+k3B_?GCul*}<@NWXj(#c6#1>VoPmy_nE(n_~)Fr*lzxMUUQ$l**PQC zeu1QzoUv1p)~}DT&R|b(Fl|kp(wKcG$tBUtpM5d%{e$ZYJA7N-nGd!cZkW+}%KEp} zPjBwH_i1c znjb#At4Mq1ba!x&bMxQgFLbGJoJSZ!WhH$tY% zyFgsd?;ew{wAHQC>c?cNtHSwr*vh3CO>PeRMB)3(;kpvF!v@K$GI~*}wQDy#<(pE< z2xF6P%aEH@ZArguKRYh2e?@-y!;4hGq-;jS!0!c{GmZ;_@%63aQN&Cot9@^26 zUMsc_HSy(-%33of_I>cYGB*Fla-ze%Pl?eyaX9E~#8JtlxsGQr&L~wvJcL6Rj{qvj81CJ7^g>qcN(4z;awd#r$4+oPVaq4JgY0KPb-TaBww3MeOlA+uk)$n; z^V{yXq2=$XhaWCc(oSq(JL<;pYt1buu;Gf-BVNjNgU*6By;c>KC#)O)d`#_7^pLjY z?~$B-y2lSvUE4;}_2ku~8*6se31+a&_k?ukuT>xO`S6^1B%hbF@cB?9RsOou(`?z_ zzW>PNQrmZ4(p#{7Z`F=}2I2y(Ql&*ZSSGJWS;yg#!h+_w4s;ZBscur7G*-y82>*i& z7{b7FNA-@qV96J3NiiwbxBFVVX(Zus*~9bCk3>)V+*UbWJ52j9p!3e7a&B`wAB)C2 z)ztS8E8AF{m0u3KdYCRZ!uxG|js#I&u=}HB(Y-K9tHEAUswYdA*)?KmtSo6WyXkrU%MINe);OdzE6)gD0*u-Vii`PxS=~AyC8R==7DDan}En#gb_dLGE;@AwptkR{n0Q3BQ$Dr3BCPR~`%3eqNNUZ$-1?D#Gf24Q4=nD3ID^`KUP{-+Cx&Z&FW+z7F3 zLnLCcuf?;`EB^-7!c?BikN4h3{lDi3wwdi0n7CW0`7UQo zZ+yy=<(a0s{m=*h?xfU$j(cMT*&l?d4Qr|@EcxXe*L+^Lyca)iTz1K&mBn?lW-U2A z1N&Tt=kn!_r)IPIp6$Ol+{rBd>Baiw!=5Z7UDhf2f^%k_!7+hjJW8FmaW*#rtHtsl zil}SOHW!>y6q$z?YeVcA9d9y86CU7UhP6(R2MW8y1AmY;;Mi%Ukv5m#{?VnYDqkv1hE6 zi676pVIkMv7RGbziK~U3>Dk%OzHH7@rjZMMyrOPo*~rn(^AEf+r^~St7w^B$&%Iqe!}R=YoV-A0pDB;^eS-e#Hx6e!;Emc$39E?p4yAYe zF^NSsrE}zA>cZQT2M-*OkF+mH+NT37O#lDT^%X!>KHvKc(%mfzN_RKX-Eo2Y-}_OJ@67+l49xY;_`bVm&z^YBvwJ93-*dCAhOla% z+S)LB|1L$fADIa)B5cA;bd@++V$i+us56ndK_Us+|e+nq#Z-e@sKP z&pG5#6^_Ez=x=Ai$w)+)=%`SMDJ!pF{Hj2y82}S+4+T792sipq^mR`=3u0omkijK z0+;S;@r_sp!=0KbxQDlPH5lzooBxgi`bIF`vaUhv%LbQ?GLJ$ws=@$~MSfJKr`t-45VCI^Ire-{L>p=>~hAA!xF0xjO9+yBVtg zE~2aR2Lk{6j%|(9V*gqO3p7Z2@Accah>$AFIc3;@G1%AF|FFoKHY5m!7EIO)@zic1 z7tnBB?=M*g%Snx@&c2qn;W?k-J&F4(y(@S0+L6MX7>Zr3nzxv1N=u?==!1eX2EwwO zQNl^D7YiTZwN=kmtB;GELrBkfC#Dz1k84hGSC#t}de@n)y{u0510$P;17+T#+Q)j= z?8}~*cv=i;j@KFgS&uZ`ojUnH=z>wU$ZvBaNq4J^&}X8Wl10sWuQhvFz3PK3sKOs_ z<*ukSU7tMa0q|!x#PjkS2htP@%2DM2opR_R1$9$(aB1c`zt&fV6z#PmbxSDtZMnCk zbM+GHLRv4R^@AkDV&mQQ@$$;`%{_g8g@+S+?Gana&NZ|enxb`sDo>)JGlYAC@A)s> zKH53qY==7rfml+v+TPw{ovzb*|4*(4y?^=_q5eRver+vF!J{8M?p^*_I%bTO_0;L$na<)xTs$XgYHL#`0WK& zXX|(D@RidHkg|;CTkDOn7VYDl)T-)`S;PEOo5?g8%PQ;Ll6ebj%7*X%kr^Y-MZhAC z@~v`?_IIj+i`ozMo)=Q~*o4d17npc&4^M!WX{YxEM`wu{7Go3B2u6|*au`y0!}Hcp zSiY46*&R+Uy_g<1lj^&7vKTyZ*cZZ{Vy7Qez_a^%XWga5gU{6Roe4#ZudQwNZv!rwO=s2P0 zeNk_|t5#sKM11QWb`1`Egi{a{_q%O@68qC zDzFJ=QGL^&KgO=#j+!cNhg>+tpTI?0$LrR#a$bMv5hn-H*_3ZD0d5UlRk+-Nidy%v^1@$D-h=e}KI9ZJ~tseZTLI1n^ zNmD`TKtZs~xEj(_#ad2Aj&2^ytEoS4Nja}S{S3E5yH#&0B}dB+w`JT3!pk%#@&BY( zEnorW=D+Nljes)8Z7c!Qo$g(Dw-P4^fJv3_3AJ)^kX&{P_QR1Y?MFo6W+I@^9qmss z%+0rf(tlp@LIFX3`R~UlmnFtdG>?<}RnbH2`V;{a#-d*?PbXPk6*l7f&AGqEV2b8; zgQcDNI}ldc{F55oDKagOWuPQula(9VYV+o?!C6Kj+K+ zeDGJt?{ zdc$SltV`eTNo-j?KO%v>F>AmEh2W0GXI2;>6u+%g48b{mk9Ff%N{eyNqaViK-{?AwPllGR;O}zV*%3 zwn^OHz)|(IK`HonDkzJz)agL(ZmrA0yjpECyOq0#cjNxMw?r+nV?)Ocq$eD?{ z+UC)^6Fr{FWal2(1VGBh_ClP2tx7d!K%iViAd2MN3dNMQ{%O(Z|IYU{OH`&(YQ2ktKLe^NBI8agBQ@XZdQDC++4_1Q9}4Pf;#@wvZ0m9&&FfgKwwdXP zTlArFt)lNDiOBaYrD-4@8I;XWkJG9^eH;-Ted zAGNoBQRIOg^X*Js<2?(_mo5RCE1i_p=Rse zfUoi@=GL016B`}Yz5{z%4(q(*dx|07#@j<9)M=gvoc}aZT8$De314S?3}%%0{)(qx+!N}x6eqx$Bo4l<#^za2Jn(26?fq#J@fghTRk7~~z)-pq zX?}dc1s@NghNEVH1^D;0+<2q5ag`RcIs~53n|AOi{FC@2-Y`KyS*m+i zs4>2ZX}UAuX>0v3>@LYS7kWDGsp>qb>U@**>oxf+w4Z5up5MB4CtSd-^MT?M=JXnG zKXmE^sg8;b80Q|Wf<711sKb8pz_o>QVWw^4Xo)va*SsQ*DNQEvwBKxxP!6KIh4J-? z1;G$^q|lB>!a_y{W$3o8V}!o;5UYwa!{qN)E(>8nB;`ZAP%-j(vWY}wFzNuRB;>xWs~ zyw;_Q9LK(D=nm*--NRGz*UvJ|SR&`>ny@5+&d%Ir$e2!O#EmY1%>btt23*3guZVHN%XZ-JxzY;%e5{l4N_%Wdjj!AUyz z19RCrZ8gL8c~1>4_cnQc=WYwKhmaQD35U!lG`A|)o86(-s`yUp=T^qP>qm>v_pqLo zIB9NV(KYo%OrB=#RNSK$OpcfCKRzCvmkf2gYOqWZKz^bvq^yRYgrYyT!FTcs&0bE4 z7#+<66EeoVlAVRM0^8t|hac`JAD`NDd#HzG1jzY7n^|r+Xg)=g`?cl-=1%U7OcV#f zijS6a)7h3Iv`>d+70_;b7{v})t#lWfM|~~5_X4j;M)^+MW4yQ=r99V9+dQ&KKIzfF zenq6(*Pi9`d2f-$Gn*H0*k3H(9p-b45*&Yc`p%eW#8uxtZ%+%Qpif+okSW$=44#j( ziha~o%YCDrHmTBXR%gLJ7NdqlA}0&WeA+L~m!IFzF7Rx-hd$lj-}nBTX)_wZ%p9>( zRwG7s!{`7%9yp0l5f+{ki^>wbcI6rG_6g4E+z)LxC-Y8y>G)|qft(WjO5-0!gOcR( z!c=q7)cdPl*XreU6NI%SO?YtNC?c zV|{R8T|FnS+A*OU=8`GN{QL9E1GPNY=38y@kjqLfQq9Iy*+t1HhozRVCfGR(0<3&+ z(BHieJ~PgLp*|4%RJ_ldZxlOm;QJ_hVcX!e@i{t)PvBENQlBycxzF_Bl%G{@I#FyE zqX%*QoH6_@fRfKYtH zI@bJ#U-+CB?2=irFwuDYU%m8gZ=18?_+Z(?72AHqSXJ}%y6244c;PDXsof8wALMTY zjo)YVzGrd_O&J)$aCBr_{4U;pJbG;9xfq-t*D)8B$Xg;0cWIz~C{5zyxLfcut$>?+ z6tbb3GVOB1{{%a!F$b4J8A)4ZwNGdN2`Ir|G5^bR7WLX!`xHNV+f7H;TQ4W9qQ^g7 z>Xne_aZjPKW5bw}Ba4c92rB%ryN@S2P5oGmQvYe4U$4@N%3;?gNx`+oIa-Je<7-d4 zjd^`~&zL}cuks`5F7PYIlF${oj`UF1GXe*Vr-WUJ`o?Cs6s2Q(NTlXCq<>hwIeS7S z(il`t={lwt`N&aI+rRd#^ynBITXgf%%wtG}Zyyp7Z@dSE!k z%E2T`n1J#tW%u{-xLJ1aiyF&HTBo0dF9-LzIBk4iw@s*O4N(NGRE1>s(nUGVS;$<> zJVoShkpz5$7ykX)-Pk(I#R2x)4!CC#Jy#jE=bl7O9Ov`dH%MvQ&bY9ne5;Tebvq^M zwRKI8(2G$rGaT}~HjswIAuTgpVZ-=2^DRHp)MtGZ8@6u^K22px=_m0Eu9@%r`nZXh zZ+mlesVO!Lwukm{lR<3dU!`T=wAjdL$73%qTW}l}6&VNj)X=a|U_CINbz~MvwX7mn zR?Vo0$JVH@%^QAhzxs)em&?`8eqhwq6i4LFlzNR`dR2p9nqWocPQ%><4@2jUg+GZN zm`izBKjldupw||Gu{?MO=-Bw8odo^LSm^4VZP^g_jj3V{afEmR`ta z`hicQDYB6lOZDp<5+8e9zd%3aOf1-rvRP?Rp4Zn>EOyoEkzk(mm}N^A7@8T6c?p*4qGE!KRm zjG+C&T*>Su~(Wj#ManC8YF@C{0sK3Nmwtub8oiF*I9GH<> z`~EGnEK=9C!1U7P*QvdGbCWy^CaGt`6hW=O`&q|RO-Dy8?R!zEf&U9FUc|h9`{dwt zX8ycG-^!PYwMvWb@?y*GKXU+oZT_~qL42Xt;OWDp?K>mM4P*JBUzE9~m23Zr+x^Y% z<_`B54#uPHQ7G)Yyy+7RuqdftHgBDEumPHu@yS{Pl zCuS4ta`uuXeWcRv>*wf}%M*!vPF}wo^7xHoyw0Y39a?@9DEli?tN?4F?bzeOyZes$ z367ojVcYC(<3U0SwIwTk)XJCuORir7rbQ*2(P(~_BQ#{^PPo4wvfRnA+LOMnlS)%} z@U?V}^yk5!tD+IJXhHtx_v@o6P}7zKD?EJ*;@Ts2?+#Uac$Q7D)HNQJGe(I$z~4zi z<-J&P&?WB}(S&rM7-HVmcUqFV+$Uh?tx0+Aea;22VX89^sV&wVJTs~AI-CeIMLws%LYwMm*7%qR zX&`=V-a5ESQP{;ulrwlsucXF%R>Wcv6K^M-s)nK&oUuag3C8432@n+^KwC1XRNi7l`rO%>0BENPW zjYrxnr+an(wJ&_ARMR~n-L}0S1S0S0`E9EazkDuDc%n3=W!_X)PQIZmZ@!h5jLxTB zrJp}&OlDXc@a8|3sExYt@p9W3Q!9plMi0n$*&e2lOjv-_F{AnjnjS@hDodjrmEEJ5 z1t|X)C;4Uy1_g5c^vz7i&RAxZL=NMaq8l0yh*&1rjFF~P54Nx+jn&>f3{kqKUu$n1 zB5$5EyaQHsWOEKs4HyOo+A|A4Kho&PtFtKx!qgj}SlCNCroaVS;F<$`{GTMkHi2a42@ zt(E#OUi?g#bAroBwW?Tlhvlty7ik`3cvE?8Is>!Bl3w%FxSc3sUyDL~s()U3P_X&h zy65U@hTC|Xe5K)V(Qz*(cg}nvI{N%$T@EtHD)${|r5u}geS9k%><2F5svF3O?W{LF z_j2s_I^Zyufzb)OC9R;$ES}{B5MXB&Jq^<^FYd6Nb)}l3o^Os7K-!e}9XTE`{h8ps zb&tV{(}Fv76L$SlZky{Y$=;&meCNs`dQj7-#MKUO(gR)Z%37NZW<=DJWgA@lT&N6e zXS9(rvl`WtFJhSgHvLYqUa#P~;ECvWv&<>52e1^+7ZhR?jMtMlGt z^E_=R5kV^PSuoWxPDV}`mGhvoS%n5y_t8!}-DMR9+Yhpg8I5?Nq}6Cu=PGbDb<9_J z_R3XwH@ABCI_or&-Bm}}bqE9@wa|_@J_)$jp5XXyYkEnt@n&?0bxzQty>(pj&is4g zEn6VpY~*?hPV)egOdOU-5ZIZ^h}NKeL8m)yYHTtfC=}$R&?;YgrC#})+uMm`AOU15 zU^}W>6XbEil3ycDu{6)j9FZUA@#iqRb(&O_ zv=B9juu|ii{hC-;o;+w${rm=P5@e%l>}$p2oyO-q8I!FuE5n^DtQyZUouA06cx)i&#xsw5V7d|*;- zS zR;NhHR&VE5!jfg0u#Er@B0H7xdH<${em4{+EHgYrx==zBPMJc6j=G9ck4kW8@fBl* zH}DZB=>|fa@Y9V}kAO+%cJa}A_@A-Sm35cTB!8EEP zdVpWT29>bHGBa&F>5^SZupRHm!va+J}@)pls0%?l@l)=Q@AoqRq zz4@AvZf2LEjaajLF})L?x7zzLUf5U^S=NtJ1d)0fiPc5QF@6q7WR{jR4jG6K$r;R) zhVAz3>-@O>>Cr6=ljB7$M@N=LAj6EBf)+h&QB6kB&YdgJG8Moo7fK&+>z^@@lk4$! zI=KclGn;JL`=d>LV^;bO;u43M6rfg|m)+ zK5hez*ohjK(A&CYn&zdeik(#-w)?swce%$!fbAvq4VRk%gx2tG0zAaHA zBjI|&f~l5$NfWE8W=MpkO9^mN4!)sMg+oQ7q`UrsRaheI&g-k)F}?D6>FjH*W>w2# zaui$!0T1BF^}h0#W`1(%kSNhkGBtZtPW6(|kM&1^`1+$388l63Q}I8O zl!iA_0o&uYnS^GJ*Kvd5-Y4Dcp6$Ky`+TJtT-mVm)TnbYD^ryyc{8S5c0S4R`jM ztWT-4n#R2=Z6ce>$gb(B`aP-pCB%jnuqpE21!n*4!}GO6Lo$2z6H-S z6q^R($AwV-0=Y>)kAhIdsjAmBI3Bap%xX42DW+^sWIT;1CKD{bVb0sKe7 zAP4GT9T^ZtvAGi#(|wB(q@m89n@Xo!N91m9vpPBB6IqLQ^&4#4m1D*yKKG`VWK>W- znNiC{uBSw@>fCWyUuBBvQAs9r-sMzp{y1y!f^x0oRJ~aCI?Zo$dk~$S9*^|yUFX-# zXx5qFoiS);Q(BIcta6y&mA~puaLpwX<7&yItpUTo_z^n0_ZK4v^L_u&)1*b3aF>;8 zhdH4&$kuf$y@C!J~?lwNM8D+gKb>MxBgVLK`PePjAqQcLgx zEf%>0E)hyuGO#ELg2#}WYE4<|k*tzYH$2b1`FjZ|TXg-)%O+joVVVjFdCE5rkn}Dq za5NKPOa@Cq@m(rHax7wpq-JuCfBtA^Phf!tJ%_ld4c;ns`>+VGnuTzlma>{ zpdf00m)VPDFim0kO>)bdJFJ(r)XqEbFUt$8HRcuz=deSA9;w&+Pcl3omA+sJ)g#n~ z)T`3&`{qWH(>~79eP^CjfEmI{(wm@x`~m47kVH=PnO{&5tRhFP(rxw@SPL)Ss*+}tQU2WVBqWMg!ijaxK{_MD3m#)y zVuUhTIoC`9x;$&!+^3qET+reI)574owm9tPV(B{&TE%G2iGGFW(X>>ofi5Y~cPUgG z5w2Lfonxitmlpgn;aAUVwcz!e5io1&3$I8^rV+}0BgkA9{^5bC;(^zJeJa?Ew=C)F zpv{(`@upFcS@E2SYE{ffEToq3)d5e93jI8U{wArSNOW3nbb~yJO-Hdd2u}v~y`tBl z|KQ9FPY0eJX!MIFbV{?9)JOXYn|ATFsN~NJ)JCq(Xt6%&{Mhv!Z)nAnS7=ysDf#+&BA&;l;2mrAeF0q8}O$j+QcjJ;LkUM_8&rR6(2Hoj6%AdDbyEM$WpynK*rpq zEo*9SC&WRl^ka!pSB zIP3>TX6~In9q{=?4{Z3^sB*Kphkc3lY{+jl{RTvwgUA~|OwBQ`<`{9;bB@k_FV8w* z#mtrSro)ZsVl${TE^%Mio_;^ReaqZByD$MR2Gs6g%RbHAPBSRaKKyu^L;rcv4%1ao z5x>Cb58t8boexouw(PWG{hZHNGnL!7mid zgC@FIRje0DvbZTU^JFJ$TFNREem$UdnTTWJ0zu7y#c)=C?18Ch=QJ$2fa^BK%5&BS{_eQMt8y8#|$^ zc zF4ea+8@s!AbpQb~_306;us&5|+_|wUW}%^HSsKCdn$6;%#$k%Jw~3HpsfV<7D<6;{ zvj^|l@GRb_r6h@lU33M!+~%j| zrI@00F4Go=2DUp1(kQ@|xaZ7sMV2K#c?uB1+j~2l!6aeETYkwxmf1q=n-GRI-R*kYhDHCCdt}e%L*Rc<3Ec9{z5(Pjfe@e zS50$7YyYqsdAI5Wmn;RBeE`TZvRF0uO&Q&$PWKVnmU_s+ao(wXnQn!Eu?)qWOX|h^ z&d&~lFIrS8Uyp!Gpw7mNMjaYERg6v!O?Wb_`F5)xe?#&F0H9RlLfq5oE&W1tDd&xl z5oxwph}p0w@Y{cHzJihf;A@JL4bxFr`i&}Ba^-B^ zO3-}y-pdj$^JA)ZGEM6e6~Z3WY-ap+5SpY!z98lIg8u^Po8-W#u;6+YuPLTu?<)&j zC~s-SdX-L-YF^i^P4#-X$6bIb$;(!R{&+`>fDO8TPoF#W;P= zaJ6iW@0+XEAPUaNN`5Mt21X6t4tQAXq!|L-VfyzhUpJ6Cm#FkM^<{!0W~UDfZR(+- zX3)2~P(1YG8xUpu`~v~=LCC^ci}UromLH$cQ)d`I-X@C)Cz`7b^OdDjMPdvRYuL{n z?g%ML)2zQ7DFhyQDTa!q1z4X0c8Pdm%*!{VUhL~jgQRtP#%t@O+lC2`bSGw8%d23o zcm3T57uV-vgO7%m#TYH?xfI7w z(Q*-C^(oRWU2J|5R^5ok?ooqsNjd3phxpLEO*A_sd6n;eb$POCb5N#z`Tt*>L_5@v zVwr7614d|peFHUP&yzxn&775&6o{P_-}<`8U(hK(!LYX!6DFGb%p&V%8fnl?94CN3J(IsSM`0t)Qu$ z+P^>Qj&{!40PD-~`)pwLe4QcTd)hw3d1^K+34I$06OiwAw?UQv$O=z<<5+06nyittyXu7(6?0l zK!VRrQMjn~qVRel`t=bsHdBag;rV367@YpeSsV^xemu4U!4#8UD+4}k?R)w%y~(-= zj4nZka-}ox9K?0KZ`Bt(6Qp5V-!ohl!v29Pk>Y7J>^?I$et$Kq2ftM8P}l<Fw{TMHS@+PV~ht+;Ocp=Yj4kQ^Y$|XJh`IIQ)?#@#S-#4Y$ z-{#tW)Y=o5JKhwW^I)94=Mj&=P;ga?r%q@?o9CB_<|Riub~&ti7|0FJ`YX?ep(Jmc zPKi&h`N}&ZO?jfo8ynz3{9H~EA|%yb%iuEc@|Q8okvDMs?&7`zF}{;EpzrXGYLI6~((Aa2OYb}OX2ynW zy?9nbnYd%UCfk{jJ<;|;CtFbey-qLtC#Fw?*zZ!L!!+I8fdNmHGb}H^hUhA^sfj0+ zyO>wod-Yf#*!?M2uCm^fvD*37+3fi;Y)`ibSV8`@xy}0Yq|w@ba;AQ4v#K8w1opc@ zWnP^(;a@NXm7Nn|z{L=S5tMMvTUu<;LAWW34V7LuMCJfzC7bR>=^%>j3$I*dm_S67 zKX$mY=S#6Yk8L!i&9@BGzLi4fI05yqy+4?X(4(43uX3F1&T|&1pTq^fhLD(CB zI&jx)wChn&9x#i}C^!uF2!p<}bi~-Yl3o8X&7mQE>7GR&kCye(3rNN1Rwx@3H|u!V zV2H9=`|@j1L4f$sy(v|E94@V2NPeigxabm5Qc{a4Y)k&038gr~O7fF-Lk1&eG%V>w zPt&DMK_h65M>`{IA;hO_t}Y>0@^ZGf<;i|7!6~TimLF*kKsbN(=J38|W|r5M&%xI|ykixnxjmja9tA zUwF52Fn$W=QHrD!oWw~8>oC02EqpCvr{TSBgF=YFzP#Dv!n#jC+7Ge^7~rMilhqzC z0n!G`e|+)Q?eoJ~;2R=I#m|~7J!}x+(N1Uz&>hI8Q@|C?r}6F%%TTo~HU=8c58QPb z%EDJi#-zs%!vdOCf&@Whjaq1;+V4T&`(AhOrs%8*t2!HW-QCQyEYjoX;CLVc6Q}A^ z)8a7(@XC2DHv0|FFJ5kUDewxd#rxtYmd;oIGhXEHi^Z=6^ZSjQqp`yP};OVr@9^K7iU{qPKvg24nl=#6S8(d zEPnvXjUY@{l&ssz_o^`q+}XO&aS3#9%JUIGEgCVmroONfm0&{f^T^LBd(nCeRt!Nikc z34q&djFMeE{zvd-e_zO3_Vc?U&zl)<6(D4*YD-WO1OMsqn=ERXkDon>vNI^ZXil=} zCh}NU?y32q?u0-#XXV$%&@i)+qLKBO=|g6d%6UQtl*soTPZAoUL1BtScj4k?R7RH~ zwgQD~EtCqVK9W=Ku$$UQeWLO<20A95B3`B6iZ&$_&rvY!hV>1hN`j6ERf@Y}MZWG0 z?1Kj*uAPlN+6$wGL(0j8!yQcS2(j?`tN(6kq&UBs1H9RgPCp@xw=HFWgdK(RIWFY2 z9l?vEs!%P6gHmrbB8Xly7rVwZMHFLii(O%I)60?;Hh5K|ru`5667Syj|FQx z3asy>MLF#sab0+0fr88KBSKKoss&BY*J{?@ILN7h%or`%cGi;JdBeFpbOzsP=*beO z7U|v1e?H37!o))8@Sy{2+tuf^$kRqzahMr4Ji!DQXuC^0#>ae}>$P_$FUd^gpUec* zC5a)nYixt6{^Z$B@#%=l_COkMdH6F7Apg>?lOpVE$NgFwI9gY%w85S$M(3_>7Es^H zK^lsZ51d4xxWYRlp7Hld7VQ5`iDa&wu~z+OPaNdvK-)5zJWg9ahVK zHF^u>r=YaI$?bx)NCc6p?7tbJSXS8HDt81^`SLMZuI}b2<+?-pFF~_}g{9Kgg_Ty2 zu8)!l{d+#7a7kz_8kuN%xc&qn5!0m5%F?7z12hodg7WKG)O`AH?lKcj3x{~MR2Q}T zRatzdW2gVtOOH|}lWW>>6=VzPzd$!W*93ZQeb5AN9oLhXza>cYLeVb2=KVu*f8!l$ z5b1$AsrYHrHdlDVW&_<$=El`6nZ<61hT_={L8~cr;nw@x^d_T_RDG9P5-W6-eC$sB zw4{`}tu1|u;2qeI*}bQ_O+ih8@SO+eFY=){l(>2RkMI(gOenvB!+!{(H872pv*G)Pfyw8`Z$2_sJTh9U>0aBG2W-;m^pahb<|H15a zasx?E+>T_?>1NEA-6wDhlxmi!81rl#&5&+6L;fa&as9QV*AxgQowH z>fdun;60q7VjrK&kUa3=?Nrn@6a$%q7OiBc!``o1$Gu;;55y5z-`UAG`q=_d{#EvS zMa;_(g zSu^int?j5d@!JBRjZ4#7)R6^LyS}IRP+YqIrnG5RKYCcq?oj3UaTVNycEKF|4MrAH z^ojM^@axH+?lG~fr8x}A&w~{^8LtoEa z0?$$e|79TICC>uzicIs5ud7hX1aT5x6&21N&%=7tUH+(Hf} zx8u^Q;Ox?Oe#pmz?9QeRo~gYhSID$J&|6{21)rEC&B?u>G#P%CAam(jTmgxH#>S^W z0hGLyA&c!|9#@hnYg}e!$I2a_ziA#z`Ic3GXgcQ@q>aNBD2Q5P+T5m z?MGy_6f#9^LKcHQ9CCz~^6;a4$yBh~NR z&&tt&=i&pfKVmz^OoZ$9QH6GfekU>KkqK3ixfUh$x#7yL>u_q%lTnyt0kkY|PTx z*X?+mco3J81>eb2&$0G?om2bkg@SK^2da-K4gsr*=x#(=M{jdyd>W{Y_KsKr66uSa z2A_1G@-gE&dFXWgfYYm6T`oy+G_9zfGut!EUF@(=l)UgE7?F_&eP?uTA8uaqg@=uE zJ`@Lhx9;##4GI+{9iGnK*m>v0Zxw4AWksrhV%1ywa!5a9$s)UFHP{WL?4!r-RD{#o z^rpMdFd^Pzss#`*tuYHkZaWyho%ZlVTxGbL!+$~uS&>L7Gd2d9p9P}{M)!eCr zMU|yANy30M)1f1~yV+wE)xOzG7ET7(u%F%|4_j-p$N-(EDe`~O0BUKz{`DiS_D##7 zsN}~-+tS3=y&9z53zIBwZj^yaVLE8RyHqYeAJoRCr?M207~7|WvwT&7E1T2NWAGRSZXUYK>5XC z>jZ}`VPv_LMC(P`$q4_?iKxjZs){3K4x>U0CRBWOHfw;~hoHckW#s(qUjBgj^ih&m zt|_jUpByK_r>#7s=zl?v#Z$M|8qWf#ht2)ce1uPy@|J-c#IF3I_f% z?jQrJ`(O3!gM#Uqa3GY;$*G)lR*8Bp|0>H%o0+#H2W5fo(F5Og7l3-_(=lduOqHOA+!P- zH>il{HB2hf+7G*-wvRvKDCp`hTjNX6B9UaI0ICg-Fse-wKTYS367l0Wf~n3p{@!04 z4-?=eI5`o=XGj6!REuAbq60_#7?AXWg_}->;PRIPg3C%w7O^m|9B`7?y|ZmMMxjPb zAD8E9_E=D+iF%JQ&Jo4t-3GAbo#{b zLS_QDA1I`FO2-7*$G2x=5CV>sWKMCOd@7uUGSLs z_u)4#6~d@54^Sd0j}8QN&vKK6B7z0W=#@Azp(rN^*saeFSFS+|K@>~C){Nr(Q*l~-AiO-7mi2s^~B zaSbx37yLl4;nyl}@AwQ9wbBhDk6|H_XJ8vO#Q&=jZ=av}2Lon|wA5HOxsp0l!Sju6AjaBF~(Wy<@X(2my^=+yMwuPny*%EsGqLG zZV+Cy<>J{MN5O8lL=mv^D8yQ>=eO^}zoUi(&@ai|u4#t{6@z7K_qubAQm24YsCqu< zV5gaks8F!6)LNW+GQORI6y|Q9O%of7uqKrp#|SA+PV=Hkrd@vM_HWmO+T#INF6RLg z(OFL7G}>~vPX3-p8yXp%Co`tHO&2vSDwTiB?!y$8P^$Mb&7yRbybI7XNv#uC_Umye z*%lmXl>lY4uSzC%F&jI-4<+}nHOK*O0Gv!wF=$&eaVU=2?$g5Uh96b=BfyXB=EqxQ z6zL}>(Cz)ky4*ot8a5ak-^El5E*S~CrZ9|BB(+c#i^a$X4}-q6R{%%&G%u0!vGtBK z;C_|15>nw|abT_!Y-UV@W<3H+n>@0T#<69c2~R47vHSJk&^(p}AqsHYF=HAA?7=|B z;ktkkZsn<$lQ;X%LgN0j3iVn~V4p4SzTwfG=x6w~XgbHk1%!4s*KXghVmv6|`qf(3 zwYp=2Bza&&tYuR46%vAk*0f{1xIn?DJR6hsu)-Xr%`wm}cX&Ph)+Db$_fa3I(bwdH z$17`@_n)4w#4a4?f7uppbXz|hhG@lCoc2u{*S#)-1_VhS|5AIrJPZ56gh!~D96yL; z$y`K4kfwNeasW@AuFB{gA1tfC(t3_yWeZWE2994M)M*bV6A*caHbe(iAK&6SJ}b;E z6iA)0F?U~&LRds;z^aBj?QIeRxZ&`TU6$$ezbNg=#x5&?7ml|JjDp6&2TlqXX)W z{Z^l6A29*i7P~fwBqG=9-nZu_Rl-Ln>7>}@`9XJ}l|jfj!gfet=W?6Mxc}n^zP;DP z$6&DlJgvp;e)T%cQ^-+mFJhV}CznUfyL4)f)u5EU=;xJxZrcZC)ynrGllg$!xsxsQ z!AqiAV>FsYjE(SHFW?%y-zqhhAvI)mu5T!l@%OMQzfp+w)%9Vmw~vAxKDwEf{hmJj z#@U|kP^EtS;Goppj0nB^@ujMZ*rk2wpYn9pJXb<0JtVi)Ew)@d)fS0(R4z3nj`iWn z8iIy-wIkYs)w%1bOD5QhrP#H25Q>0VX_Ar-Xj13S94K`uS^XbQDD7xm=<$k&pW7ZYv@qis^3VHY)AEE)ziT)(i zhG~%|_;T#z)33qXYFU_8urL+tiP*5C^Or&x@|TJ5KWIkL^r)kdrdCm&=CMM?@bA^g z742Ku4Wi<&-c$he+BKz0;5dWSwrVGrIeX2m+ z<{elL`9cEqoHMR!`9^l;^^t}m)rVWsSZ370%U_U|b_}Ggp8~o)bLCu51!p|r`J_JI z81lrtu+uFuPmydoG;~mO_Vs5Evmy{F{#=JNijC>jeB?;j*Z-cX#ApH_D--g$J5j*+ zAr|P}6^f4Y2MQehkICIx75eZA!)5r5(oEiKNvV634->R`DM9@OLN8Pc1$YpNFQWxo6dF|DGoM?`c4HTC{&Q6@j8&CsGt0 zVZ*vYr!FFDJ-en^+OxeKQ}MxYXhey&;myUtE;+A%2Er$9i-%gZ;^XHiPn69DD8KOf zr*L;c za|4I-ly!CU($XlUW7(t)n%@69xb??2$q7is*xBQgp}Qo!QhyzUE53s^Wq18LCjy`k z7Brd!D{>c-dv2kt%WIYYfoas!GT>jDLM003{JG81*?A?mYP|=v&)bDf!gW9cVdAZ= z_V#wJoi=9222{eu9!Ume0|SF#6^#GZQ%;8sRILwgtEc0WR_%=q0LIC!tKRIn6&eW2 zVRy9?UA(pyyTwkpCrw_4Pn74-&|@uy`Qf_=L0XrWSbe44Iz@rf1cxWKX0IW3G+vt` zKoZw!&$R^-1_-)O=m#mvy_rCUWza};5LcEb33NTyYK>x0wYIh%v80rW{v4(2#pxVK z%Ltlv_R*D%ecAAa!e4U`BUG-vVL$yjY9s=#n{L+JnX z3B%2>RZ#hea)Vl(C=hCqp^gYdMLDB~6bwpEr3pKF7B;lQ_MEn!%?w??*sxSgK-zez zdn2tIPdyWoCqYs z#ugmL9S5mz_M4THW=0B@d)?^`)T&%LzjgE5avS=OR@m0}LMCxR= zhS*F#?X>Xl;eAFrj0OR1YK=F9*#30bE1v+9z1w9JfP534BhTVFYov|6*Fw}SNgu&4 z_CyN+DIrvA(0bJkv`f8ielT8OAX*!x3{K#TXVK)A3)Y?O<;4esws~2y9y7Sd;~QS- z-0S5+*x1-I&3~|PDnh`#-TjnkeEW=ie~Nk3;XpBVciumqFS~`VvsL>o)0B7v?E)7O z#3r{se7AKqBBjT=JSQg~W|rGz=MGURKW!!L`!Ajk(==!G)=EAry$g$F)~)<31Wx%p zA!~EHRDBlUoXNWa;Z=in$cSdmM>-|BtS>j*IH~0){W5C<-E?f}osN?q8K#vp`QueS z{PIOZ#pSruZ~r1i;KA{-IV=n)N|$5i+d!|)z>UJ{YAKJ2+l+s*Jy+Q+yS~6pm({(z zDmt?Dvfbv2q#4)I2iux$W?sJqUBagy&bx;DCK0XOkkD|a)zj9!JjYtI#BjD}>T+(IukmL{u^q0SOz^$-2NoQl3YnO9kTY~oq9j``@n4vq!}?|IGOnxL{3#!L{?K!1R5np;L#uFk7W(`n|UGT@8)|M|~d|{s;RT zQ&&nxNE3NWPSfwSa)@0dY(A8bqUFPEPmWNK5Bp@O94A-%DWo2cHXY+ek zTH|mke{GyAYxmGQJFQuqy`a-h*3F58n;`(rf4Iyt9(YPCJo&#CXia0aA#*6~=h&7k(`49w`?P z1G_^Z0Ob2BtX!6hPNk6(yy<)D>YoHj-)}a5Z}IW+PEdKRzi1Sm&T!}C%(g20OSZbY znzU0k?ozzmDB|$@Quq_GHSPYTQGwSR`nT-uw|}Jsko`bei?pQB z+xybeHIE(*Ncx`ooRl<*&vhDa2@73~S@1G0#CF)9PWzCNKqeLOy9A_sUm$xKsHoqfUVVCWj+bK3)Qt{$kde~g)a^rei zig@0HP{pct#YqXQokVzPO%r~*sYa6a;R&zxH(rHIIA;u_1wR=;B5sp zaPcPc(fgaIeaI2Aab>&aw(MiO{w$q|$%{3w_klHJRq34arq&cXmmT*P$IddWD$Pij zExd`o8Mu$DO^Mzx&a!Xd=hoFLP~T_#t{}S6y&v_g$F0e&pXMN=yG`jz5~u$QDskuL zVG92`&I(aiUr};5(0bl>GAaC2|2WnQj~(WT+mI1mAAGTVZhqC(c4IWWrbc}2>kmRa z-mka{7aLr4KC(s0kt6ZSTKDDN2EnzUNkPljDd#3l>1t2*%XpXUXp-PZhZH+iPm|~` zvO`KIJgDe%$K@$>YRlqxqc8erfE$yCZFDNPYi6d1vFy#SYFF1Qn-F5$9z19O8l1ku zYJGhysq^&rC0|^u_{MMfYS3QyT)KMpwNgeHT1Tdj-gM5RrfxX?Ji(aJO~HL)Hs#Kp z$|vckL8X-b<)yh*c}nz^3&Gq}RH2J*mW_BICMEMg4NbHG?sC6zgAp^mzqe?C_PIYq zMeoO~mk80_jKi&@7#JBDeIEuru6+wCc4m`io#u+ht1rAclQXy&5fM?i)?@ylmkKNa zwL$rbMDS75ft=!^jA*l(x4%>H)*nHUYuxK1roZoPn~sLI%=DeXGBQE;dJe>$|BFe% zZ@L5$S)D5bh;6B6J>00?HP`KM&&lw|j~^#|+qulbGQ7Rq#K{XvsYB3)R`VE-xBi{} zvkd-EZ^deM{u+RyyKoFYZqFX4NAYp(3rcV%wYm2qNRxfsKllc@olp(x2%)`;aGTS#VxDW=#_IW4C3CO8NAyxHtii-6 zMFrjp5sL5LQi+Q9>&!d&l(bC24bVUHkAZLp>1}i&36$tqi54#xFXNv!aYPGAfuBSl zMQu0iF90B4&(oA)G0)Q|XwWh&fU#FLbc1!_g1t@NfKuesI-s^KAi29MpU7mY#Y9!U zxN|doVGh`^^D3g;E zP&n_w?$M)=Q{Qf3+hJ*lPXDF*R_}l=uYRvt-caFiK)MAUi1Z7QzV5%Rjf^hC0;qNk z)_-)4k_IUllKm(<^AMV)`kuD%9QA_U2Zs#=szt?Bs^{}wJ~e@=719T9vx<5p;FrXY zN$nQoB2v&VV1$=VEc!DDRF8~2G2D`uldIlb1&A;P{pLewVHV(;Bct}a+nu9%tCnZ_ z_&rLr&&?@YDyqEu>uo^&Kv#MW%wMhExp3}9b8UA|w5t~xof#LPe`1dS@IIKK9wydb zW!V0biACl>(VV5zVLb+)Ps0XYwPwrq9M^tk`j%gqb^f@Fn=K(I6)Y7aTq z>5&8_#PG;$x*s_5@?KC0iSwa3JECD&J7&OvqJBEyfxYVL4*apurZ1o)r)1y}!rcds z43mtHA}F%K6Gam;NP~p+_^eZB69-sHL|JY%|3lKC6dUff) z6y09<>3dFMBr3nw&;jAVgDN(B=>mJsV_HuR>?E_ z5-8BzrOB^2lTHKUAj+MP`V;J^^$I#hN(omWPa&`Ziiesu8USST#!=p+tYl0s-G{c zVAuk`6!hWZx^>QN=Bs4jd~TCCfJ5842MzEk#EoLB$99&~E>0GA?xepAG6pHM+dv_f zebQepWFN+|;g8&SYm`gPl0Cq=u}MQETM@=P8;vzNONoXjhR}5Pz4l*&@^U@4)?m0c z%`-D@+}-{iw|#GPs}I=2%ebwqhb50eZ`aUyc`<+k^Y32RiX%|%&<+{ObHP(NU^a06 zs{M{-!N9q?b7kqDOmn((SqAC@w-?@-%x)|G^j+DC@AIY|zzFJTjyQO_e=4a}XCn?8B3U;V@S49V8` zny_?QEla0pVlm0+%u8uT4_=tHp3M%-IvUgjoF(mzb6o=af!~LA26ryU70I#3&i#_j zo&GEa{4K92^O7=mo~Fk7>iT}&J135~G&a;%22gx|SLQ}vgau8v)n_nKPce-q{SDYnC?^~!b2C29q;*32?tBc? z*{+J5avB()dC`9FgHC)yU(4|B?g^*AI!bc#XS@}3tkAtem3>||x5Zb~NgflcM|AbM zJYnf@x1jgoigS8!XZoF!A5+vA_u+&0Xk8Tb*Y$ySVb}TiPPeu`kg%{C z?U%b#KceN<{q`jHhKc~w(vFy=tE(#SQb)Ic5G}Tt8e6(Bucw(8MJ;{i8(UA3${n6G z(8<{Ewa;3=xAR}GCfYWO>XntZwPP;g|2G+#^NWem>i5AqJ}9Zj!PscYqlLSQiwrfe zGv`!O0{*PU3gOm=hZ{xa-M?34>l9sw-G^FiN-R+NXG9!loWECW4IF?B0XyE1aIUyg z^JZ?-tdb^>MbB$QQMyLc*n-VEp5k)F+AHsfnU75l(;Zdh4A{W+waiy*V%uMS4rSy9 z=q{D|Tn&`!b2rG!lNVY|c|0DLNj)&|e!94`d@Zl2k&!Pq#!AO=8BZ(UVE;Z#VzGH= zNH5yM=(jSr8DXF1=eDIPI~Wbcy{c+eZ96ox(`*vPcUMFb&j_BO5TG)L(23_Esb6WT z>8HfR2N-Q@*G7WnuerJtbf5ADN~m$y4gPd6k=~B3Fx9wRO4G zq{7-Q&n;s;9grJzBPP$TpQ>1b=uQ)CmqVImuB!<(Thx%QSzwY8d>Tw=ENMWA3E{PR zw6SKvoAbtrwzaf%3@+&K7{!R*lF>yM{1sYijY_>jpkTP{0X#P6Y0s>_LQ zk^bwIoE03nS@VGUmE5>kvl>HdaqfQn=I|!hSxA8vxegH4ac%{ILdH>~r>uXi|E2QM z*q{g$UHX+!L+qV)O7Tm##jysHE86+@@7D3>00lbJKDqX^;@ZZ57k|4|l{J3GcbHbU zSiIZ?zg9T>k!5HRliMUT9^?^LMLxaeA8yqn(UB2J-~0(e$B&dTo`8rpF%e+hUmpET zsPS4!WK@NBWzkpob&0U+*QzZVx1A0>r}mdxTbNUte)8@Q)F*qFFMKgls$sL8{qfG! z$;E2r4ocS(P`uGneK|OBoJ#;vTW2TF;DysmH@6Zj$My-B}tYr1~(sZyy`Cb zsJLE-(LhN4UpavUb-@5i2)!%eASjHWOT!L#T6O0n!Bz_K28#Y8@~YgXmMg_K7k)5TAmW9H*;0@Glm-3<6d2@g14k23u>hzOlJ& zgyXc~43lXKC+NGk?yU(yb2sbL=AUNTWu0X&m0pBUU*Cy9qWh_eiFOVvXn=}7)cws= zIYYP1wZ+b=Xf&*LtpdbLXvNBn8X`3+JUtAzU~=>;xw)TtX|BrzHuKr63oj0V!;6#k z`yh1d(}O6HIby^gwFnNAxgN_2jfO}DdM!r{0NXgJL)VNS%z(002e!61uv_WhovQUH zPXkFFxNGzuK|9d%>5h$C--|9FmN2WfTQe!7kfmNabkcTbwUg6%+gEQJG>Y<=Pk%BG zA_tFJhO?ck*x9<_lM7VJPIq_(Bb8XW2ouxMNZnJM;!jjdK|J#DYVGgZH5u}&;h>5N zAJ6-KC|ZPs0=gm9P)doGj0+*M8P`jY2IBVtST}Ah!+N--aNxfsuXtc*x@qtWRQN9w zLfLMZ>H7olr}RTY-kGmY_nz~qD4%^-IFyd9uE5XCf{r-W-WBV$*hKZ<<~xZkzs~eO zl<8=`%MN(*p2>$`(4O$uHEU9v+8rYMp})WimOCZR(^W=Zp3~XAGwb0Z>^vvUZxwiL z6?_G;zypEvCG+KrIpJj)D;_Ymr0$*k`ueQf*bo*smbE^w*QNA*>fH$rInz;(@(gxf z8gcT;HP`m->k#Day-j60Y42v+-Z>vA?+Mzx_4YFQFj}~!@lzEN5ubXW2w}&Pv)1mz z48v*ZSy~Ixpsl=c|H5m5km7m1PMzF|MS-$O*%m9eUic-t5UPh2m*jd2y-KGhNFO{D zxa7#)!iIDI<5=bs%s=iTHnXZOkoHg3;n$_fN7XBBccRt!}a zt}#$iWN>G;cnfZ$Ltl~RN}v74*6QNYJIci5IbPfgIv90FPDe_O$vuXk`_AWNL>Ic| z1hEEq7Tm%SCt5uUFd-;rN058X-Ntcer#rLt7S?BGEOb0KMuC&wZ5UqF*Vp&FM!=%$ zShh=p`F*03Zm(Co)w1psS9Gog_0X=0VBAFu8dQgEK|(HpYhjB2ID1B;>cmojL< zm#h!@KIooS_gYmqSe%7h3{7d96xj^A9u? zZBC^dVCOKlqoL~6;#)JprWlr3XV6D)zH}Xgg)1gpSYqszwtKR7w6Y>#R;bqGERq+% z%u@fzE$+wzrxv3*<5?c_8Hk_>bkr8^9ZpkZ)g(df|NRI!Btj#pn14{nGP z$AskoA^G&-)Wm>V56t;*fQY8j(uYPlyQA#iTzUr;t{`PHI3 z$EB&a474cnSZ!Z?M&*9~oa@9#Nvv+UyNixPyK0MB-r+J>d7^BU&OeBn`5Yl<(OV>N zw8t1%L4Nhp{IBII+a_Q@2o8IbzF*U;RVg{$TG#W{ph@S_w8ZUtAh}C^A7(>g8y)WJ z5duz-eh`Qlezd7Nsb0w-jW^_JnvejYk?`|vnpHd=mJ4*(T$Pdh_#)CHxg$!U4B2P zbtWWBsbsX)jM!Ejafxb>igunTUu>VZOm}1^*N0H`0iq_wD}2~`#|Qse97#3$6|F8E zmFU6^_k|aXI!k@vcu|x9y1C-%_gI)ahGXX4jh6^4J8T9WK!f&Ylgaa<-W@}wx(;p6 zLJy)wy-1)O5zkri7AyY8S!j=mW#rDjl&l@lUCoT)I!{3huSunyyxr*Qv`utLJVzX%1^Lg-p3;gSOWCWmVm>`B96~)*?du8M=zy z=UyD*Cxs|-2R6cMsyEx~9%#!WVHz`F1yqWLzJf0O$d&m#B+Poo&NPorEEADkD?sdo-Oq8%EGvJNoM zF5^Ecw$gm~G8_+!XDmJd>Yp;`D>zm?5$VUj9v=E|JNcjhuz>MTU`y?{Q@JQ^eIWYy zcx?FvIjssk3$0ux{!GnxZdZ{QL#ip2D}>_6DqX5AT&iV1C?@qNir@0Bu0(}Q(Mx4{ zF}|$gskHTF3H&llVD6I-^xlGVOy;@rt+}pp54V}Fub}@BaJpbIX}i)QT?0;}83{a? zk=uCx@KG4-U%W|nCQ}ta5~tnDgA!HG!>R+WRn zIbfAkI8_qJ4-^?AJcusb?MV){ZEzGTBrHjfI>={FG8+bViz=?eK%#pTdi6iwzE$dy zopD2`;f*Yg@$Hv&xOaK^ixxwCk_X49~kr6jOyJ($V zBzb6epXC46v_o;X?fjKqtD~M^x>Ew7u$8eWP#|_Zu6Xj<`xK(;n2;dRC#*2l=O$n1 zNpQ#`m8rHtqW|tOgnF993rP%Pahr`FBBsLxDGATr!0%!k{ow)Vc0Iy+z(8#p$Sn(w}0)a!#Ub8ph@G}^qS1-NUdL7&$#mvN?rAb|rjS&bC zc2+H2qbd(E_m`7kK$#y4u@o@p+7CewibwR$GV0-R`Ofw={e7KtCwCps*U`HerubY? zVd1eo9w)LWgwJ;{#@XBv0F5*ji*K6qMI~i-ANmOJk&~$_bed6Y{#)UMazUj>Z)~kY zCc=YVp?FHz(E!%(z0frr5Uwc$u@eKhv_Dh>PL-U@)szuqYyGhd& zNQ-kiEl!yj{w+F4PVr5=MQxMG6+UN82x2zhc*1^E!p1Pm91$Tuk^byv3F^0w7DOzB zcA>!bXz3fq+vnPs7wY;Occ!5_YL^ z6QM=`9wi#N)I9~E z?;^qsZigmTPYh1s5jqg1r*aYJ#`9>em4RPn~aD^f!(>eKG7ffBo`$_n)R7v zFl1;DmeH#FQRa)az)w)ekqycrLT%;Eo{Z+aq$mPR0UmW<&7xiSRF6Mwn(?ce;T$riy3sNgL6Qnr0)2iV^5%K<(%HMQF~f~vm= zhHsmFY&K;!rq9c!M02lyvd{+B2)a4q{voId$)&q3vwJmeD&f-^EB0|cJeYlp?#wl1 zg5pqNPa<(1?=L!hc~|&>xH|!ybV^6^Ci9>2Lr%wiTa<<>grw8&fc8hFnRO5}!qaXw zT0RyUjydMFn)&AS+IK#}J80)UO~J|@)?9zuW;Q_ce8PLkW|Dm$v|yo34)3F4@w0W+ zypEIG?^eQFkP6ao%Z$mIr~6h?t_x{ajFlGTtYPEGo$b!c96tqubM70@kYw@)vdaZ9<8LgvwO> zq~WXE=-eImrCm*QbMGw|(!3*va@sJ8=d9QKqRaOeS{_QR&P@%;K{!ABVJd*IpwBHfWPJ`|s;_mK|*x&{oT``B(FJ`$+;n48CCXxiI{t5o_wrOWGVll2!h##Ami1Cu49NHJ=ov|4 z#F1fupG5Ssq7=* zv_t0G66OWs{k%r51hw7ir<;Q%VL#bmC1k^itz5N(wN_ru85QTVi+T_WSJw-PvLiZz z8ew5>I5_vY{U>>NJ2$Hc-{0Zm5b9A#0f}=y&o&nD`c&OH$Y>djtx+@1-R&-efL*1H+z*YO-?ep7_Y0bOXtIw_dRdJxG9ix;1#7_lay;WFLd2oP0S`fwaJrUYZF?Y-M zO|+1=x3}Q@TZZ9xERN&F$?_3@YxC^*YZ@NBri0?=m-wNk`aPf_@|PmLdi!%LL2&AI z=kVbM(#ucV#hBfuKH?{;0B3BNujc^a-H()2(SL~;ao(nvk}a$~7JSxQIWfT-+q!;I zsDv1$h;2~^3RoH!gGqBwO3V-~(s&t!phWf>}4fjAO~ zxagHcfCFv%J-8z&A{3urX&FZy*q4d5!ki40;0t!&QJU%s>22&jBM>KbH4%_hqGe9Z z{5cuK)!ZXtGNm4S+8ndAhZCD_1#`9b{i!P{p)HV34Q%SCM*Z42k5s(V|FEkM&_P?G*kotrA4QDYeggnAc_6}QUbVGBeEw3>#8u8l`IA6W4{>DryOgW%{BOA&PdCfs#4ZO2JrOp=WPn7X zDY{_GP--Y^_y};2Y-uvx_1q$6Rh<5lQ9_`j)Mq(~hw50g7mJ+YPILBt6UOGnd@>vO zt4heM*b!){bz&6Qb6lAAuy`e+H%ZGlT=v_LL>aEDZ`zT~Ldv}D3tK@X*vrsh|a-<6phinlOn<-@RhJC^e=>a z=qDukZoYJ6zW_yZpLloO?yNzMA?Ptn;I-lqw})2&(SU*evRgC+Mcn~nlUZL*W(G(W zfhR#=#4DJb3KT{p65?y5?M>T_?1XyQoQy0YDJ+h*(M#g35z{;S0w$zuqcBeYcQIi7 z_F9IJpyb&XgjFmU0*)^Q>YBKQL&%~pwEsFLlKG895L>(2X0=(kAJV6jy~qoBIWJ=$ z%OM`uzVa5L7UOG9XO)dQ0cDwe_;pHau0ZXU&BzA5Lk2$pjqMdmw7SO*4h}3!@4lHT zwo3r1&vb9aS%uY`-iMs8nUmVQy7|{LlJz5r#x^Y!kMAJ|ZLYnuz3^Yx8TCq2MobB- zglhN9BDM!WFg45cHqb+jWl!^)pH?Kj{1lfR01MeR+5A7&KX4P9R~IXla}hU2;o9Dp z(`xN|$!GIp0BtL_TswA#1k$&;e4GKr%rsV9Ryg`>_J7`?Q_|Ejrdg_pAVsUb3fszj z2%1IaiyMKQ50#5>9J}|0deo@6S-~eK66kfyYjEb)Q2QIWX2KZ6 zG-3ti5(uwTeCEi^1sOr7Nzqp%zdQK#!els1XEs=9fJ_?-gjTCFdNKTup5h6 zCIKgb0yqh)QREP62E-s$b+FUMBjr~4AdW}aS{t&*wwtdUii;RfJRQ{P?OJ`-E?(lx zzazeqLGe#!)p+2j@jq|P0URF^-oDLdKE`W}cF0l&6}l*2nF7+nI&LJTP5 zv0WNMZSLM6M$zA8ZEeU1<#Fi!{Dq`2py$$lLRgi|`Z};h)OHnzg2CRZ%3ktXG8=p; zkfTI9_|@`9`LibO2iEfUNE1YnO6@7q&ly$a8>Hyd3@G;5t8>|5CrW~+A73UO zLPIEO#3tiYFbv_h7R(E_{qXY7Q2obIPm#^R$y=R_stc|V^ft<3e2c!`0%Xn+z@N&w z%XEN&a=$fzMv}^Hym$tX=ak*N%BfjkeGi0+g3N9qitpAQ?*PS@TZ@7EGIIh8WBYMA zl-w=%eOVaoe%VKRu1CIS*$17^{v1t-c0+thJ_O}_&Au<2Et$3T^CA{Yja5!VRwL0# zdI8!c^4rzsfwdkFOS-)!oTu+`NAOte1MIrgAKXyykf=Ty>`YiQba=t?1mPE0bmF(! z=!SevQgmWisB>r2nbQ@^oPodl&cN}Q^|~W^=RgdkVCXlvmj5^*6mQODcT#+N*KF`! zi-!{f!C+E4jLNMAeUkY0zx$)5(}WvH$piTT?doT#vqk2D*3+%UPB@9KJn1WO7`J=g zs7#Y7xF*?ZJ5=m3oXPo+k^Qnq+dhyo-~uF6tQCnIIU$q^K`IReN`(32$&{8VH0{b} zjmo<$o!Zho?1TZ^+O~8{Q@H{*cp52lXsNN@!C+M7z)!*p(1{W1WWq1t_nzLe2YxR) z254S#p}*0Fl>j5%cW#j`Sfprwzes$(YL7WoG>fAONCeHH^|d##zr+ZI&s8Jtn?U^{ zNO+-589pv04AY#~rrMVdqMYVpeDRx313u~Ho?cnN*o?m)40I0`qJZJHR# z*BcY+<#A_l2Otz12KNl7o9s?siLF0kMIEjr z2haex7cW8E8`_KkcH%3cg&PNZ*@1xtkMl8mlKK{jjgbpb{~+`}k11x)m*CSjIklk& zL21{!?*ldv3!HmnFUWIL9&+U=e_sP2&28pMbo&N|4=H`Hory`hJcBLi*hPHz%DxmHZq<*$BQ;B87X#V*BPz&0d zJ)Oka=$aVhUQKO2M5|ZMy#a)TMs4veN1$g{iy{rLjORaNyVPm{D@owZB15(vG*6hv!tH4g9~Jl6ICP!K$B+{9XXux<1JC+e-Y zw{CXv(LtkUkWEUjFCO=*gqfg!ezI6Y8hbb>cOlA_0}h8@I*DLXvSl?tzT@uHCWP(7 z7)8&O>2ey0Y$QjUoa_a0fVW!w@8;9F-Nu*1R(9n-2<{QSt)TF3t-r|1p`oJ5q~NW` znT5)^ZfBdVxxPo$(%!N-`IBDGO+rn}efjAF%jNUSVgr?%{iUf+JKw9kn2+j}v+Clunavv(4O|qf zW#G6W>UU0|@@%ZVUbZ*WA`ZwLFyhG_cM+Qa!s7{kH;pO!x2997FSIJ>WzU~%XF#Q} zy}k;bGxcSM^D64qN@fob-lRJuLIm-7MKfms&N{6NLo@p9sNv722Iciuj@Z_6vzyhQ zXsN6F@H;(I2_}cc{6b|hNHmyA{{mqK=w$aUZTL)8Ie9T<(`95%7fEM&bCxgC4iCh6 z+Jm}x34Rf}c^4~HQf}P>Sxlf~UMAV#-@Z5^O|2jb$cG;Id)!i|+DY>w0hH|IgE==-OQ_a|e4ZD>JvG&dn56F(J{YaPBB|Ku!+slz;_IuBK5#v7a|kL;#~M z?``sJ<>A3nR`a|=og7erT*+oAjF>9u3zgiHDbsH5h;THx2B}E7o$Hj z@cypf`|z82B56&npJ{=nMJ00p7-JFNsQRXH+Y#c&?uADV%#N;-{W2RfpXP<;`+C#e z8+O;Vr~*FvxR45@I>Mui5uqwgtsC*F5$CgdvwJP6QX-tvhRuOEmNK_ZafQ}DvLM@U z$wfc~!q?-st?1HQA)PlwkoGpR4d8LDVWK!w?Ne`wCkNn+aqoq(eM<=$Cz%>^TyOTz z1wAkN842{^(TjCC8hxKV^)`zdX4ls`{)!3`txtWgnO%v0NAmFj8w}ZCvF*!8e2|m* zegcC$NbbqY+S(+|>{@#A)0em%!Ml5OR=I6GVtCr{Y2d>5X^Jb5`_SLk+Yw;qP0hB? zv`}Lm2hKDqbN6t-WIc>%R0#g6idT4zQ~| zH^3MDW}E;$NEETDF5aJ=Yw&etZli>xDasG5^Gyf(%k_3114P|#e+vK*qd5JDkYEKt zpOJm3_&h@;a0K73RHeKQmCiLMEgFxDIq8F|k~dB^Y3C-arwdi9~#2#r+=-3)28<7VXAw@y1SkX9a7Qyu1c7x5B$BF zR5Jw-;J~Hi4!!)DeDFH3%i0#-DhIqBKB}p;<+^J(>7UqjX@I;rcb?NM;9bz)*>6!) z5a(Qe0$;p7H+U=0LXicxbwGk~HWHhL1bMjj?dp#p*1XaJ^%Hqn4}5wYwHmx6xxBf7 z0Zq=(kr~ib{x?Ibb8QNfMU*TTztRw~emvCYELu|Y@*D5;v|i7Sz$IXnR(Ed>tJNe` zINl$fev0tyA;h9dVB$U&L`$v6d?(s)m8KxZaoH4e^W|IcrF*TuJ)zl%6EAgh7a~f) zuJ_gIOscdLAw4t=-`(Mw6V9B{HdJCs1=V2sVK0lbA_wjVg~!B zxLxpYCsq~l{g6@}L9BeGQJrVbU$O?0&HV!?s|A++Fy`Rj-IYR#|3#sT?!`bwRb%MU zLm1%yKhM>|A`JB6h?d+zTgHs#g2DvwYLk2TKxb?cj{O8G)Ia(U;Kwppr~HF1jaW|e z#x*3xiz%iFNG3ZYxzKh?xAsWz`vIH3`>MXNkmSu!&8owf8svp1KxTOPX z2jdtuGVv#$K`X_uJgt|?L-`o`24g$8Fao-8I)4hJWFYFr4haYDmpy?UlWe$od?_FH zlQg_xDGHBZq!{LL-ggHkP8u@b9AYcxdroCHN!ZueRNp~_-1lHbUQ71AM6!WwkmKXN zLW~)XozM{1uf(ck)8osoN5i#;f_NW}8@geN{MY|{pFVm%LjIch25GnVJ4^d#(2Ty8oeV^2lHNMhrF0qeDt(?@4n6j%R8r zdZBhq%;9(T*(0Ptb7PkqkMp+l^|DVLRg$pjwK81%h_`XIXMfE&Mo$B{0;2+-8^ePO zhlnFd(nqKS)3ySx-{>6G=#%Z+ z8MdMT*SrS&W-#>E-ER{$AbBm_!+nLH3oVtuW5Qs%qKR+Zna3BWpDZyN``+qBcpT+} zqBtz8rs^UWGRqB z_ep9W8fK0UP~9m9Grbb0d~eIZdCUKOclQz1L8) zG0c0-PKIVrkM2#69GUD-oWYr0hx$yDybPO9!TkBd-c0mR3Mi6IG>6Ida2S%90a+=; z4E_WKg<(*0Vd$~n{~dfIa&14eB@_TqtvpLckBZ8;2&~i#6W`JX4q}%!7LT1L071WW z58EzEPzFpu2R;KanvIkeqd@W|E}jOY{QCzc3)ZBk;4HP~RP2K=2gGnPh`Hi1j0ifL@_7xD1aW`%yyBbTS`+r!m-FN{7Brm=5wJFbnv7 zk=4MSeDLyeehk<`?^XEq%MZYek7Gqa$y0dHnImMP|BVveaKI{s9+ats!S|=_FyROM z)ayMFH-8DJpB0fmRLQ(j~CD^?4A7t5OTu@-i#{v z^j?(NIe&=o3SdA$K$f3Kx;lZTmI<@+Pw7H%_WHXVu~)$d1kb>zaFCeH=nQNaoNx`RFmM z(PSby>evb(z(9*c-|JuEW{`e}Ha^O)*O39FK(@vLYD(<*yv`M^n}tZ*e|QN1#{vM! zhQ7kT4P*r1i{BL51*(=?^%np8Fqd9FF3xqP_R}=2gVy24jn-;`;M`p;yl)KG`<#kzL=k^$$D$mO8{D|T-8=rEb`K!nMxw>U0gO;_DT<} zii^RPx^@~-d%5=8G3Zi*MM)Q^&VCn0qPXZ|d&2M?$m&stQ#@#6zw+ZSzopg6=NdSL zu5>UK6n9ra5IRW33cB`|B$Fr&23htN=stz3&EdF)pQT)E)N}FVn9Ls+#eXsM9U87E zxqw?wk`Q>=4qRM)`=0jLj8-I1jN(6@9)B&_;7yZ)ob?yE^4@x0-??ps`*@#;inw<@brTe_ja(FC)4?9ViI2box3IuMeIW%0_1|?=^pJ9OjlD; z`#m-JS#VrPx>Be~=&?;Oc!@5x57Md6O@W9sVeq+!S%wI(IBu{6iy&}(25FoZ&NRce zBXZ`^9)%g2fZTD^y$)0LUh!a_wRf%Bm z+QH$bJ_sV_0-&B?-h!aIBzJr$VLE6VY2SO1H57y?(RZf5ArcZUh(LJgcnI?h)OhOv z;H*zm-`Ic$i!Ap0o=}AUML)*@gkJ`VERA)xta}f_Lz@jx9X&b&-RM{c9Tl@=v04+wK+PS{`l<`IMEtRwF*OZ~_rc zT(#TQ$uJP#$2?uB9pPU35&VoW5z1&!nk&IelKDn^rhv`GPgjxm3$b25DsGPsfOa_d z7hsS}?@XE5z3qO@>G#!$)aR8&a0KiH!MZyD3-RP$o3-QBxq%vLTbsJqcIlNDImvzB zH32NEV5>~-gHk$hiq-H0{XjQ7j|{3(#>-=WIc~YBs6<= zci|A_9_mL~NzpLKnhO(C(ydbvC*a@GLLMbbKu|qPCVh#it7OaeEg}pK{98LnKv02z z1K+B}XO)Z4pX}Zj@?l_a|H-0;=KlBdhW>{K?PBemd4gd%jH*TsJgbrX7K(1unk-%*l1a0eFeR)9suitsCwJj>BNrjZn~EwG$zLHGfBk&`Bzhn?Rob{qJ}B|Mhhk#0t!iqP z!RNB3_M_a2b|q@OrXw9eK-_qqlTqH{m4=bA%fT)5j$JdCh#vvO=Oz6;aIyzbJSSoF2qF%Z;J-cj@3$$COVF3d34&pl{6Da}$SU0h zQxI=<Jc^S&(X(_QX~*FS>y)N_+U3Il z(jO7V@&mU72@hUmHCKU*Gri?VucDbM!7OyMZ^scu5&3UxBVNqD-g0%)D=@jGfk^5L zO`@>61eIJSiPstS_-vzMz0JAvYnH08Sr9TQMvj<+29Ec2#} zCqNikvKdr}gv3pdjsh1`wO86dN3w#~Unft!juibLblna!q>gcXOlou69I#X@Tr&qA zTxNS@m7z$|SDQ1DFX;>upDHCZF3J7j72zr9$ev}Js=N{^d8foIVQ|vm$vzm&tg3OH z$WxL%=k4A^ zd8x(3C)O$LZ;ctha>$9hN|r9Q@qM*uY4ZH0E4Av6)4XG!rUn9Y(CyaR+SH{kq)N<< z)?I0$(OjG3S5Yzg(RmzP^_J)pD;cmW$7Tmg-KoT{cZe+x=z5rK|7kjlQ|?rcvPbG2BP{33ATVEOX2D+lz+E{O_*!z|-`5Q9tBXNxui+m@IQ`&KXaV5fV*1CE zFq*j<=epMJ%$m<{x8xaC9UbflWJAg8m87lpfsE@jxlEHFrZR}u;@bzZ`<<+MPcs%x z=|w#xYQ!(+fn2AVKBBjNE84dD^dcy5TF_!!0ZL?6R{Jvy!?g$!hY26?REjKGYZP~| z1or8=^v&mb&K)1Q+q3Z8JHGP5rE7V>X!Fu+fIv3Ez(7u3(SI0^>)o}InH=X?b3KL< z$65Mc>)_9~ouy-ZaLGKXC+_gBt8Z7$%r#An%7cc!X`p=)+dUf)5LoO8-_gk|63Ea# zTe0zD*zDmEV0dK49D~Z|56V{$yBS4k|92bX!ExJ9blexK6xA@Anu?lXi_%^z(u;7N z0n!*ant*D#x8Y~HCf#0P*iN@7e}G&U|DfsZvb?tPKx0>&Gl#!nfw$yl*qVaQaW;p)1~@rd%AkfYf6U4KVMVYE>_Xj2$V1SI}bAq z&|&-C=1FRzA|iZ_Tq`_pRXmxj0m=w2&2!6v%gpi=_S=a8!e;S=l9iwCcZWzs;R{I$ zBRSkQ@r^^AY#e!rw`r zHf$?7IG-eHNz_v30TjuXKsiGmPynY78y#N0lC)UVi1GAYssMVVGZOj&1+*xMT_5cO~T|^ECb5e-;nlvTaunHi@Txb1gs+J8`|dEKe6IL@ci3c~WH%>V@srY(b4-_`?otG|cnxry1?nu{CO$ zS||0u=Z9Z$x<49N#%*Tfh37#1xcdgMOTbmG^rM1W!gM7~IN&(2FFsI=XI>q8Il9^} zh{PY1V5a&Dc*$wSwTzTd25smqdzLpS+uK3!(ZNdX30hxV~QOX=bS1^=7r!=%LbsT*gasFf@PnJ>7@1fe;qB-pMeqUhUkG8|#1`c8RS4)g}9X>A-LJ zsev1NcPcG(RnAG{fE{)DK}-Xmi=r4PjRB7Zpwgaw4I6g>x1r-E-5TNB*CqwM{`H-c z_Cr^#T^ULkRYo7Bw&vUMGyl86h8x43a{xSUa7QP13vy$6mSz_Qa zdwdfgriMzz0QaBy4m#jWISgK6a-TaB3>zMIu07@D_tqi7V;5m%bu5Ar5^kGYHw3V% zRcwTJM42CoGEH`po$f-8LwbOas|s928=d$Bf_uIN>&&ruQE7o^7=GjA z4%#@O$nz7|!}|LBa4RX8O}J>qF$SSVuTdHd{@^a1#|F5)wZ6{aw){Cl@aO8-2{$+r z#9?lnK1zxKZ?g(7GipmhiGYg7MLAxpmd*!QjDFM?OOBOB+};OinMI5G zML^sbMSl6N(LQ%-+zv_b3hnf4$j#dMSzoT-%13Bz{At?Y2R)w&Cuc~vF^9$kxy3kt z+8k=8gS<16V|ci6&tuwk6y4I7;wa%lUsw?_lx$LVP83RQQb}#+mJpHPF4a1w!D@HrZwwtoQvcu(_>>bg`yS zdBZjh%r)=tBdolpX7$MODH#1|9ColikWFINB73m8%HAC`T}G&&%n>!Cvnd+>vb$2-c#PF6!@rkm>%!Rrjc6- z(n)A?u|F zxT8_1<@XD7#bbgTM&XH>C3xE#HoD zmEL-#q0g$L7&yGHzvpsd_39Fd`)X8x=x=IC7s5=~t1tnUh4qIxvAT6S?5pJu&%a)L zsZMwHVCio=Q#Yf3#1V_|?}^-s2P14g?GSz%(^F@X6@$;aSUDKfRC!&R#2R-G@`p?8B% z1zg^`m#9UX2vAdj;XD6mFiT_2x^XwkXgs%+?k4C8MgzBc>gd)tVJK-Z43n>2yjpJ_ zzR(jUU{@Uhi9ES@c%dN?#WlA*+#-lOyKIr<+RdM|pL|DGEI=s5<-k#+zUd{$TWU3$ z3$3Qj^no{cnB-(+s$L3j4BB@T^>L3CsA@Yr>TzDEC)NO*ixXi(($@W%QUTGuzXZq~ zuKb6zBL5~PCYIK`q{fAZg-xT)#l9DzqaIKvD6h}5AfA|UMZ|ehG2%pXQW76zVjW&> zblWN)D}d9W2j*PkibHZ6%4tvG>{{IdhE+j-`+`a`bxTXj*?W|@g|{8B749F=F%P^= zN!jR}E@Tj9%Nod`!@uZ2H2Q4kO#Hzw#c6TkdS8=inEwp_ zyCv5`xb2^$CTWmUtt#BOP~S;1q%dLa&5;b4@ViA0vi}}ru*JmPH!vBv#;80{8kW7T=PA+FyS=en6It?jDm3npG??yIYFyRtCBr$UF1!bXke##!w;jJ@7fbjeV zg-np}oN{V_T;PH+ZRo{6Opg)`*lm1Y818J7dMO0h(Jv10*{=H%jG9AlVk^i6Qt)$- ziI(j8-VI2qSM}qEbidVJcei%FvCtO63MAp@4#jM@lh5zZ)adZH`4EaHf9KD>$*F*w zVmJfoHr$i&U9!j!Q|4PJfhVv4vlSFIkQFtp>{1 z-9KyxMM^}*%GPI!&_cKzY-(+74IP7Q)#SSkw7YJ|CO<$|J7@)z&8HSV(f+uJng$&U zSr%wDAQ>CpX``CX{N(rsZ_krk{lgsgUk;M+Z=ZuoIE|rWm(;Qz9>BbgAG$M6xC@|O z=ng5DB;)_{U31ye6X_YJ;bsAU9d!t&csQe-PQ%;pY=ssw!Vu7-RrqJv(5F-O!h3bi zDvWU9*xb5HbbL=Ld3xSsad&36u$ci%UvF-xYX9|8z+3siGVH%XfUI~_paz8o=C*74 z!o($%BOJ=zk_w}uLPU>pUOH1d8)|}comt&4GXV>pH5x$jQpdejAtYbBMJUw-lQz5>>@PQdOUfu zy+qDp)VF7{pFo%fdg%{jDHJWRWpaX~h`bKc+gqDbmr?9Nd0c?ejZzX_94^6m;`#a- zSCCQ7&N4?DsoCr`$t<*md59`Uv8_3}L*Xn#tkL^WTc`fXQ}( zYBH+MYwZM%D;35N4eVaJ&-e(+kFD$eOZq^)%yN-w`%}xnkCa6lLTk zqmasM7!q{VI{jFg8x~j$ZW{pb;&c4!HDXw28pPR60mGF((_c*VaCMh#gLk1BF zsWs{83x7Mfoh+pIiR>lTru*b0=wa15$ht7XW{6qg1>gos$P3ybEhAlCkEK+fUg=V* zxlL_O(lk?3&Hv88DH-<&C?3CA9_V^nQD}2(Ddor;BzXT0^Q|^?bV300a=~Y z(8*3q{}iHY)A4XJ6RahO%j!S0fK)@$zHoU?3p&iWkp`dfel>J{@8c2D+8P zVk$LnRB#mOZ7wb@lXjcYA0Md_l`i73>H#YokY(&O%1`Oinh9>vyo@GczCMaHapx#1V=%Mzk;oK z9TK~x-5v|S@<{Rx9WT4k=3+~6&E^nInI~izXXdx#>$UARo%_}3%2WO3I2Fi@1?Dmx zCpPWkYbY@tt)QbdbVUDsjV~?d8P}BxM%&sPG|Bu5xk_Z^63JgdjIqgHG{ogA3HaC4HG_-qhwLxq}#^a9Kc1+Kz6NQLMKYa z$?3YWQhC*!l)>Tm+Z8aRsa@6_Gz-y@xFgqWVx{!W}`uk%9dONi2a=6a%a&uS73QQlZcuC>wy16DAA>{HY zGn4bgi4zZ?O2=H2IAaws6+;|ut5T57Z5U-Nyxn1JWP~MR^Eh-|;Y~U+CNq9X`fsCv zcK3^ZvYjXcR`P^-6)^{gr_NT3P^Ly%IK40^VtC}+$ZOUuaJZdV01#NOo1v&$KE8DQ z!Qyxmr`=4C48u0a(P|K-8na6zPyXlvn9pXCNzX6}?># zCDdMArK4MamNraoH`K1N3ykHrYWmVifuO;G@+ z6#A5Se>J!X?kzt46?N-n^(_j)qpYds3c#0DJB$7>Ky?V;mY;JKmH8>lY-b zSrDZH+3R%AZCdI|xQPfuk$B}0~$B_<%29K-I6H!A^6m1K9386aOZF6e8 zC0_1j=x4bIA&Z52-WmV~RFHsr($6YT{no8pCjodhLH6-?n(45Jh{v@DO*D)wR@8c5|?y(dpIl5r#Kupgj*-rBY^-%?P^--+GHotjsNi1 zKoZ6isyZ$<#Y^oPC{f_&XDpXe;fSKyqh)m4u#gVnVQUcH-na&+N#N2s`nisucm#le zn$f#-FXL2N{?P03{xY|hVT|ye$fH?Ik~q7hzruYcj0eAUI>hVV%C|}K;J-7v4{iI% zvs|!CLFk-7W@s@G(%5udZM;qe=)=chVHDf&z=-))S67ciI`%`fmrvOO>Y?Sce0UNL zDyKlwKyI?mf&U`=x)5~#9%SIW z1ae;`w<{#VO*NUFB6`}jp6jbd|9Jistt|@dl&%} z*jjyC|ClNw9WX~G0Pae^)3+W(xGcW{&Wm>$N`-WSpz*ql-GmSsv}D?emvjHF8sYOH zLt`v|vY>5WM6^=K;T`?fb_17BBDntNvjxhKk8;~y)o*x14K&Td*61ZijjV?fKZ3bg zwe1IA07osLuFc40Aphq0Rc0T^M2_~4UUF*g#g(1#9r`Gx5sf9_XTZOI;>{mLnr(jD zJDLl#bo*R(uQ2*O$2}pdeRu_P`hg;30Fh|!Jo{xo8$O46StgdpoKu}WsC%FoiA7Ks zEXYlEC%z>UScipF&5l=0LDkQp`Z zM8u!mwzrznb;=At!GU1Qy$)3?5koX}{TRC@El{vtfS`Gi!~p!&HK1;qL!8(4Pmg07 zXku230$6O8!n~cszQRHi!UzQ7L_#DpmrG0C<>BXy5hPm>d6#Ay$lSYbj)A20)Xk5Ft{p)fzkc-2dlW_-lg&y63f|4e9{43 zd0udLDKbfMs-6HSP}#CjyFQ0GNTix4u+q)1B=E4-k5<6e(Ykx8-9yG^D zAX)s$1%ow_g(H$6lXj9Mwk7zLxb9jX=k~g@mLt@TFz$6A?dZr>(-{4=oPHpf12EJV z5J?@9Q~s_iD*QH+NB7fP%b&FVd4tnpsPbNkqs?`2Rm?%=SYggb-~I39Ke=DmW9ky5 zbdegQxn+T7kK6VpCc!COXPGbti2)=y(<{JjVLZ*$P%qM@k#-Q2dZu7DaT!sq8U}?{dNBdS2%C=$o)`322I!?r90tZ|Pg_0B+ z(y^nc6sd5jv_IC|cW22;3RURx@>H2Mp5H)w3+JB1ge!ir4%(QC(v6}lZ4>W#FP<_F zgt$eQVSLp>qcEed@RofjRM$ibC96J6i9gKe7CGNJBtOuJKt97va5m&Qmw6goJrG(q zG6d4z8}?eD6-Giv?g{urWRIWDySOtStdY2DS7P%?cLaTs2kyy>dvvy@oBc2aw!m>> zDXxLT_L6wdTm`j>?v6_E>IAWC4S_2SL!?OOTpRIM{1g>+|Jf-JumG+`YpDx}>_g%j z=6u)5E2?w~3V}ZvA9zgFudj_qqd<{Br<8XSfVogIbOcWGA^o%-*k(SO?D1q^RY61dPETtP zJKFUA=G@GiJW;mVFgE1bE38<1503u6J2cJzrFJ?euQNl`nGNR*^r9SEY>V-zmw`^9 zS(6}tAk8qJ#bjc9HB*r05k#t{XclDk=waQbK0nd5-mo;0k9X1=ic%Hw{Iw8NJ;mtU zb>xg}yaH#8oZ_Fpbp4ZsRuKk9vkL+szdx^mc-_s_d5VbDFZT(YK|M|DCQ-x>m-IxN z+;v~TICsQW`1$_^nTWP8wdOG;thUf z5!|)G-6iRcVa|Jk)PnV7YhsU{N#+^>&xjZzFo1%bFvK7E^&!=M_xBvLaO9H|wTQ^d z|4#!@uc$E3uJ!kTu0j^=!v3=yP2R)LR$+TaRCZinCXM*gD9!9W%u@)r$ z{viMU9S<&E5j9t?(?)$5CtJ9C=)3<)rUZ#sbXXc3_p(G*-Di=~xd)zMZQzhiiGFeq z_LsR=8h|cS<2Gap-Klv$rXWWcJU?Ck>uD&7E&w%=UCQCX-#F7q=0`AD$mi=`mc*+2 zGE(}h(_!qpk-2|k8Rg$+k#<1k0qDAMtU}_QV4?=*lD~)1Xg3m!`+^~H2J+$lRBt|p zU5`(rt9m2f1DGP10whJD z#$)0ZxakJOu(?O_dYxT7IxvUROmnTo}CgO<;o z#%Vsw`em|Fg8tB9pH<1XtdDIGlR2R3|Pp^8%bLS})$&cHe0~7O%Yn|VL#I5B z65C}7DiUtn()qb)D_a7!^ed+5FY@Mw=@3K7_$}I$RZX*(>^3_T6O};ul4nAMPxa5J zThZVYZ33ekP)@TYCSR0Z{Dvz!AEDz3(%w`j>BlBsPg}U4&dZ-4}eY9Gmw*We*ly>e8c;KV%%+@LhGQY z5j-LezmGsTsUe(_$TP82W=C3gGwC6bPK;<8oA5ld#7^MWhQWe;4JM+3FU&OTVHMJa zvR5<&7kk=oY5R3u)TooNeG3y-cIni2?=_%%9(FWYu~#e&Vn`3ORgSznxIx2^Gb zBslxsjr^?NV}=iW2MH@~-QTruO-qH$`-+dqVQ5HR=vTc-_X*BO{rxiVA4<;(vq^N( zE5PVQ@8GOC`MF_X2j!ts8dqenX^?jep~A_=pCLclRYV*QFTbeOOfn#yd*>PUU7Ru` z+9f#zcpE{u+SI&!(=Y$-K8486+BTqZc^mVcJphw+XGU%Kxuy=N@WT=?~Z%J*2){^C*l$|L$?T>_!f?#lGjk(Ue~Jizl6+H_ z`_PVp2b=fbRuSu(2rIl@?>>{4`KWTX~_19ua z{oCNC8HU!q!F|9h1cte#4+`u6PBTlQrHt}zAP#yne;#FBoEx7yIGiWfFg>ud>)nkM z0n(k1Fn3$;=Cu4>yMiKtKk!*SmO5}PsICe*JiCn3y%B4xkf?Nsj^`4|A=<-0*u4hg zQWOX~iN}a`l0vKv^uO@YL4yv-c%%*8y;-?Xn#bX@=GCvFZO6-ZUw9U$ISdR~x;;R} zArwmi5xvyFGPINKN#86>FI~e3GNuq#Ol1F!i|4-`=Z>2ly)=q2SpTTW2`>Gn`FmN; zGK(gETAxy3rxDk7P7B78jtah@xE`=%nn}L&gWS#W)nr%Ag0I3-i(mY$FTSrFeiG8+ zZ!>Kl(^(&QPace&GF$?LuNk-Y6j%*I4M8&$)j&x}_uLGO8@fZX0Z(#54r4gz=i4j4 z_MF&3IoEBcJM=yal`+4cMj`+nccXKlni*VI23JryWAM5+@tc;>9qbL{f1~j|k`w)o zJYCkljRv)#Wep}+CkrRCPNUC4=H}MuGu){NYq0jSQ8iCma3mq)8VtS|g+$x^W*rO~ zfBp`n?wEYa2tgA4{?l%*>L9|5&g|I1UkN)ZAb}pKY;d|@!68tH55PfzX4*(*pe`0? zCvSS?1s85z4Ipmk^N5p08jI7vVj~+LXYDD+I#FKT24G4ux}bos6yh$bf#TEnT3oPn ztT=~!HEmn__H9^wpfyQ}F%d}}@Ao*>y30HYCe~GuPN2%ah2jl|bTGrgz%=PaH8kPy zhzLQau$ass9oK^TS^Qc$83?V?l`4+v+P7!*g0yU3fsYMo$LO@Qw8dvw+t%(TMD^;1 zA*bP}PydW}3d&!ubQ#J|j%QiZJWWTvv-ml{Ly-KoEI@Twc#m&wzJx;Ns0P*$k_2j_ z*!rFi+%sQ>#wSt)BCKEdsAU8+2~R6IsD&p`c&`RR-N8$h#I(`PztRmRBxVbOi{<>- z2kbXR-(QGSOJ>(X)~kDxQtj4_U9IVi#5Zv7*$oTrgZAB|1X?2g2e3Zd{(2`T*}#IDR*KOECyfD1R7&LEcbU8z{Z_y#>TpS)N)^$VJP2mr^h;K3nxPfdW}K@L&ra35B*zOZ(#GB6gJ@!^b@;?eWS8 zU{3%4=T4+CT#%{+i#mh7i7D(z`+o}D&JXZlDh!u!8YxtWVtQ+=*U<^Fasl@-cGbO^ zHRfKj9|;nmJk(ik@+#}OaT{t~ATP90P$2aVAh_jOOXC@r>=a0w@%GXsE0z1X!1v#-m= zD!c^^v9>so`S9DjE3%mQmp`#@AC^B12kWi7&xb@8Yw{E$Y_^}BowSIt{oTG^aTm-A z>5o@pr4_NQ>@Rz|ULDP&h!b@)u6T=oClb#cuALiKs_BPOPpEX)r>W@MB$aE!x{1z^aRwy~{``>nUC z;Qb5O*kM$+uheB-40f!9WUN9aRE|XM>IYw+lV(~^G+&X!Ht)~Oe+=6%#(aTqC&<{q zWb8uHRX8eyfQk=)V4PkC`I+0Ox)}0jW!GU!gUFurcs)U~Ijd>->8Zzi~D|GUvHF4G^tRajYNo&`Rz;vJ6pc@AGLcrwR>E#O>DUy`S-Ru zI(TA>Gra-|4qIKVg{1b=3!|f>A2{{Iu7j7E6T%SQ{rIJRG2k`)?>opr3{Qg4$2~{N zC#)%vr#?vmRsi;M`rqOIGC^R2Yhd(2op3*)T>Et`W*UrI5!3al zxIfcngxY&G*eu|FgXMgdSteL%W(U81kAoqjvw7-iOy1%D6<|ZzEwZeH9ew)fJ)7?R z62wUO-R2MY!+b`g)*CxKIQgs1;N!!d*KCUAU)Ktsdl8_6U4e@XH~%8rTJgU(=cuRa zDTKY(AD1z5G-w>bU()WIcZ@HzKGdJ)^oI85Rh5*6b3*2lh={p!YJ%-H4+{!EhsR{M z0uXf~-+S*V28XNc+Y34mY^-wY^&Xd&TyrHT-5*Pr!uX8oAX$5gw|@y4v>=!?iaevW z5wAL=+R}fqYZY>{!L*acQ1#t z-N|7Ht65pJOtuS?1bZf)I~{nmdxRbCm143?L{u&8f{e`H_bD~Q zB|Nb4;5kJ>q>KGY%Ccw6rZ;f3orsjKHxe3R>A)vlj#gV zi#v{VyOqV@Alt(gxz3Dh;6NQ}krQSkoY#oiUN77Bx*IK41%#36%w6<#_ahf1h@Yrq zTYz~&>?Ysealrrw*m_Vsw;?YM9~6lM*L0}s>+44t481OcKjqqTr`|9GK)!-lCV!`s zsIAE7l1=ZFv3s9)&Ku&cg|IcBLjRA$T&af{U03d-;-KD88k7&YqwalvEK?wU(F>|Q z*1Tc~r*)dnQQer3bIYP*N8f6VRM@)%4kVa*#n0>2?;Ksfm%yL{009j+gxq1^N#TQd zsFOgiaG)TJ5r))r$fJVUUqG(CK>^BFKE9cS!vu{cn2@@jkj7XiQYKSe?##|HMUwAd z0KI{yW|12Y3gW#+fet|C41;@=onTL&2H13KrAD|K;xvcLi7DQoqJp4b00joRVe%q! z`JtpAkf2W(VJ_GQ#csxS_WXs%n&7;9INgw*`m7w#kdG95!8wQqIU>&B@DOw{6EyRY zrT4md@thdqwK;Xm-B;E+${3)|^c`rQ=ULg!a@2cyrz|FeZ<5#>PEDBJzA$5o{u}2G zdH0K76afH*Xp~H*jT23_hp&ayS3_JSBZ^|tL&|`0YxX6ou^eEvc)Jh$ImmrBgen<^ z*>+uUg+SdJuw^ou2Jq@YoRD7|z`CIAk%%V9-ST`DgC_gZh}D_op~`OvNDku z8`0p%b%i1#vVQ&HkLu6qPt5`5A4Lm=n3wV)UaAu=p?qIt!^W$?Dk`PIKls%Jx)wu6 znp*ZZTUBJvnk7Yf92o>Oz-WalBepljt_{DrIs_rKTHxqO_2|iQI~OeM<|-Y2oe%kR z$jHbzjan0s)9wwu01sj`3=9m;|038Ad-GyOxXolMD(H(`{&YX+C{0~`+xv4$ONAf~ zC>!9(!B5~lVhYA&a;L&W3_P>RH?MoX`9~M^70HT$f94@NTL^RC!%du_PhRY=Ar8az z@LnHJZ;z*{X`06&^w|sIpR3R%KN}kxPV4cXh~NO93IpeZN>AGB_D>e^{lXBuqWtp> z%pn%Xf$Rqqcm>x-4{{o}r`W^oKVk~h}qg8Mq zR@3BR$>!kp<9Sq$%6!0XlhDQgI2ByHm1uvNm##i88vUg-EasF} zwABNE5W9ji=j(PdTFl$10~1>!OK3ASkAl!~k0DTosH4m0@U-&KlTfFDRe^k@9|Y{o zG~G6rG67nOLS%$Nh}l$)y0Nd}ROXgG&vIw01CQ-yt`E$;R47EB&Oy!EDuAuq|3K6; zJX5uSk<7_hPy!N-yIG9=;L=0DI4}UtV*>pcm5(BnYED{7x3;zAJU8v8s+BoGKI3VX zyY&OP{E>rJZ>FbU4oIOZ;G>K`vULz^Kj70*uiuz2CkAHg;eUDzxhVMiAlmUkPrgOw zlfkd~;GP(U3sEvZLis+AY_<<}=U7f{-Zk7D3(?y&&Jo&H(J9KDev6!>vA#ljayGsHP>_LeW!3P42u3|A%a6e%P&XF&WU=S5L^a_Fp%=pq$ zMP}8f$@ZB4SuhRLFLx(`NH6h96iOmaZ=+-lgVO3iGlla!F9WObVjX^zAW*)8d@|@k z3r`8#-3k?Rwg9HD8fF?p>fllkMsKm7hz&aP{#%OGMwbXa?%$FrW7f;Xz`a(1Z<7in z+Y=PolnGoq4f4yvS_iAX4!nfa-KoUF=cEG)CT5t<$0@Oc#nc)t?u$Yv-Y^OaojHRx zaih?>2^InbmduB%`m)GxI@%CM2l1^Y9em(3FaZ;s6Jn-N6w-t7pHYb6>I8!q315!U z4s25yNyE8oo)|*$1PSaCylVd=Nu|NIU|Q~X+wKJ6%xjN_P|r6^Qh}8~iy`g}#S%iq z4vJSp@fKj}pubQRTEx*^kp{Q}dp1~_ROMR-mK5ZOBqYB4Ux4&G2ja1+!9vxT!Du0z zy8nZ>&ioVKL5fC>#)3Nn0lJ*~b6IV36G@{s+Ecx$rweV?O6jYN>7I2nE==L}3(@y7tVc-j@d}gzCcU&eT}~pQ*B^`D z*M)BwJVQVp9_rYm#=i+CGnD5zU>7R|JYVgXN9`mFgon`}b~Dr2=5ch*Z%az6V{E?L zgvRtLy#5bwjqOKDhq5@&LJKKpfrP`_I`zurEme6h-Q@6WZ!Rn55ua2Hk`2T)NW!3$ z$6we5RhDg9sPq91G|HiNoMqEd?2>kFq33(}zR1XbaP6qm+YN`BnG-Hfwro4CyqCR4 zr1`r9EROF(DZ)aG$ya|>MmQM{X00sgS@FA`g4ZYLqQE=sc~^VXFu?hi3%{%NitJpQ z3(3)u4S0c#)Q4?UK~gC!kA}@l^_a85>{z<}EXUh#qeD71Wj%`vJFte)#K<9yfC2{bMMS|2mULa5?VHPKG}C!*2%X=$ z7?uI)LIU7mC)E}E2HDj*2yHx64qcpzA6izVc;l*JGwo*ut%xxFB}yYdJv<23E|bX+ z{O_HM;1oJdfGoRJvupb!st+y*`E>McbG38nYiReUi3iaZYUN!sFu;#11@-;LntoZo z2q4^|8XxZ6zgd?su33f^e@1-xjuipz1Kz=0xuSuv4k-Xs&*xDDroHjnTC|jQFmvr2 zCNb-!-F9tlu&A7IS%^p{CWaIUSNpY3RI9396v9xN8eViewXj+?VxqLcNrTtMCrr3SuzIGI#bbFw#eWJ8 zy9k!i7G5lW7ZE3zsD2<74_;w(=0@Juj}HCl7wk@(H8 zMo7Sf9xz!$$ozv1H@OD3=4>}!{4g~q{4p&hv=r(1a8~4bA1uw#IMfx#sX)4&hrA#g z+kblPoRyb0Yvu?Ayk63^5BA;sdVtmB^a0O=QxA-(jZ=xKt6qN+&dIgW$jNDI=U4Yq zP9748HR!$eHYzeDgZKX41AZbTzlQr3)+_!!bw4x&)V8HgW6d-1!O`$WLPd1!H^H&> zE!Pug|4u3FFXpNsnR)gj*c6|9EQtFfkB%uzrlZ}fW1}Z$C%Tf<)BCh@rOY|HA6coA z@wzEK6%!OvO+9nV#xdx2uZy-_Z1(Fz)*A379ByUzss_j>iMb27AK4fgP5yZ;vqB0{ zYAX^pVd4VhN(t@50p~V{lk16QYSl!kbJpzJ7+i{td>ymB+XB?++qn6}Toi_mQcjXv zJ7Fz{Uip8zEI4nr^Y4?7UG`wPdsdQ{R=Hu4Hq=aiw-maK8<{$e4V4 zb&OcidOCwEmPM431ly@xjyuwkORC6=HOJa1s(qAR$wIXLu8uJ^bzIsvPX1)4tfAxRvit@okJ<&Xc--nq9nOFG$3h>p~_e$@mcAt8h zS~7v8FhFc<`ccv1a+a3m@#cYS`%NZ`|JMu=J5j_#hWz)G zStr)XRGnV4Dl4cZXH6DX;JyDjcsJ;`fsLo{^$F&*Nq*lrwocR~gO<`O$_$h^+v5r~ zD|g7ILnA{PCygfXFeC2xk3!PlvI;5DnZu=IInExYatE41acjAX`D+==Aa^W2_n6T} z>kG#L7D1co*=&(KmjRI_Md`5jpSV(_K0Quv?AVamw}zkZjqkaoW)sG+?ff48v|P}6AAU6Ug1+rt>)W2W z$NZCHvX*B%&Q$bR79E1&2S%@5f7juk%b4(UnV8y<#VL=W=$azUk{sWRW1OMU)Rv`b zk491nlk!U)3NnjCs|Ws$xn9b3cl6_F;ZSq&u<(t=YO{+WdIR_5Lt7&~$|B%SmHRtr z;#UFRQ?qCZhm~j>BPyCGi;t$ny*m_+_)b#Va{T;jR-0c3y|T+v)?)CfbM{MfNrGtW z3R~M+Y8?D-Q}ZJrw>2qoVUqW%YT_fW%ifdW&ObU-r!ThOVoYnvq8F`6rDPat=C0s3 z{GP!6+WSCGEEu`&)eS)x)DB@1bbu>4Lf``u`JuBTYc5aCq9h6p9dk+SUU&R#AT7NA zu<%Sp=L0e{@dvI8g@F{u%@&39*9yhXnqQu^myrq0y{&I2*Y272s?g+)_=}hM+)kT9 zTHBKf4su!B$%PHcW22^Rc6|F6tC!SX|3lcWDSoD$qaLo2BI6{btf^+TvQ(RK*hcns zJM7mgan4vcw4F7R%nlWPhnRO~jkFwNZz74VYb*Af3P$EQFn#~Vq1wC6z+U#ggta^@ zO!I+tJ~R1LOpS1VLiOU=rlIK<>cu7UieqL?pH&aF@(F6}FJwZ45b@io+)$p*GsC8A zYi1GIZD9S_ytd;H*{b8B2GvWO=2U$<#e1H093`-@qxD9(PMH-%e7ZBOf4;qZay`eI-kR!_+DGk|P6fYl$KQC0H1y{fWeJ^gN4RI(GFmn2h~Ix~SQuc}JO%AeH2X_04CuDlWJ3Gi#nU>)^z*r6#py z@9Pc-(}-DelFT9K29$M+3L*i>bo=Gh{AqeNt-SmA8(Q<}=E`@6EfPLcg%p?sotyAw zOb{ ztQp=5y1kztR;j+8W@_1J{po9wy!+pnh!q#(=RUG*swLW(Jl8HU%P?~>E@=NFG#)?m zCx@v_y3EBXKs(<^K2ihIBV1HFs_f*WzPLS`3(0KiA*!F|8TW~ty{R?%i$_J6vGa!T zREI2x;YGZ8?nFfZOT^^s^8B&hw&1)AIy8%>=^*SLhCbZTdgLwsUR&)%#;m!^sL7>k z8|(Y~bdu%sqBI(3lG0N3xUw|fow@lDNPdxw%n#cEUX>TfktO!t3(#9-me(`tI2kNM{58AexH z*i%ty-Azo^~&ClmiiPsxTZSS6-k>0Yh3WEbn`jM3C+H} zYN}J5ODkg`=Oj#r&!BTtnBlgLvx9MNd^1*;!d=AzB;AF%e$PhL2=zt|YEiY7$fS7F zBSG|dY34{-8gIU0G5d+1+EHdf;VYuT5()r^Y{D65nsN`=L|7N5Q?my}9bC(8+2_(7 zwpjA2X|T}DKA8Do>}2e|?!`6_=hQ}lgyu>9?zOq9z>O<{SBy)v)iY$|wzJAe;;Z&& zW4c?UMRcbl=O#EJOt0Nvp^@p2IyK8D_>Q7%)b{vfJHJ>-cg@6)H|I)yzvO7|sWIqnLa?~! zDfM35wjI*KjVuKx&DrNbBU|$mBy3$Ov>Bz#{z?;thEj_W-)^-t~LX6kJoKBLo`R%@N*f6a1C-<+HA|1WhgYt}W;r6ZR!gt@mvAoiJrR-@)`u z!M};$!w*b``p_CXWX|8&oI%ye{==Vk+0LM^tbTr%p$4@j2a1f0Yiy zuU=j`zxzHvdXjzuby}Aa+jgh!v^o?!4m`_ow6aLML@rGn{5V|fW%@OS1TRG&W z%AW$g`{XZSf15FQWQe>YhiyN&$4dYyYUWgj}(wjBOPsa}*d22~L zN;PxUTfOkoEzEM$lZ#B+o5Fx%>&enYnEz3#G;~Vn_g~!8UL%N4Ye#>y#%xr@rf46< zRdN@VLzFz=OKnWLxu3dhr}$KRn|L9yoX>vPK z1NJk|Y;ZeIRRIRPaOD(hF_ql;9&L>RV8vkT=Ar-X5_e>RQOm<<7OX(Q{~ zuAce%UdV#fQfp9%vb;LIpEkqh!)NC}8O6S;XtrKZ(>hAu5NL)CB6B4hc^39Q{U~Ke zQn)WdQ}~Qbl=vHCV>+6sM*^?8%oU%$zGx(8Z;D^eEVMGQ^BxbjUdd?@V3}NOcom;* zD;7dqzdHTV@&1-dN!b}W0k4Y>Yf6*bGY7luE?=ggeD*8O~LA-Fr)*j zr?93ATr{CeR!yT%iTNueM;5`a&(Fp&*wcqWO--YkR zHnvZVI^ghS&p~y zU3|xtuFCNl3qjd}_UY)NL}ew&SX81`#q#l?W<Sw z`;5aunjZdvw5bfHdR%jhTyXSOO*i9C@$uZG%2Kdd9q=%zGozBwR~uA8rdD zN~%!YBcxHpTTV|uUAo|8phS3BKz570!mp00K+EGubOrS!xlfac$9;pL3@&d*zfT2p z3pw}A69H0!s+j)}cfF6%)nS`3<|&_7$SgjUoo!Ese|H`r950hBuS{cL)rMDprP%ZF z(C}1>?O%RTvZQY(dxd0O1hQLek_qRX#NP_3eHK^F*`i2v14Uohznv(Q@9@Df$4lV; zI5-!$*i~2_{AGS-qi=)_Els5Ak52~C7|-S2lUsQt{tT_+i zHvwNZn-oE}78)6_XmMx1mu^w|<-4aGpIU2WE&0Uk{tNbP!WoHXGW{4IN(9)o;=gxS`PIc%qR! z%E~FH-Q6eEzlm9_qVODvOf5mFGUq^B<62HfqjRyV2|m}+VMup#F50Fm)a_4{@Ka0m zc$Gr@M)+iR)Cg%mFUWOR*rngGn@WmfZTndl7JJ)?VP|Mc<x|ujnymfn#;Sx)M6`n zM29NmrEiblO_!;aRIWP~wYHG5^qn=)(t2}j)Ld|59c1U?dc?BARObPVN`Xlif*C0P z@@&8F+GoSyD~E2~@;F2)FAi_ZP!yF3OLK5|HF9B(>|`IaSQ%~W4OKE3mZdn!`aaYWxGwWZSvb_b=gJl7^4wb6Hf^p{DpnM0XUA%6TLoQvs^azeEdl-Uv5!WGnI93HdE3<#c!|m zK8@%XeCswrYNlq5z8ExYxn_y@Z()n|7-+ z!^IV?GeeSK#4c*cfh1ltP1U8MoNO;B=`v{Q)t}Pe){N}=`cF+qPi~o}np=1(7rL7LgIbFQ+XWjRR z$7vw3lmHRry#8mwm@%PW`IbPUl|r^FVfkV=BLl&J4s7xk8?a1;WYT8aYRx1Z=bK&E zrn^~{m8T+F-s`9KC6mvwA+)|G5n=0-4!*Gz&Yi19278=qx354Xl{@of6h(X3sf{VO zxA)D$I*Lqzg;-V>eKFByynhOSPh07;nwb`xuRk6YaasLhmuRjcR`3U!%9UOn^fRfe ziw^)yI2;r(ut?=(75*m!<(%n7z0z5LEes}w)C+3NjjL`yA1}F3aZNOrl(wDe?q@u0 zqH>XB_G7zOw#PP~bUguBEO3zZ(!QGQC-=>@_!FLey{Rdi?Ih{il@|u+-gq*UZOzO$ zif4w^#=bgZEEOBv69&+7KVzk6O#6ygKkS!^jcqXh01&|a>P6%0YfqH>?owEVTAQV}BT;kx zl*!FAH+uotrhhSY77q{c5*=0-|IrklMUh0HbQKf8pok9WvYMtKj< zMz&{CI*#j?FiB{qCpIVX%Y+q)HrDq~ju)0~>!!Zb`^uebM<*){b*tZI6rK)8K{_~h zky*n%mq~SDlZN`LjO;6XQSspGE$cCdUT#+r$w&>-i%o;4*Otc3(4Q`4r6}Wgwk7~e zuG9A?e9mZXeLaKdq{(+bzRaK{{0Y^P$oCvSethlsdpREmml_{>qH$zIk^#9~;yC^+ z=eyN-Yv+`B%mqL#V681yo?n7Z2oT*T9I6uam;^0uT~XU` zLfGahke1h0UkDXi0G}6|+uS=`2%3L0$_SQDSi7am!=45W1BW9Tn1>-DB^`XEg)8Us zn0vHwzLrN|pOcUFw%JP+Jo{bQ8y_cqu5neG(oTk+Oa(|_v+C!Aco_rXYnlEkZ`U@K z->zBLYj5&81qtcoHJTgK1a^#vvW!mD=|n^|NHm>%f-xfX@Ul~vomZX+Lax4=;!?|z z?>KAVM%_I=d_JwiTUz>KzVfqTTj`^Ny-u!j`mc$}U-|yilA<9#{@sm3!PYEOZ|YL- z-59TkO%=I~PaG_diE)Q@1BuH`EMep04&%%i$+F;{cK>0)iqSom;v?DFx}+ zG)RY(u<5w7@Z9^{^GA=c*7|bdop)w7P~56v!!B{JlR0+3_$hOC#@gV(j0mSeBG+3K z1+k*WeY0Oc--i5_K?F{sbQ`Dg;XfXgZ?D&Kn8c(&p^49Vd0h8oWKNVw!f$;H+&Aqh zn`)T~wS$hxxyjD;1SjtK{X08lO}x++mxc3%0-+(XbuwWlvaNm-ZK~BK{aoLy>^PQh#pN-%`B5OIMvOZ2tI}-@!IZ z@=a+bP9fctszbppj4|XMb7Z@_-%EiGzD7tho*J`e{P?je)J6EQ*CF{C z%Con86y%oB1L|J$#dg*F z1N)b)%M*u^DaA|dI24i1tGo|7-x5rl7TqFwGT#D4^8?pVv)jXSo1f4zBdMW?!|Rf% zNS)A~wFIUbD1_Pf>qiazz~W-S&EyZ>y(V1hUjm*`AhG+=4dRjx|zV)Qx?beoT?$+7eT*++#Huj`f4wd!jXSB z-bB@i8x!9KARLdkg->L<0RU?HdK5%6%+(4w7)E36WRf(e_`RTmXyvAS_r1}7U#+7*O5s~Yfu z`+0kXZnyZoW5Nv!an3~+ev&sYMS(XzUcl(#+r;4-;BGe$M`7z3Zd{7hfNvPC2O=T4 z?R4?Yk%L(CG{v%sC%Jy`41RiC7mYsbn~t9F-HcKfF58H{EQ`jG60K{hwWa--SVZqM zFVSc7mdmdX6brB8rwOMb9v;t19W={Q*6?^fP&UB;*asWn4I~&?L2;#w?Cgm3 z+Vf+;iBNt)OwtMTUc#X(FpAJgd`#K+Xi&koUq3$2Y+7cPH@Ioau{;m5_#|{gYCbn^ zv!k%K%jGNgXj)n8!8xjbr+BGWqXa$n-d2^R`Ff_DB}B$J!s_=|ZddW6vpR_why|g1 z(0Io!t6H%Z-7fTEMX{u^Fzyo%6B0S77>oeNY);5y)6{l;+?H2)lMsyd+nnJeTa z5SM_ThIkbk#p&;ul~?uWjrNwIXG-6UT2>WcC2ivZFwxah>u%}b2&giH`8YimG#`~6 z^d$Q$O%@G;Rn)z<=Dfa~si@XSbQcf)Mty+@L0^J2ycHQE()GiWT|)ysC$l;;v;pm- z@-E?GHxzy8U*fVK;4-z6jt0yBX=-0O@<;D#tQE_?kI_@z8s&JI5xxtM`a~F zXKgl;KXPHsb=L+POG%rvnQ~Swh=Y#wY6*V1Pj1aeSPt+A9EvmA$h=v!wi(b&VKLB6 zD!xgk?qu_F5xh*yngvIi+CLfWav(GK&hZ{nmfA)S@2&BckU8eHO`gsj=v0HzuL0Qq_l+ z?A6#Kr652BN?{$+S(!OGRe&S&p+X;fw)V9VC6|I4wsIo|N`X=gyL2g(K@xNi?5jjE z7#!s1!8|>-ob7sjk9wYOedr~@OW$XQuTGP7yi?KRF@1OmfK}{`>Z+d`=~SivUZC1b z?T-=23UAo3O1v_6YU4H<3d(U5ts1R*y^}%!rbzn@RtLQ2hcp)dOm(>6+EU3B?y@GSWWx+Iv@27?z_JLD#Jt zDo0nB!BI-?Z8#SLP1&L z5^LD>X=|faf)*{S!!{kJZ0*^9Gl?w?ttu7^pG}Vq>D#Waw0ShAKWJ}0Q-qp~T}hge z86}?^qCvTwysMu{fhnZ`@doz4SLyP1#1KIUXKK}36%Is`)J@(`SjRuLq{iKK4_(Ze zA`9*?eIdN%x>)U7c+VVy?O-{rE|j6mf}!Ui5V#MwCUpcSO4s&l^h3(iC;#|?*QB5Z z#V&9_g(a(Qyy(qb z!ke7n624H?nX?Bl1z=R#M-$EXU6=h#dGso5@t;C4Bo!Ck|DR>Kn0N4~ZhnRqjCL}x zP)u|ZCKkX4g}&!J2EG*>Y7jF6zQ9y5@0wf&&s2!b{zTpZYJUF*6s(AXoooyhq5N;| z(an9YSxz|QIXm$lM+Tv<6J&JV;0n?%_ZzB#2swFmjcurAIJ^|aOS~(+&SfFe#y6$7_;GzzN z9jlV5ax)>{dWbEQ^uA*XtC`X|!Rz`ZPvbw7Hd)uyZeysuTJ1YyAM&K0(eO7p)JaCnfGPjJMn^<8Ti>B?0lBicS@5N z{-Ti#|&El5LMjC9Tn~2t&&3*Tc|(9OV^02 z^lp#?G{r}Z;a+jbQbv&@8;!w{3G$p4?zNgh{N@v*!5w|^KOQ&M!LI7YX7nZw*GFVz zty+Lr8C{hq*jgS#`F6|BzM2OHHbss zhU}q|*K*cG&-cMJqZY);V?M)PvHRpJ9JY)kvu&IHAvW}F%veVsLexov(36W7Em0h5W-pcwhdmwUQP|%z7`5sTy*h~d$&%jry}Gpr zf31_}N@h6d;ejgDe?TOhj+YT^MHx|sph+JRYWbOIcQ1+LON9C4-TAPwExtz$!mW9k zKKlgw?7gi^U)~r|qBMl)a3vgsQ*5vX0M;BRqNl(tAId5**1r_4B6SEbqV%x)CXp;e+3F23b)f}&XMA5O^^=Vw zaZk#C(3m{vviYYP-Vzfi6sB2RRd{z{ljiLAo#@4h^_JMgZsx!-_OW*W6&|=wA$r2B z3T|(6c(z}0%r9yb*(_uS(=m*8VSf0FNw(G`!eRFs~g7_;7_ zYTKt{Wxcje|hCLKD*@m1Xid(dP zeHThrcP-l+4KktZgb3bTXvgLG*|BvaSPSGNF-VX)Agj~PUPRY9xu1IDxXJMHl9@Il^w21(WhxU?lz{@w(uB4RLEC)! zTjpX<9ug9qpLd&!(>&V_Dr(@MW(34v2XKN`z%drr`a8x9s<7g(ygNw+1yF7r{`=Ap zb*e`HNCZedEo}V5tMbcERyByDxU4W#Ws@)0-#3|2`rN_2MDW-H4@AV&IDfUazF}s? zc9bf$;JQn79x7`u&i);h?qA-g*F&H>WeoWFpUa|(>hE2)CKS+?O4ISBi%V~_7ngL8 z#SL%lphneY-`GS!J|(DPAJ3GLZQa*41aJV=>w%^eJ9KDc-P`{lH-N?^VYtObAi(vr zf93jEQZuo8cg1K(CrA+|uk32CG8NP>0;up>I6d?+gB6G34e$phtSKW)9I;6Qw1nsN z3Sqm23q-BK0LEikPW0)QXY^)*v`JwcJYx%%m4uq=jBTG;{H|}O_1cxV0U=|QGou{LiDkC!M~iO zt+cFxYJ#!J_YMk`PMD#p-;{)7X}Ohy^X`wiZLm5MtMfVT8jh#A5QelK9z((vAlKo8 z?$Fx&K9Wg_v0!B#sYc3(!d}7}BfF@(!!}>)CqE{L- zjVUKX{|uAc7a-XB=Cioo!B!hVL-DJamq5#T;(IG#&z5q5r-}>h6z`OFE`3TipP2^l zW9P>Nn60jbbfbhdSY2T))JpIpqdwvS*N|3u(X2X9GC=%LQ(HZAX2!nIMZrX%%eTXe z(l253upsKdxmKBE;cfg1xp{Ha;h*hgm#OMYbNPjyf@i5=IEdoa>+MIvOd%qc0@Fp2 z_zukMq&|mxeq|Aq6gj}$(|eoP1Aa^AKZ!OvXE59lI!X&RVJq9U(Gzferm@JJTX^s| z&aVAuvM?{ib&LFi2@s2)^Inv`C@qK=cn`<^yKCHMCH<~E`oTkvfpbvZ`}=kW9(%jc zOYb4&pnb>QS%{yl%RT~gEH0}*^FxZca8WP6&c?zAwq4!|`Om=Gc&+{NT*i?TvEy(8 zUDFkn(lCOtg1TFJ{2~hIFcTHB#;;1+E}fNNDAo0&E9FoVKg8Wt$8GcFt~@CM-yJ^K zqf_0aDs_uYf&lrN(BQwEnqX(1`WI+OccS*2XMO2WiN;M=KKz*%8s3vGg0T9dD!#X0 zuEucIazGq2d!*DcZOO~L5cIC#-!V4KHLs8Nr2bgsqR~0>LSvZS?x4qAj2V9g*~2eO zTejM_c1Ju)Z<14D*gM0c7R}`7G2iLKMe{_g)Yv>%Oe@;l7o;6kx^@^IaiAnHgolxk zm(Ak}ciB;ZVsCmmpWk}-+3C2PkhA6oq%qac(pPtW7jdt{g-QGO#fgV);A-WZ#v=X~j}u7A z7$JJMYX6exf6xcx9lvsL^?bO^A6K>Eq&W#F?|fV2;wf_1$@bjR9d=XHZ0zm- zXpoYtshX3w z{fuUdoXh57sg-b`asp2l9*R{oTF)0QyUoJYT|0Y}@^av>r@ZnAJj}qrz=sbXCN(uR zNfd+p7}Ip6!=f57+4^(s-AO0TS7%R3vt6roIaKnP2XnYzyEv~m5e>6ns_r+l)`PtX zr=nNf`CD5cKKILx7KWe(j0YJXOV<}UO2MT0=@jvnm){S_b=@HC-SKanr;ozBn}oRM zxzE+Ad(x!;y=5dauYbM#^XJbx9%o<;^{=!mJqn$iog<>6Qonus<}pf7Pmgt597uabm>kxW5Pk$k0v{g5~;w`hz!r|zLX8ioOMU-Kr*H>LRL{owaGKTwaBx*RJ zbzmBlq`L=Ih(E#KpLFAXhKpDLijN_s5r~KKj~2aIkNgdmI}-gHfb0bYJ=35lf9N_a z##j4QynrHjm)$faAInWJ{NOdP3-u1Q+0z?};;FpeJ1gY2XQ)S*L71Y(!>&)JP77yIt zLkhZa^oXz9w)%LNij79bKu}ZdX^6~b@InH}EFCLCq@A++ZxV6)%SW^ir&r%1#7GT2 z6&Jx4%4r1bn7W)GrU*i|2g|>6npkqWb>!U!^nHQN32ap@d)>HX_!)|Fz@BnGzI6Uw zcz7b`;|8?KbPT`!$S(wIM2SCm>vMAZU@IyqT%X%>!zR|X_YoDp-Nz!^!HZw2A*>|f zy%D9p(144w9B-EA0e{H$mw{~HD+c83n1z!5fYQEjQ9BZh!OLsvQ3TOw+?$;T2=U5eFkxfFECYPFQ$E=8W-e6h^km8xrY3cwC!a`_ z?XN$=W8^pWAJshZ9Zri383lh*q0$&LbeoicXdVs2HB%^cwIr6^5~(}bT?dCSB(6-E zzxqw~Y5D^a^x8>B+tC~<<%R<=r7ac*jMflHbg{3 z#PC?YMQh1Y5C_4K_kNXb3u+f+x99Evs!f|o5bXYG(L}Q=T_L$Axjx-#`wX9AujPJ&~_Bm_?+j1^Fe_?P;<{v6AvK3&$)5Ai$yuRGOk5PrDHfSOSSN&KrXo6maL#@LHpLbn|8u zC_ss6_-gv}Z>(i6VF(hHP13;n!b~$=5z;j`yS|VqEX{m{`RB$C%47xI<&1%EAs91A z10*kl%sk%54QFMAXj(<}S2o*mJ|bWFZ`_b(Vq!vf+hgN*`nz}M>l+&AxbJK!4^#Z> zPo}pv{lR`7a_!vLm*GtgBA)UY1%>fL9lQX}(PWdwTY`Dfrq8MTs$)ZR?`JDp?-V<0 zXK+YiQ4bMPGx`@1h-b>DLd*hy=zE}|znHszkj7CA3BYtjS#nB&y$j)fY4&m-7Yh#$ zdM=XeO+j7PI9!Std?OAP&{(sdy}2-+1ueaBvg`GWKxt z{5wJI!@RGw-AtTK9lQvSH|_W}UT@XNC13lHi}vgV*-Pfa^XE+|srnQ zqU-nADSpBcp#Y5RT5Z4GnJqMWQps=n9_)!!ol$Kg>&0(>s47?Re3jvqI@~@H$v{Q5 z`5Tpd)LfwRgsLdifR9puTY?6v9u0Iq&XhLR8^PR^QifiSokG-hJ^o6gX>< zM=4k(SL6-sN3bxcoU0!W4(F-|hv#W@Qr+JC;~#zuiFpfl4=PTo`cb)HK?AY$4Ky>V z#u1WCcp-8ukCTEB6II>ZKQ6C9`5bWpIL@L>Hk1Vb1gqRi9|)G@cv$8FFQw$I@i$v6 zs-}=<-zZ-)I6+T?^rR%I&W>NB*N&B*I|tFy1pfk~TH;}-S`t}XjhB^`?SO7U$On3zoddR603)2}2e`wDGCL5$X?G`#0%8nVc%=eM58-H9K0XB2pL!iWK*1~6gk zY-AFk#z)V7@(&=1_c$mf-6Q|KqZ`k90pmyGPVilO25zwc)VSr2n0c1R`+XX1Gip zGUyvPsYgRU?s!6WtmXa=z6|Q2T%fZ%oYRCNC}oiTSqM6dgjQ(%J^4z44}i>oeiqse z@(rSiK?0xN%7J_lUk$3-S^AXk+EzmM(wAV16@qcaVM}J#EuGquUCu)uw)qQbweMj| zva*OVlEXtAsQc6YL`yU-;8YE~W@fJc13vW;^}|OCxn8#C+x7``UY6*g>1Va_u)O7*Ey zNH~Vu|J zi5bu@N+_Q@sR2x~;U{M1Y$dy_l~27R7xC62`l6zq`AeSeB>u*zh_(2G(o7&}s#nLJ zme+Puc?-vJ7V_{VpjAcAH8tO`n>;)Zp%PFLnl@j%zgJQW?Gn1|_u^B;Ltef>|+QDb_u z3iO^s`hVc69~u8%vA9Q7iULiRxZb;T*=wCW*{;FIpd{L+U(!vB7RedrtKC&$e|qRF zTN}Iv=LsN&lu0nAeB|^aROgN&FHe93hULG+lP2v_G6-nGo)*MvM&7?mKBq@vi}jun z&cwF~>J-@emM#{eyH!Kqcj^LB6%+z`tS@|?2)e-pc0%K<_MXkoP9Tf6@Y7$|6IJ!D zguUrAofuIK@!YXScWlaf*WG4LLI!a#2I!(}?&s~I-U>(wlFRh^0Hs$j;@wZPY<`SLEin}@O(UB@J^7*Wf1);a3hUo&YYnkH?7kFMT z+m1Gy2uYoe%!fA02aC4Zg7d3SQL?O#H6dacMHNJW`G0%87vNNJtQ#U(%RuI%)=dOr z2~dO`xFm&dq9FW$esQby{M7M5SDbL>Ry69=ON4(@Ok;Q*9`3xg>1RZ9FgAcS5O@9E z$Ej>f+nXSH0uNogM##ElHb9XYrlwX6Wn~|)`q!5+oe}I-0%J-)VAva=k%xKm(QlD4 zyUiJ{Yt;P^^lp#zfHh9g*}Lnk62K}&1>{q+@@{cUAsL4JOI z2|#5r(@R0FyHqaTfJ1|0f-C^+ptM`mwKp2tdDy=`mf!o>s%hP(=h4|maK^wGEo@o7 zVrTtf;po7~ijQC&x%AN@9(@@A(u=ofkH%BYtXpIQ^bCaXv4?veF8q}ut30L!p}CbC z%Oj7HErC^@5^6qy4w6b7r6Uy-6pY}?T^y%fSPjsu{SjOk4oE=~lD~zul5Kar;|^G4 z9l-)^KM7dN4|6vS)NJZ*X3w@;Apo*eAJF4@JteD>t^d2XoVgy-Z+;LN!dm6$f4K`( z4JE2mdxs7^eP}0bBA*{PA^ZZURb)3G&MqKS$*VD$L2M6m^#a zc?N|@g-LmS$HRV6WqhfSz9d@S{>Rk_#XCSMUcKE+fk7Ew?aImOg)zWmxpu%MQy%Cw zO3wjk0h$p6i5+}yCu&XuZ4W3N*d@yJty`X(^ETqj37H1kS>7iyZL*I`t9XKfp(UWfw$;nkuPvE&z-WC%nHS!=nrz@5h>zHYej@$7`}M>mZm&t z)0ln{XASHFk_>z&?~C;vSIKuVhHY0W5ULxZOxj>CrxZwe9x5zB7TNJOFEn<;B^Z1H zUL|o&3K%j{_j(SEisR#J+G1%&S3Lyvm*Gbw9qk}MTuQjK8~eIRkiKh>F$Hq3@E4S? zcH7OJM#?LrOqXYa!i1MAH947*ed$zEf9Rz=%|ev}5n?OPyJm z=<%e|&9wKA1d@aGWsT}L#~dD_tm(ZCZkJ^NPtpc4lhLnMB%bRmdMiH(*+w)hP!Jn* z&nE-DWZo6s6Nq8}kfb5Zq+=DK z(K82ZHQRLXlz+TWNmtTX?ojB8n)?;zRqZbO*Xej{>`KU?)(DfZ(^UC4C$>mRy-;6g zp7Ealpy~21ro(`xS;n{78ay@|Hlbn3~3kwPl@tP2>)EULP_|SVkcSXkDoqCj>xA5_Kn8u=t zX-MNIV^D4~Do;b~yhL^Q72A5VdOWEgvUIl?!Eu1IOIBP@?Rs>-KXQfPx^;q_dG~S! zh59hwhH9j47(R^#7 zc6d;@w6knAXifIO*3?r0*$5;h>uAP(Ovx|1IjBDf4z8`sB8}GHMnBUh0Y8h`&r#47YP=vhVr0l4ZqBs+H{9$*% zt@!8nWnLbS3|-fA>(@7*-ju1Ld^g-LIwO+bHG*A;VTp2XEsgV3axrTaY}+5=H0(}O zakcYY?~tM9q*xFPrV-3L#|^{C{ib+gEMilky{;{9LCfi)X_oOvw!1POnHm>rEoDSI~>aay8 z*~gwmTy&Q(PophmJ$!aJT1pSjD$w`zTl`jXcEZ=1SGV(Tn@UfhmmQ;i9%;nnK5lHn z`;xuWy&bjZb69*>Zqv_I2?c?!G~2d*6x0U(f%_k!uTxHQP}J)5BRlXDJRU6~AERTo zVn>+}@>B4fj{uK+v#;2QV;0Jr!*8ipRvuuUffu!vv%RoM9m1dG?3}oYj=SbmaSv(D zLlB3`*nWBUTQm1%m5oO^QZltut`jrzVa6zXvXgyWjl_rfs>(Y`GB?j#j8nwT$C8NL zL`4d@5ISN&S>}Iox4j!Z9QK#G8E9wT`Z2vHQ0f7`d>pX7*ON_S*gYF#G8glJGY2Ja%EHUN}@uOFuiVvg%GyF&*dY3kY)fYi+yG z(KjLYi6&{ADwZ$3VH`a)7`0wuL=DcHgzcVB^~nBwyq%Y2$idEBPJFPVbkua&?nnJQ zuSgiS?Be>=D0U0@sPgj~Qawk8(y%0A&FI__mRm^ZIY`IAyB};zaeir@QhoF&I^{w1 zXK1s_uPp``UJvv=OdKB{U!HW%gKAE^+G4QWd|sss?{A3YcK>lqmu)>WgD|{nwU|&z zJwHQn!rNzV1IL$^mC+!f0VOoHP1TumIMymVuW{eoR9dvYjt2LT_v1xkR zU*+GF$}if*m1X*8_&*qA@o~0h@3t;vNBMgAjf+0WJbpEzak0}Nhbn3C<~j#eaYjSx ziP2#bo*U?kc+R^s8`l+Bc6I0I3Cr#jO)UMmS9ARMap=zS9PLSzUREY#@$^Zhz9`g( zr4n|_3Z)a>vAr}NzV`N@t8gpEI_H!&;2aDaG`F+bgEf1Zut`mSa$OK&^0|LRZtoXF zX|jcXY@=h%N$VK4_ez%hcZ!(n7*Z#MO^9CP4_?eT&fWGvg;Z^x4& z60Di4J1)&E3+s;*?Uctyo!t1deI4G~Q4WTT8!(){UhnBLlk`b@twyT;(LN_#&5n1Y z>xw|zcl0ehVoMrz0WV(?4MWkKRFPXkrCUWA8FFMID;VfXo4PsbJNkqaN=|h`EmA0F zUnV~_H8sk#B`QcC)tqdwH-0HFEVT=!#4+=0lW##Q9Y1a$E0=hT19R(jB*XqPf=w}d zO53opGrNO+xx z8?r*%=2NC-y?K#{al@WnP+?PXE_;&b;zgp*3eE4Nyd8Ealc{tCT>3*r9_OOZ#wWn} zy23x~65c8>aaMM8vB=Zu+?Ua1Tqv!u3((p!pmU1{^yn%yZN518czSYjR1nOopF&2n{LDFcKi-3M2gv?N5HL zR&wJyniA?fwxL)8ZuaW#fS6 zDJY0lnFKZ9Bpbu%4~u3scI;<{!_PQF?d41qU4}|`0bE>MJQnQ?Bs2ob(5_e0!=nro z=ex+r8?aU1zTLfW;X-;^+I?a7rEb{TLVzizW@db;mnTIOeU>MUC!x65LUNS8)w?w~ z7{-l$-i_)SrqvUS$6?kAnb*@_HDaBxg+KfY`#rNBY_{xb`<7a@yXSy8V{!5(#h{F< zbpl+Z#~eork)v&%jhhPHM1!Y{5d%I2by^jU5c<|kVF^oWU!ncWml!AdrPda=1iP#RYqo}5))yh zi`Z3r>p!cDF8TrG1K%baRG?w4@ChzlRccGq6Q<0LO_bVY};bv&DBojw<#>B&10 z;p#DwqB1{tyG1z?or|)tnM{5BD~g-**~KHOcke#G9^0AlV|g=9^{m%t<-Vqc$;Z|7 zo0E<(hqrIv^4O1vgi!P6a4N!n1aOuzMudja52QyYJU|${g6$T=8^`wi*xhKjFP%lm zxxM&=5OEjK8@#1aF*ow67~y-El^GCxeGR4%cvHzt``mE<<3giL$7m{vx@tuuoUb=O zK&^c}vqSYtU3;pBBB0r|CkSq)*Nx|q%;s>bU92JMR#>bA=G#|KsT#6geOqZSh6hsi9 zJF{+`c<63te=S#R#OWb_MTxXb5KC~~F?4#~raG~lFQ_Rny zNh+F?4Sjs!o%-ePClPY%3ck}AQM(sxM*#_j@2u`f%5ex1jWRQ1-CXvD!#y)3^GziC zk${W*pL!IWbHr=!XNBd3Sqx3c7dosNT|3hHW4mc40gj-GJ5UBA&cIhs)MGs@e*&xL z>PocKlNkj)-muUJO(r@zTKWKV7AAauZUQ1itsYYsH3vc+>%Xw-@g=?ZnuRdz=|1rg zW~*ATNoK4U40Nve*-r#I*(R^6KakK6UC%dl^NeTl;HBj1sUbxI6x@W6awY@?`N;2N-8MEcPq>aCpVd|V#m^|ouG;O}s4DHx{dqPdPek4x zAKG$$nR880<5kWV`hjdG3>j>P z8;gU*O2Dgp2xwSSbF;dN$`x5TIXTtv8w%Zdrt(mqPBB))<;BMLnkHuLy~< z)ZW)cAI}XUG~~GtxM>fV$jWFR6J>16iPP#64o|)4P7(&FJJJ;&Y$bNNPOY%&ZTvpn z+_=nsOKtOKH-iZ=5}=_^O)>c2rppdp6h;P16$udrD(`TE6n8$F0+$C?|EL)gXmNv_ z@bUa%S+?1NopdPcaHj#%rqV&7_L}|W?5yb@(}d_%4-i~ZzKIU%J@7cE1f*v!Dv+2E zB5$lMW~M#HWm0v-?7&W*Tg0Du{`wrkpuKIwnx;f>6wSSFT!{3U=gq^dI*A`?coDOg z+Qv#B6?vZir41rg-t6bnUS9ku{Yq@i<&Y1Ws>ue`QMO0s9;Q$7=nbFcd@Pd_Cn&~; zgc7Zt;jT+eHr+4czcb#74N_9#+6x5i{ zI<`_L7A>bZmcW1{@ymX3{W!`#%<29jkU4|IoCpb!76Um7?}Wz~-fC68%yo_>LL_*e zuEZ)71^O~FWuJocE6`P8`TSF*$Cr-x*sP({Q@*+xZB9-he?LZ@W)ncrCVp4}@pQF? zB51rhoASZVYBCsJ`P_WJYN9C2Has%Pz@U57kPjg*{q2TCCgm|>TX)xHb{Y$e=6i1R z7-}FGi;2P!M9UF1+R#&H7lh+TR^K@N3I2!JRGnA5lx1{d70#jIw|57&_L& zU)&pT1QYAXV(bVb9HUfLR%VE5#xKh6wEa5=6_=-0zi5Nw9N>kT)b#d(RttUk9z~r> zjV|hUX~aVa#!TQcdlbv^{$o8?q$|2Rr+5u)>W+Hr$6V$9aR5Of$kl*G#WRLbqGNJy zDq{C69D0c-EE#E_1;4bmkeCu8hv$|Z7dE3vIH;U|Xm~n*L?5cVks?=*nV%o94}@@L z^&8aj=V+T*TbN?s91yFz*G2RK?vsmPzNh@-+=CUBQ2iYzY}F5T?u!%%`L00_HIMnK&WzLJs zm+b93U)~h!38$Y)%WJS^y^Sz9^+%5x7kh$Q2CwUR^H<&nc87-*T zkHsk&io+xL5e5txSUqtNd~rjqi0nSs2akQLrRcr91CINm&vysG=Dd#4-pz3P@#9Cx zN3eh}myai_@ANNFuh*JuT1+i@$>hfHEAYI#fJnvJWvi~Q+}jUs$jVrq`w>>W;5$0> zz4ifu0U3{4*RZ44PdT>UHZG#M&Gimm_6z%E$b;ZZGvlyeZfXO*_3T|~WQ88I#U&CO zY`uG2wxGCZtz*Tp#%5R4VQhBir~Z!ONfJDdGajCug_DvUp3&UgED3-NH}9^<^(PNp z5Y6?JZQL8A&d6vmzXe>lZw7Bd2*--;=#mF-Zk)W!hd5*;JqeR`wNFpQQrTP|0X=Nh z+T<;5jNXC(MHJ|O{tG=j2fu3lsRdCo-HaLgaJo8a`N1dh88=Il;*0RR51dyPgzw?3^J`Wb;-_M%^?xC+|YS+{3yi=%RrCO2u z1R-xx4IjsUTQ`zhd0!s!1@DkcdLfcJ=mZiVA|_0W(fdy%(nP1rmboZ<4mR$lgF3Fm zT)TH+r+u+m5NP_dSVCDLUpk3im=cF`M7I%7X&||O#7E%NbX9Z?HI#;c= z!8ZC-8$jc6G8Jj~*~agmY&~#_ujLMy^K@K`5~w~!hU6wGc)a!T?MD(hi)om-(4}}} zRe{<7aQ64X+!ZgBmCti!ovMa+7u$G#YS=eQpUxIH-0mw#Dq%1oLP#du%3bgQiXKY? z389bm@I!KJ!*1OuyaF~G$?+P_cxdPcjEYUB<(a9eIVg@#a_49`lQc|x|CrxTHQT|3 z`LkRT{0bgM0OKVxE9~f@A%^R1OIF$^O`rOHhZEA6dc3Zb?Ydz>#ggTG!~u}S4YMLp<_XACLjXRLr%?Xh5F=T zkT84YJ4~|X({rwwd&ansr7V6sn)Ib;CSoo^Oy7E<(Iah-O_2MlN{zWr^2{VK(}0Ki zad=tQ|J7R(i`+4@^&)?+w1PrC;sV5-E%y2t`)@cLi1SK59}_~+nwgNSqw?xTcs<2>BMZU&zBN7G7 znHe45TKsA2@5_TulXxOf?5p!Q*JsVAsL9q%`UoWSMsYTvy?8+1#A@#J9jS9Gg*g4p zp`jsiGx&vej^oL#LWqH2MWXKcGYCe-U1=%VXR*_U-Z$;b-Af0irRW*{c^WMF3jGDO zeo@w0^g=TjKdSy@v?>BSG~k)_&|IuY>Ozm0jALg^-Q}i}$j8#{-*)qFqK&U>+$&T9 zE%DcvWcZ_k&`9Q#PE+YYPuo-xXo=^J1-o5jYRWMeg!DI^XD>)=C_K#P!Q;LR5|u$# zfns8PZ{0`;biyEKm6&oG%i%_{QxFRYEMEW-EQ+UAH#$#=m&T&k5G0ALN-RlM$t%Un z{|rW6HS?X+vC9M)XY?&NYrizLAd_pWRee7`0&)xB<{biu;HTSDQM^x9#_WSIN-i}z zm-;;1)opZN!V&^Tf!VP9Zi~_I;BQ{Sv$PihBicT6#S zwlPKaqjcjBKs+8S0E}tpVVNDsV$DjwyFA!9&wnW{%GAISBdabH? z>Mgk0(7PZD0v^^t8{BCWKS=mUBg6qA*mfrDpZPMl$dc5g9*q8AlUp6HtK{`AQO1{}M(Y7sa;rO8i^~Z|eQz+7 zlH2SELuYp1(+6Z#`LcsykpiJWmv#x4q& zf|%=hd0yd=*7hm#=kT*}w; zn0&z|ZQN3B`i|J$#tg82o=EPpqW1Cfw%+%n>?-OZ_3A20d2piKrX$llZ=iM~g3+2F zbtSZbpv}TNO+7T=gDnds={*CcYSFhpR-zRQI{Xy{y(%BgeysX&5h6SfKQ?AtUK6Gc zDRt4wxgoX+%5u=22h75CE3e)g<*4}xvhi)H?N9#|HK3{nC^x%L&bc4*sqGCy6yil5 zS8yF6rlA+a2UcJFo8w1D9cL1gBZ1o4P9V_Gw>Uode%KfFlo^WHM&G0gPunSjfjOa7 zIhcZCP=-CU6rL76pS-dMV(nSY3UOG^(V;ZHIaw+Q73G$|mHMNt`+KC-Cy0{pYw6ow?^UlAZhD+Ie-<&61rrN3SiD_kwD4B3R;+da+2KnLkBL?} zWTGB({c+@_bVxnnm;irq0V<88ZVRhj-TMqFWaLkKe=|AIB$~=S*RS+>X%@U-2LXnY zY{i4gr@Xa=L%CghXJYU_+(1>JOL6{ZWZ)H_YH?$I7#ZYd^jh?9h+NB6Y-?)Q3-?4d znL~=FS;k1IYr#Mg`7i}-~(Mq%CqGWkL$9Oq+40wko(d{v(T#obUT1@?K0GW;dD zZ3fpR?VfIp_VT$TPsFW zlapzXG+kd`4>pIKyu2EqVcq%WN`-(qbu$qL+y&1^XX!xwgZzm?+_9NW@cbgcBEAif z)y@L1qzhhLBctS-E^Z{TKB8=Hs?cMzmph_Iq+d%Hk(gN3t{`6Ni)KTu5ya>l;{uL{ z^)q05*M*(s*Q@RA9>U(pINqk~YgLwpD~m=o?AaHw!ZSWo0=>t;sRGac-A4%~^l|dV ztseSo0Mkpx61Lx}+WRA4xxX>E1EM**D?ND5xILA?Cf`D_^s5rY; zoc6XHp$(hP4y3~unEdz$0surq)zAtCWzh4w&Og+H?h;Mkzgr|dAdt#GcD(fxYpM5L zvSGlxp4lKsO6;eIgi`+CZpkxz*5GM9c0ALRfe&)$n~TGd@Po_Q{-h%EZtc9>qdis5Izyw*&p0GGKl^I`G8y_BJr^KLK|!4*eNQvx8q9J$d<9fZ4xO zJ)xmt&gCw{v#n-t2@s-tqi&WSi+<-|7dxaUe5yp1z|E9~h!&MU&f1pQlje90x))d9 z$FfkNuH@DFeS2Tqq^-^IXNx=>L1skAXWZ-(8y<{{*`n29+WJyJqiwgQOA@ls=U%da z?3OBk;K2Ov{I=c;nz{)9!V3l#x-Dw!L66w~vH{F))vipgZLfm`paRW^I)3-(t7}{N zGM09Bs_gD*M3EkU6=o-Mq~KE z6K@~ys%vczI1q`%ydi?V?kLm_L|$TIt*PiQ)BwPz{7@wu?7>Na*8WQExy`6p$j2oh zkSeVc2)j+yJ>vK=C{8~IbuQ4@>fieo3WytdE=0dljcWZ+cZQeB9s1Bv3Av;JEN{|7SZWf}Uo&R3aPlL!BT>rYz2~r`Xu~aXHv$a3tJuumM zb2L-vM5?j5PtaKN=w#Go@Cq$x#NrBH{iZ|19UyiL-K?UIjIZbF<$p|9HAa~}ZO47} zFxuf@tmDkSAYn5*^f_HSMZn%|jkf_KX*$I_@P^Fjv$Nx#Q3c%8+1p&8q1zd!)0EGBg zZH)(M8yG-}NLtr1)<=+21vwf!#G;clyjJg^D_FI~aG7gUTbrhV zHPzLV!6(qYcdu7i%`fOtzS$gfh9fNrgV;8$`%nUetgSbG_X~la+yit{xM%6$3qfXG zC$#j6H;?nyD0g4(g;>f0tvi6i9?+2b!Tx3BvvMIWbwOV%+dOiq!0UH>mYEaxHa)lp zus-YU|L()?-l*37KqkGk><(xINOxzD=rGIYrMkUX%fH6LK_HC_Qe|dht~2@uA!oY* zZpo&-uo~b20-^QJkiv*C?4XMRIdqKGqrOee6RRjte%jST;)Uqe*oy&(PuFW?rlTNK?E24 zJInV0bw&=`2cb~BrDD#rV4!PG=l3-=)k;aA(>xapfh~-MY4K4kq0G@nvlfkC%njdA zh#RGTLT4>Wb320r1^W<;!(9|=g21HiZ5$I8?2M3=;&vC6k8Cl7wnv!TTn@*8dAT22rd7_JmjO;BPhVU|Uj_YBJ(lr*`Fpbhn zfiw`tF)`TOvYAhwtiXTRXU?efaIDuKY&7Rd0KD#V$4jy7!j;zCvd6|`GLCcxB?=20 z7bu&+&t~O?D3T}YSs!hmEvuEuY93TWd3~#>gJ7#6zs#yP;>F}Nw5hrOcE~R3Hf{Ha zN-($@bGPo*z#|e50WTu)dO^mNbU?;v)pK~>8sDi&R+ z2J(@|J|1_>tvWkBy#rcF*|7Meq00b3%9)ZjG^qm!8QmL{;(NcyTpMZKiH2s-nF3g7 z8%Dq&V}IlmI|-G$X&h zw8IF4hoBk0#esvar^DNGC|n%&mSX(*yK{(C3jNu+F@c7c;yxKTjYaPNwoC%H?7o~_ z27VuchP+NUFrpBa?}V0(7aZb7_on&b{y6a{rYgq5G|7$+&A`cOhr>u4()Au~uWKK4 zVBM9jc5@%PCAx{UUJDcXOiDXnwK}=Ei{F|E6Q(;M;j+CW@jpy`1yoe)_x1r1FhCRo zX%i6v6=?|tK}1?Q6{Uuh?y(R95D-u#lxFB08k7=|j-gSI8cI5b`1Top_rJcg?ppVH zotbma8~fe++0TCVm-taM&(xOT-a!>G**D-2wbz)fb9q8Lt?b869F%eWTA(hnQ)59x zP6(u!-$W?EsrA<5c0`FfQqC>? ztv*C3zKuNwZt==-l}fNsV3J+0AIE;zo?V&xm?*x|Il>k=;$#Vw95_4dok`DQUJIyB zhIyylK2(YCMZuSjGD!@nbT+>cb-=NgzY5YJoPGB^y*DQo2gU5m2HJsm=CrdHTQVS? zh|lEcs9nfg6gTSs9QWEv2B_i?(;wT9HI+`&%CMS6^fXLux+FM{f=rW<_evL*gm$K1 zbh|EB_vX!;4zPLb_OZ|j{QE?nh`1mX5LwgEl0Q7&ZrBJdlFC`gtk|>ypFOF0R#Q{c z1KKFQ4WQw?iUwDmy0Ozahwx&rLxWkfDr`CqKH7`WYFC$DBk=Q2V$K4+kLI3UgY#wN zIZIZp=cWG((OihW-jaIg%F zh0PI&hIj7XO?M=LUQmJ4lzO}=bu~{`*%5mZln5Q;u$wdU0D}jmZsQlYU@6s2cl;Ec z4s%SXaY#R)V#kGl68H`dU)LrOE!eIL4jjGLz3x`D54oQd*N55I3%@a_&eou{vD~E2`d{31M6uwaH*uXOU#q3x{p0$t<}j5GyemhmQFA&guF&Se$`e1 zc81lTyU6tMOF9hpq|Q{0u*gU&r=L)arUX4ie@U*49kW8$)$3zClyi>2GhpJtS9}1t zUE9Z}V!?qz)~^^-(T0;~mf8dNnVgtd6+&~(>IdiB4eSPI%4pX&#!AQ51b}Yy?Q6Kq zEit?9iSQuPQ=IS|Nbt``@p~`h^B_et`2+$Ed$kuplLd$9{Iz*4yC(uinx34obi?RG~aBWJjqLv*Ql&#y$Cs79XE3((DdL`=Uv}Qmy{4j9XclDfzp~*>SMj70uPlZ zNtM}poM@9 zHjrv%J}V%oX45`%f+DNm)u8`C*`-Tpa4&lqwnG)16>tiy&Pv7VsJQ^E1dw05ly*uY zfN!U4dUIjK8M%}X{^$YX!~P;~sE-!&>gf%bF+sIHDQypRyJK$8Y`!j`kmbs1$vP$; zB>MVFj!F`AV@wdkTceNP+Us{*Bb-p5PS|FC9L zq%lDUHTb78jR^zm{@7!%+umCN~TYo zLQ^mPuxHWcrx@W@V4q1+our`4v+BZO`}1;h-vdA6eGU-n(t(jnJzx&)-EW-if4)!$a#cP0c0a>{Q)q8kdbJmjTXtd?pR^>dpeIUkOS%f zKgcRN^xNPYW}#>1;J-W(ME_85Wkf5mhgb+67`7icC#;r|E#~PNLqy8d%&N*DXHBGh#wu5;9IfzWOjiC@%KT~>cMYR z99ff7`VxJ|+;mJ)EYtrotatwy2~T1ji{16a1NLfa!Dyi~!=t@ag%Fd$lOJSa=v+{d z+Fr)?R~H~|uvRDzSWB=6ZLZF; zr4|E;8nw4pS;pqO_fvhgjSBBvjLy(HgjjsIL$kMPfjt66asSarExeAiAaBqxvxxg~ zD}`HK@1P*Wd?;7Iy1^>OU{`rXMAeED&5$DG#V=t0OBw}{0J`5GKRk4TbQ^7m;hoR|WF z0vMc3Z60r@dYypjXiL=K zM#{*H2%l}K(=t~6DrrY|@(gPW3z9d~KRHvmbX}cCe7Ve(uQZYGxsAD`qq-qtZFt#R?IAgq_=ksQ7i%$}WII05L-v0>$$!lq$DIHGp1&$IMxdjB)qpwY~{CnAOYscf$O zoFaCT8t@HGUENevs${mWARvqgiU1K-R_R&C{U_hW#&Xzu>gnml{|OEcKc0;gRa}=j z#oBD>ZTfuFeUFK{Teb|2&jUUNL{$V$dhs*kRJ7CpoR5P8y01>rxnFR4eClt*{DSnpfQ-+dIe)Fz zT|#zzXl6rSn4ZFjM3vs=L3}_*Ll9coe-6rnnrgjaeqP?Lk=i%UBqhITK*B6~UVfzV z#NJ~*+wSFgXjwq&&w%fh9LP7#eDC2-2-CS!?aFpO+Sqh$%G=`}vMid@=dNBkd_Z}}K@@+!~IX9fopXjhJYbggXd%v>-#vIk+(CV<=*rwhdN zGDKpCn!dyQnmDDf(EdO*HMPU`o&dPV|7pv&M0RDKgLNcx0Xne#)3D;c{T{g0=ib=V zr0L?~^1W_t!|Ng+AARpStxE9vd~L;%DgIt|O^@hZm&tI0FC!y=H`8GPkG>ifezL3- zJir&^s?PGRMqQur}FPvewD;m{BZ3LTJb^rldcCx%>6Bq}*RD5&?rF!_KLm=d!v<-TLiCQ^8WJ&(t0z4Zd zj5NQ$r`TdAps^*M@k03)x~dWmZ+;fw$K-As*ZVS`Iva*={`Ul0D zZ!Uwdt)L`EYSnPDu?c)RIO#4tSUK`Cgd34gVY?6(DE{HlyFXVx97KK{b+AplQr9143RN`)xmWdZCQMemu>~ zeE2uthO-t+?3`FrW3?0lVi57a8E!72LKV9#wn@4o@^zI}hx&UK(gwb*PFZCM~~A6}v)PIKyO zXmng~?-W)B*eCwa{afe`yKaZf@MMJ3M~Hj=T5Dy<;+q}OP#?YKMuW&+iBK%TeNuVG zD*5YYhW%6`+kg-S(vhCY$|1kNkB*9k46xKWza15sgnHuC1+R~gQx5pC%p=gSF)_QN z9x*h~^bgmHQhjjvObj#yS4~EALf*Y&u=g}QhG=Wk*luVV$9#DQ|L5|2orr6&%aC4y zRU(8I)ZS50X^qRxU3|YbXp4uy{l6Wb5nT%Z1DFcTPv54ef{p49w^CS*@L}!zkwMS9 zZU?i^-Ck*zekbgjqksO`2koG&j9fPJMhAR_NciW&Hly!jZtrDAI+ITg3uhKx)GhY$ z4{~&9I*6XcScK(g<0rQJa0V?|Q^xf&ip!LpbvO5~^i`{_@QeG|`m9?0@AP#-Sj zzO(!{YA@VMv;F5+Nr{pY^~5L1cHJ1wOnr?~VKuFbuoM{R2W%w)r|Aah;S8Ejc`mlM zDr8fvMoY6dw#M#O!m->tza8dI&z3cPxFRE9_LFu~1jH~jTwGSU=Y?(h?tuX2p-tHI zZ%*)QIXEnE&&z+SJb^L`eTVx}42zEiju>3U1=R)3Sf7WbnQ?l9RQGBjq-0GZoyAxW zBVIQU#oW|C)wN<;LhN1`42!DDIEthw%2e1L|6}`(p4GzsXMU1W+-506WQOTR!%&^7 z4ex#=f?r+1xjMGD5JNB;t&bhIKvVaxpHH(?4rdvs>z!`sqdd+9@#xJ7W#;=raOdbG z<&<_dN8w3u+2tL62$WcC=?f&J;I<8bOdr&hdy&?*91hyqV=SrTUgMKemE6*x>+guUGV}cUiBnjBm>w-_3 zJ{PeR$f>{6aH@{_X0{1$tiJY@u#I4^$d292R}zQ>0U5<`gIK23RI{b*p zEsD$7?9RAbZ?OGA98yCU+>ahVPCZ}*n}vaXBD3PkH!vU;MM^ZU^Jo2+YN_~G+HVNQ zb~T|mQ)h;52Nm7VAD55M7if~4(i7T&vgp1FrrsF-#7^>_mKJsSyA{Y@ z;BfoB7|*aC(47`{eR+t3-h&Nx3_Mi15vAyYyFgYn zg=|*MYpX03sEgJYJAWlczX!cX+?)OfdoQDrVVzUw{WW6+tBAH5>GPm`iqZg}ILN6H zOVxj+ke#m^3RD|fe#pX?q`#wkv4=>=GOn8KFSI#8To)C6!nH(*Fiz==&^9uPSzLOOhF=f;g2Ro>rL1}IVn(WF0tW`95pb4Prl82(`8+!PQ!u4K9o|( zl@1w{4g?~>`GP++vw7)yWXSEGGywz=Ld`xDI^XJ+PB_L2i~^F;^GsOh5W1Ly^oEPa%H#NgF&fX%(3@k zpAPOp+H8BDFr%#4*`K@xUYEc-g)1(gmbxk*9PVp4({s%+?stip@r?sWRr)=W684-z z#O|!3lJEVn?wKzPOz?3FYjkTA5_yoJ?EBBkjO9}1TM!OgzrdKgFgd9$|iOX#H^fc`MJ6G>7AO!X{Ldx(VAFINH|M(^6J?Orl0J` zKblhyR5(qwe-0>r*bsuc%XHFiy7;Urhqq{!I3`x|u5ME(O1#CMR624UEzU2uAG}Pi zV_VTx&IDos=jJ8JNv(pG9kf~mZqHzo?t-jtd<1Dd3szXjmQ6;Uj#Rmk!fgV(0yln^^O)xX^8?u^j3y4AIF$kQ5GAeTK&X-x476oTV}3T5Pa6ZM+M<2~b|3 zyb^NZ-ir-f&U1MdZKvrtBnQ@eIDEGps%A~=-tN`wfXeRN zzI|ED_SUTzAYydfJ{HoGC)q$8ij_aDJ(R&L zZ}n&XczGlVnTeOuk-N$tnk;ZW&+MM@V;S1!In@eWfrGZ0u>h_@*Wj25jZ z1>#aBu;hQIBgpxc+iRHZE9NaW%In+TY*2m`T4(&POxQUd5qbL1%&dEJCsai;H7&CQ z7o2y+9J>E)l7@Hr2nvk@o7+D7v8Se_YU7^l$4&s<0csJ4*Nf~R8(lREWJn>&Bn8M_ zt6Ev%fJKNIG}6<S$;mW{CM;N8)Gv_tHT(jS2lY91 zs}{A-y%Fgi4Acv)o>X%Be~h>7`-@)h^jyc>0u*@51Ta?}3~oX4-wa3Rgov4s#s$Q9bo| z-urxBx$y*~;FrASg_Dy%{w!~q*svW+!ymV9b1&DsFjP%qM`rMzvG+75E+aqZHDM(n zYITnss4j!#t#r0`Zmz0tbVXlxA4Ua}CQjpeZ2&NQrV_Kg`EEfU^_+LGW|nfTutjko3mFE16)DuQH&&UU+ zuaVG-`L*GGaqq?3TIo7p9yNw{ks=SDkz*=PvUG585SuSsB6>H~ykZP6UPE*KYb3O^ zd1OSylakilGtEkHe9SK3x$n8DGNYydkZI!l085G5)n+86&ThyE_gm#>+c%|JzYsG99J6t>4{7yC|8$-P<3X1_2yN1+BPH?ul(3dvbKhxG zvT8N!Ns3>ze;yZKilz0;kMZ4cM`bUhHuTE-hW7bt?OigLd3f={g;oWw=zH@RP+GNH zj)Yb!vgN~4WA8OOlayHE2?zavVbVp~MvGVb@pi&4<&XoOEMFUP>}15YdTxJe>N7BS zl+eAmT+hM{ZzczlCJff5%9imz|G3Eub|2N6)aL(5I8=J^pz~g+=F?AH{&_KIRIHvY z^wDRs7f8#YQ#yAsb+OM#1=7T)U-q9f92&|x&TS_7(3{XQ!o5|3JqQ%Ewg6IChqjDFD=Pe<#BbQm=Jgrp@eNt8`#-WDv^5YB>anMfe0&{l8 zXLx#r2qJw~T*@oAXYCd@yyUlhAn`+ekjZ4m1No_6lqwta^Rj^E_LdRv^2C7>hin?) z#OMD|Zj<7l;tuNX_0)c36K(6}{e`&YRk4?$w1UrRYQ8b*rEiebdBrAy(1T9sib8%@ z6Z1l`MJ-eaZH)W$s)!!>eH8V|oXpq6qCM|MkLs2F!2J90uL%YuP@3*=$fG0t-x|gu zj5Ev1%Fg&y0?_R`?2Qk`3_24GahaKtBWs_oS;hgsV&Hqh(saUjOf%}cS|eYU}4W+dj$>xtbZ z1pEE5NBwoB@{N1-&gfK?@_N$2I|Q4{hb^yC^{Y9Fmmw*{ zpj;Ti?jGCO_FYNkTIW8{WpFcSKiRaWBqJhEhV@69H!fXtu@yZB5iFn&Bgg>OYZrZuH6atqXLt;jrCO31mX6)*wb1N2#XFA_0 zt@HTvjh)yr{=L!_{7Kj7Pme5`?Px?Y1w5Udi?XxKJ-D`BU_h1?-|`n4Y!?JU;y`wB${bg39qe4x$mnKifJm*$QlLhzmp z4?zt}_IbZ;sS=R*Rw~SvC)?1fkc>@8WpqFXDWbQMkIzmEb#S#30HEw{zn*v)=b3z^ zG;|*Whk84Fn$Xo{315QR0EhA{(kRDn3Xtv_S1724F-t<0<2XY(tLTBkoM6y9c&^v+ z^Q0Ee6{Yr=n4{mLuNypp96kkVio5Ie zQtcS4 zJmSO>&~GaF_4L3s%k~5hV?wc&5S@WVby)hNQCqqYVk?#Gy!_ETGCUAgh}(L_t-bBoPKr@*U>STl^v^9+Jo4C1ZqqQ3-!5P)W}Us3($lO)Kh?1;sc?q_9B+KLbd5+H8hH&9hT3dc% zKb;F&cx+Nxq$-RcTGxR{tCw$~R{nbkjx=eYeDoNr&h zkLph*W(kRSw0L=q>nRymXxJGKYgYr?@*^|SR*$xG&IaB`=yL@QyNulZIVz#6QRi_9hH_$$o+r_R8 z!Ohx@NPI<4_vUbP*Q>w$h-~Wn=OT&c>QdwC%rV=qXXS;_#=!_yaE?65ApC-Xl5aTN zX^GB#1(@XCJaZl?DXA2Kc;vBgrPu=eONunctAtc@>L-5u707+uuU%p3?;3xOA9mX+)Cq~XDukT z5_#}cv0IXao)ISPjCtLC^Z*uX-Fb?>((fc2Tik2`x^UGE9%Yly{v#A7$YC68qD_!! z7JT^q-RDk@f2>@N<#!GjuK%st1ESdKs!7briHTF7snQNQ6>kaDCMui^t)yWaja_-k zuJ(+?I^rrOHojYQ)ovZyPH{I+ciqgJo5@o2z(2lczDhLo69YE)SiwnzeeF#qY8F zF6WU-$L$8@L43gilrF#{SQlSXM(9D64%;JOx6ST89aWz9FcDObu@*vQo&vSH5(SgK zWyL0Ge%B@C#qX@0B%-K@zYTgmm9@poV*uv#fUu~m*wI{H5N*E373-zWB4pi~<+H+5 z&E}U3tDOiw1X?@g40<8lqN2Tz1Hi%?`fQAW z<5pp;k4cEimyLIZW7E}r>eZdUJ(U5udHH=N!jSMN6RJ~pwu(IbT$%hLUb=&KIA|Ft zsF4o~gX86an1>+Mj7{lIwe*`~?{092hGI;^wZ79`eWDWR;;K3|audw^hj)>YIN*)l z5FW6925USXYB4dWMhI|Gfu)hOxcC?%Ic_+)Am3=!o12Kf;%K0_awV;_rq*niHs+1f_Vk;#-Q{*}<^i*WZVM$~+~0zVqR{=!({BVzZ8C-p3=)Ma z2jd()1+^bU)!Vxw4D2&Azi+=CeR~HThn(8qmw7?lv)@o{+QPf6J~8Q}f*&-Xex8=5 zY!i>`6O-6%V3v0dx9&}AAwIDoh+~un$A(_PAO{deO9`w`R)@Ae$+G{(4b(m+l2Fld#XZ~`(49{ANjkd zS|(gO6l_>nW)33Xo)I1(J+qq&SoGuoRxMvd0adotTlxrUVERGBQ2A*Uk@NZu`&b|E zN7|Z!1RDNi*4bsvOl*`RRvahjy`c;b2j)m-CX*7re*{jowBbtpfZIA@He^n`^vxI@ zH?T22y-~494DB-$$L09ACdyTc81ocHFvEiV_Oc7P%-DwRxth~yD*E4nZgSV5B*MgP z&CCykU1gsZ7F&uXIlPW%ej^mYL_`O~-;gXw8dsIB`C@Y-y`XN|V}MV>URj%N@`HI9 zIBCJ>n@79X6@xSg<0k`&o$FgAI|a9JtKBD|775zrdNks06XVTAyXXLrLY5}07B&Yg67uGdIl7Iu zS{3pxcEQK51OOP|ObN+xposad-#QW9pI2PhVwCnVZAN7wdh~BO8pZkFn#o4DCDLW& z+xo4tx>T@ZG-CNQP)D%0CRVL8^JUG=)1ucWK5n*bHKAu`Yc4aQ42K_lmy^2qp#x=h z$6hSjN|hp-LH)WyfI#BbayuOtw9a}c(}Va#Ms z({g9ZXy@58ZEDe_fUHDAQWsE_*1x&~VaosHBQ8DGy^9DSr{faqZauiB-ynKX}Dhp!8gp>|Bi-TD!%PSG= z_$j`L>3p?Oh`HC@ZCUp^n!1z{>o<{+x4Ky)qGHdC4h;6PnFEqdiSBoy*^FGN`wKI3 zO$S|I`p$2QkK;TW@AgmcZvDQfsqdYFA`3N_$yW8spBkawNC%ST=Gd!^*GqqsIic_^ zfva{Jj4)f*hjNdIFA&^b^YX!DshIrR*Gv!LM*d(#XD+7ZpFkvYlnU!sF_+9J^@JqbCT$NIs!k?@V*$)uiOf|aVI!C0* z0`lmxw|#R4yNwR_akuF$kGVH19uMo*!U--mF<-RnmxCLLMIMOs-5-i7?TTRRzRpYL z7gUt>C5sOm#0h7K_u8YOv9!}Eg!K#Mu6Gq9Emc1Fbs2gE7cUe%a}L+6V^&{&YhoHhu9Cq+5l6{tKH(BM{TvVo5vb>{E58_WdBvuLLJ6KXz*TVgO?PlPt z!+Z5W-Mxq&{H>hCZos(Rg~9@#<%SG*$p2^8jJj}h@!q&~?6}IS?W_%!HwE7Fl7e>c zt&329meV7<`r>{nN(xhBItMx)0-W8ewZ(=WOMRivOI54Tr~$FyJi$JE$MV(cu&W}j ztYk%McnYU|Jf(X=xCe+P^)ek=z593XfI2z+979_A-n1Sy^kH__-2!I+W}Owh^Gdh} zsPkHX63&U~?RFiyg&xK*VT|JGaoEPOtE*iMgzU$L5N!rEp4%Rc1N7y*IC-8l7Fm)f zgM$az2p?gAvVY9!1Brcx>zMtGD~kgGg#@lT_n(63dp{a(ATtv#3VX!Hi4gov4aD%?9Ha-UYpH`b z^O$-)6ga)**-V|$r)KsUYJ>w1g6*MVns$bX02T#9%B6{)K?$8tBQtKsoXGxL| z9@g;X&SS_2H3((j&lh60W;j^86wdyi&E=(FW!Q&~iGIFi)+nSWA6nI{5&*_!29l5O%L^x^g)Gbjh zrWkS&yAK*=Pvwnw;? zjWC7@dUXIBQD_Qby|Dw>nIGhb(aYrPN5e>qZ)Hk_got|{$7rek%)2D7CfnI- zB4Jy<50osG(xKnIo4cjp5B>9gT@VpfbyAHu&+K4u;2C(D57YqKk`N_|%=)Zinub-a zEo}gSoLVz?Z4;G7?7BhTVIR%-%FAXHFhE#7N$aqxG`ToVoxYv4U z*t%TW(D<|!MPL|uY035;C{V8;={?Lp^F>*y!-io0*h&f!8OvCje!(w1Iau4zN+5P# zGqf}E%(Xq)GbBw07#TjMkEd->oUQ`i)l&Dy%AaJZl)hq(#rkdsEyTD8|~Oo z@lKRdHk>Nbx?zh;8g_~Fz!&-u;fRKX$e6Zt3~j|3n9!%6d?0p1FX-p`&|)9S&$S!I zQefi*Vqy?p{p=k3jz!p(k0kWtK@iga-8c8S2tIS#_%k6>tZlJRrE)mKF?Q=tZP;B( z>Q?)$9qinP<>+ub9s%|FcFB$Zt=oh==KTHs0rLp9n$(dWwrSf4tvfz$0)iPX$Gysh zD5|U7%Fvp-yyOM03kd6x!x{K5X8*yL(bKNl#E9LPdWCv~`6t8<%L_klo+&sY(cU}w z>3@qgxS9C*7TPO?e&VI!n1{`f86<~T{qlg)awM6;L_se*r$?F#eo)%!pDzbWLDIPz zv#}|a9_Gb;J99FI+eAv$mUuF;Qo0(_Da6&K79bHO zh(^W`VH<;k0RM)||5(F5_H%W`nxjkNnJax|O;(Y?37?uR?BMs_6^7rNigAswY}PaH zkU2XwQs^uu$@N(_m#pDnPmAwD?CtwtEfmG=Cw;vDfcW{73e=@Q3{aH`w814y>6?3Q z&prOvQj!EsEXjBLOd;5K4WByRrqVr0iXMZp@i&y3!L_#5PcZGQ-Qo@aM{^qVCkV5l6&kk!T5gvc1@uP235Ou^BdCiUqyvlU0-8G$Pf^r( z1}5sS1}OVT2ogo)PyOoP*tpvfv2=+QKL39+4=O-E1oT>J@|BUC+4wQ>0&D%$V7N@=54=}x;dyDZJoiN zwJ;UFd#PJ^dX4Fy>v+il{7~}68GdlCT^3yEuH|E9$~;4Qxh=QZkQ~hKx(8>RBNK|Q zCB>_-2ZFdI7@{*|Zyfcxv)jFmBsLe;3Wqpgpa_+Gvx(0|Y{7qImMg2zz$o*mf)16+ z&z-M}n|iUvC!~Z`hKD?p9(OQ4YdyuFr~f)FA7c0J6PhWRnLAQ{fk$D>+M4+UYzp%G zIk^uFEa^RuQPRNoxjtR3jQPSDXM?PiIJqa%Rg2?lNRM6Wlc`Eqdg5pLohDr7BJ(6_ zUy-g~)Wjhr{X|GoajZnTk=wF8IOgg|9w>xa$Lw+0P;o^TyGU}{sGgu? zJmzZw2QdtZF*5~+-=!=j277GPorPJ#+t4i6dr-qrl40=EGt}A@m*_OI|T5v zj{p*LK4eZlCz5%^+$NY>YUjmxCePK@!wh2jinwbtv5uEsfI}#4JsL<}M-ZI4!QnXv zec5*&hwpzJ9j#uL=oSkRSxp>s>~P!W4Z}z#B057zTx{dWK@)UWSa~^@Yy{LUZp>D4 zJxs1+nSlYqJZ4iyhO)XR2)uS)$%c=*8FkuF!>yk(@}o}`4_4wdErkjCQwWv; zCctBq7}|MJyw@clFXlr$fA@?KG_}!DA5F_E7y3Hd4Z;6O0AApV`_vBxh(?zmLJJ*8 z*Xk=qu~9{ajd(4>Xt+4r1gDCmargy(hB<8U&KbJR`}s?gu13OG|Bst!+~R-vKa+a% z68{;6c>{uW#Io(9(z-08s4R#Tm}d4%r`tmx&99E7IQKIo8uEshPIo9KyELfx!%DD- zvN9vzF5z6=)bnoLI->XHHlJw$*6*5kZL=yK9`iKAe{XmBT|{ugOL-?k0!BI4a1_Ag zuEO%>B-CdTG@7RPRU?9jxl)K&Za8!kwiJxVHX5Y~L3M!MyhG{xn4{*Xp_?goHlaDm zOquRn%A;wZi%DW?#U8i0xX&4!JWk60JCx2CMw<5+>1)k)B-r7ZW~im}4^UC!7P@qe zgqH$$N-}+KFo?n6gEaqmp$NqX@Gz<@t5Wsf+$~l*mkIq_rv5ywD=}52F2ZYUD~!v$4;>7auVG-+P6GGbPuEknq+ZmShTta$EDnq3?DM0vplK#8Na}?$|Sv zZ*;+2aCiC;IrPi*3tUM--pH3J6EH8MPStltn%|FPd49R#qo1Fa5WCcTkAV zW5%(`K$D3Gh??~C(_{x245J+IBObROvB@&7DDMO~InFSk#m-&n!F7BXdLmTur7fL! z1w$8g7iqrpijc@Pj)HZFIdCd)D!$$&er)}nYSC@{%>=om)YCsRxGxc)9v5eowPKzN z-zVj0z*xe?`Sa+X#9kwPO?@sqwnIS(Yc#W6^qAl)hZs)s@rLAlh2B-v$R25H7~G4g zxg5w2>4ik+C4pY>t`Lz3DBv2FbJ0#tnhGQybl*Bqe$_SpV-l9L$aV3mJ`Gxe!TR<; z>+?Z0!#gm3WvojQyh?wU!t+SIgFZP&HS-wtaTVY;cR%ICsSb%v&+lc6OqiOTR_=ye z;nUV*2-2JgG5;73DMd*cH_HsBVlFoKW~_H*qlr28WFn~yvbkqF0rJCMs8ast^;bK7EgN%6`~L<}2wFlu>(~o}00`Rl>g>6axq=tr1p4`*yBcRZL=F~M0XWIO6q~q{Y2v+pWM3D&6)R9 zsGr?>d9j_5Eo0ZkGza2La{&5qPl9|h1z#KsBu4dtBqICTDPveGLJQ<1J1o=>B`K~v z8EH)&!bUArKlAqIKyru;vk5%w1&7WS9)40mSXZvXIXNUr)Q z9ng-Xt3@)rGsjvKfr^{w@Vtjc(FOVtOcW`@2Jl!OiFsVgw#5N=l0EjHTL^b*7?O*Y zf-_KYS0c!=3L$Ea=2e_LeI=&<2l^-=iZ~MJf^M;yRC{{}Khxw`e}UlY?SPIW&d!yE zg@k#S%9}Hd94_LS4un?a$j2S2KeCHe;B=DZasdVsdOgnp7d>Qj)}~vx%stEF`rjO% z-J!?4!&+7Vmb87Y!C^*7+K?LMpgcX}e<4CEe1#jh}q+q8@BZmN$arN6^Bd-NQV zUdAo-?n4A_kdMxpToFX)hz8s$yt7-OK*(-%!aR8r=VS9z2z09Vyk09>>FZ&1Zpl^- zCuntTLY!sq1gZ2p7cp#IlYQ4a(Bv*>-@oq95dAn#DJ%qH*7vkG0;2spNQ-5XRyseW z(1H1Xkb0FQK7dS%^Jmi(%2S+DaA5YeO*;R6^6_tICQxP&HR!NTPMvA!rTX=({O=fblWu80c&5P^bIStu zsFL=@k{UN#9&$KoC`64kw$PdY*7pRPpYlDCbfVXj{ql6+4zUdv{2NXi+US{1D#ff} z^U+rQs-wvrzWrl~Q=O}#WDmd1FIw-)gN?G3o)7X&Up>};J--FQ&xefBnlgZjLdHHf(sMJAztvHCi{MMJ~U8Q#XH>7$}~s? ztzhT{dlm(=;9@xLfo~Slo6nnf<*sU0<22LsoJN^ennt5}WkSuf>Z}wd=;yMV9-RT? zX3YWNjBM%|>27~OS{uk!A0clYx7&qGe(4JvniCUwjLbvfBNq*qX9$JeE|%e6@LA%z zKv-g$gIG|O(Z#CPAD+dsC;R?IUS2w9o)x`3vw-I7OLw8^%Zn0tCAhxHRjwAxO&`8le3(HSXCTyX#?31M&4yXS?1Dw9z2sXYtK8gDLkx?fz&eDZ*uBz_Yw8 zupJabo6@{^@#2du8STJkx93=v)W!7GSu}miwTfRsWCODZvpMBLZ6lV`=)+=ViXXx* zhEej@OIs~Dn!PY&pPhaWHHwp=Atu`&?`iTznxUs`>9>kQz-DqJ(tM^U{YbFWVsirJHKn3vET` zCH2wtgWCR=Mey+P)i4Tx|Dp{lP$u31XC4~s{z4^?{^nZDgp1296w!<$4C$GZ z#unQ{dmO>|-D!aR`GI7yq1=yQIal8}I&LQd>{TaP5a0w6Spd5iM(d}6-nh?Mysy|X znVOz81q7)a&m19-cIV~6FnsgQ*P^Ojz~)vu&81SRy*Wg2 z9dT;8K(K=JlK%ncJr+6uNkF;`{(<^sl*+pzx?fC+dnI6Y_t`Spib^Lq78?);#T18aFG0HQ>vQjF0vhGe23%9v76=ob_o~$NKEnw2K1x9s;QA>VFJ)N?5-IAXTx` zcHenPZQJNU)BazQ`PQ7c5cU|&*v~|&J z+;ahOMr@WuMh3fB<)y>pAqO-AL4=*IMoELp6Qbou4$UF4NKp4o4j&>j6u9A{`$5)8f) zr%<*jkK6!|b4!3`9K=L9RA}?bkDd(&GS1W)FLAhwz`rm6SO_s{!eOYg8y{1OmzpcF*^{=)-v%B8~@uWI&-lTLlOxff|0ZRB{p9Q+JXP`;=EI6}^; zGos21F@A$8JFPF%@)L`2H?m%R|Jzk^x?b?Sp<~F-;~T=ogMZF~?G%J1>)$`youClf znXD2U`y9Kb@@t!zmUYdl^FllUssy@#c$tiff%yL(2E&G`HUjr6q`t$R3$kEvG4Mv3 zouBgSh>kw0KfA(0qy`D;?8AuinSb7PT~F_X;uf6$^-%@Q-_G<}?nBd5oMq?g+&eRF znLRVg19No(<0?EUcz6erFA=L+?rdF5Lm3~Ht^0daA&lef23qzNl)ee7+`ymXQg}&6 zp#p?Y=*gWIJnatn8>^@~T1^78EYNaY1IjD33|K$yBR^jDbl?p(Rwc^JRX9KVU0m3e z|E05$gSl5IdRoA7_h()bJ}Ry^ED{ExAg2qE8vB0{qVPk#o`P}m1$gC3Z_ihmZd3a8 z1_PeH{zhY6MnK%Ml34zIu@UpXFlD@l3HgaS zZKrP?6D%Z{CD!mj<31E~|JLukeV|iFxZp-svG;rhbvgSt0>_YXrtk@CXM_5&5I-l& z2asEXq#+po6yRZ55j#^st0UNHo#8K33#36$tU)brsOfCvE4>S&l_|XC2`n@WDk^p7 z&g0E9Eby)@r;J|88kC0z1yH>}Y{J-hDz&9s*9dHg!oq+YMD_@xF(7mv z@!gP7V}RLxesfAPYqr4qz+*IlF1@a({CDz|q6fFIM9$YtT_c;_a^^PE%|$l3Zfi`*f&A=Ei5L+mMH&k%xM(zujJ(U?W>aR{CL?e z6oUAia!KAR&FEvmRVsg}ywu`TW=yuUkMFMuE>m6pP44KU4`L1u)GVs9u zkc!zJdpf7LQ^n9!7GG(^_ydML6pqi&)U8s8L#Wjc#T@wtsD|<7K0Z z#n|fAa*V|T%&hSav%@3zq^9N|D)=<1F3A^ z|D&W7(o}W>Nl4i;N|9u*vPZJX-kcVtP=vDg-r?w&rAV^Jkxkiq9DDq(=jeTZ@Av+r zl4sn{J+Av2pX+n+@2S-FhBe*P6l&d@VZTEN`8}6&lZaJ8?%E5|Gi2Z~0;v1_ zLIN^3U-MwRj80xjUegeD@G<8DBp@?yt81e9mAm=xsw%>^f6CaC-#Qwc1I$7GSfGAJ3{#%_q5anY=-mbMsKDg594u2ARNw~W-1ZGZ=ngn~ z>~L9}3vlm@<<&4|2yAL8D#ik#B|A5F4vF_g;wKoYD3=oK`_maB4G%G2JFd}T{4kNJ!t6L;;I=HF@Tz7+Ij^JT?m{LJn zQBA&v*@SiW++R*AMH% zlTLDK^8N`Vn&}ch@A!dxfLa!8Z}r(rt;UVsXlW25M=0-R2}#q?D*Hqub_$&|o~fFgtq9BWk$tSs-Y@K>4;_TCiXaKE3b?k7CVZBSMFFoGjj^^<{nhx!X%p zjO`1+)yhTi%R!CVprv5yM<}itDhSfqlqv-+g;i|cIxM!T4`&Q?4kcU#=0lq?ru}FK zFz=1Ql|`!0d=zjE$#r_~bK(LUn;{HcJps5!!t5K1Oh)uNiHVkLRkoBdF_Jw1L(Js7 zgm+c&O8OSD(xn;mmbj|erb@&5#EqXf?{z-XH^x2)){sp`#lr2_Gf+TI zJJUR8>nR=Te8*gM67zBFQX-T0%0VN zK*|yDhL1fxET(wpj$dMxFUF)k-0^$G&g>)*zwkn-KA6j^x9fuG{?<@>Tr6rn zuu)A_$*91(QQdzDJ=RxQ%8ri?F7u#wkXDTaYfb(s^0&%4d>P!EXTL-imM~-~$iDu~ z$N-r=LZWwn3)pa~K^#$0;DErb6NQj;C!EeR)%lR$#LjnsN&6p3CHijTQSH0!;Rss;R zRYUypK0#W}9@Y51!}Si@qn#%|08|y8aAi;B>U}gNV+(Q@n3qcW2ftJR6%neY!A55Y z(j^{gl{>P2EBD;CmRrnqw!e6&**)Q*F52e*?Y?E-q1nE^DK**WAth4SAj79gG`b%> zK+B-;6$GP}O`Qe60wf+h5|+zm=B`ImZ@y-?JriUo*y;_1Z4+)rX7KwdOE;QRCuL4K z^az~EX!e(_Dr8c4!9g~{c4pvdRRu6^gkLfCLkaBCceU2a>zQOwg#;956f^!O>na@= zslFblEvz18N>$rJ(hA;14K7=C3c^y(6chTTT3;n$~D>1CPJT()Z`0#7syHwqKJ~cu z!QRK1qeqVti-0!8UOzKKjlK(^|Jgt~um!-lju$Bv9o*I4X((E8>R@HF+g5}eZnW3< zI{8jATeaEnQ^^Am5dsnTg24mXXg-KyYMzypQGp7$l(HD8mSLG(OM>Ws0o1#Q=Ir9) z=}VezYkR{BaZR>SM`{Y&y72_Hhxs4JTi_YePsu9{tmg(k$5{`ud5HBtMoT~aXlUpF zlI(2Qvpr*u5TSx>R09-U4=wLJdxIC^QV}BZ!(slT-sCq9x5=ddSBT|4;`QoO%XVku zKCHPV9_5{>e6(1UC@$lwQPV)|1fN(hVOd$rB3P6}r;X?O=!&^nF$ahOJV4MV!RkxT z&8+TlV@0F`vslzFrl&fp{toU|P}u;J2#tQMx=zg6WSG{qFR z`Ft(?BTqeEqsBMal==WEFT|k}XlbIFf*>}Hm_F)Z_oIG%*~`rcC-9^K?Gy68Il=f` zy>?;U?W_g!m_F^?Th3H7riqN0n2S)`KB=+3bv^z^Y+FU5Ge@srEW>p#^ri#ntm)j( ze{tSV4i#Q{hxq{2|GZ1h+6FhUZ>Od&%2!$~#)`h8@#lkl?gvKX&!U(&SThc$#ugTK zFeF)XXT_g%*3v38&(LY>81gA8RJ77joYc+oJGAEsh;Onlw4vuo^K-6_ZdI|eoPQhn z;i~NW*-@OGOvBGvA%)`xBR^-w6qo{odie!F@i;FNypb|V$VeFrdxbaCG5C;FNGbNr z=ZG%<6ca} zy-!?)XP#U;fw8-hhHkj+H;q3FYO_MH;71teQG?Rwq{vzIr!^Ue7yUNVk1!dlKnyWf zhbu+0W?80vgHCw+v|EC&fI(DyLyLL6yFp?9pq>nFr|0cdFg)YTXO1`WPk_xHZMi=# zQ)~@R4XzJL8h7caTgcYms&g7k@c-tvoNvUJY7x)L_xSewLb?uar%bL(%erwVP`X9@ zobF1bkoGzEB+_9I;$tQ$*7BL2)sG_7)*Um#seU-A7`(`XiydZ0l4#GAl%5QNmJHg0aAD6n33fK)tL4*T@?}8j6z3mwO1nE-g(9qpsiaptqWR9;2LOylb8ag&V;pg z`49sb5~gc!c1{4H!~yO}=dkg4g@Yct{a5?i@=k9KqN8yy8kriN9dCFruTkPq^~%CB zjSqHHDC#8J{x@E0AWzq)b8I6CZZ8^}XDPS26O`BsV(Q#N8=qUj+^cD~)r5N3q0}w9 z@=U)Z59?eOP85YFAc)6k9jSg%^j?Wom*vGQ+(y>57<^61T^-@3b2KXia9f(jU+PoD zz9p}WlCn1VV12)|Ayo4|dmioE5KCD!*6;oAut=mq{p|(!npAh?*H94WX`|zE2)?WH z1ogH#-L>_3mAXQ^jmL`Ec%EPExRt3Rf1_*zG?V1|!Klu0vb;wV6xku6ne zt!{1XXMXgR!>R9VFZ3SqC~zAJ-qS9y&eZ87M1ihss#g^n(1ksZ|A9G>idfxr-l`6y zymN~b(_HIXmMqqDFR}2sahIktOW=w((*Y3*Nzaxcz5?kWdBzqsC3#okBaNH|5jr92VhQ4Iz)DfYmlY1)} z`<^+H6;d*KzQH!m3eQ`ocx@yY(Bj$JeNch7363T7VNfK(n6-K=pWTzNWTNG%S&N#?qipiRkXH3nO;o(OU_y)wC zUJ~~$zz_AjY;uc^YfSu>`xc6yfv}ixTF;j&I!j9j)j9z37(!()Od;wzfA24>@c6s| zF)q(ck=dy^fnR_9)wH$(1&z+Vtpj{i>pNKK^1j@&1Jt+q2#i}3?T&7aj&c2kToEnO z&XHnm#4(uqCQmdM0E94VC%m-8QZtbhBH~y#qq=OkOG~%g zFu~mIMu8oUWuo};_#MBO`3_!{G%&(j196QvdVN@|!z3$2?2F~;d-(pwNG<Md}IeJ0A8QgaHLe7##j$$ldbcq(VMT7>M z$%3hZl>7s2!bDO@eylc`Y;S+AX>DNlnXUi0g{*DTy2<&1jmVup)2%u-mQ4XI6SJ8i zw6h%qw!>|KY|Ej8bu$_Rmy^xRr?amN&v3OaZ?&gqTC^?JIX}Z?p<_yr_iu&cHr%;I z!Z_)x4~_+06PS7mriV!I&OS_&$UT)={JP9m%R5TLh9i|@9AD$e5~M5m-dvFMvJM@qdWwe zQyQ9#+D}*;fofqIX+_PgLwQqef|QMSI{s{%`Pm5SkL@>iaPn)=%~d^7=>K@t*7C%x(?pMLnFC>oyS4%*5}d(=36(9 zLNx#4)#eq6D>pJyf(;=H|YX?5QMpj z9-t|o4Z@S7z1Gb>B>w`E3Qjog+S5edriCHLPQyVIlOpdV&aC* z+@C8a7&FNoIdaFc1q7(Kt!h?$o$>KP$KD+srE&xt3#R(=z}y*g16 zXI{d$uk@|F#;1I;%a%32RacXhr4$zn>e$!wtrK#*d((4zdbEK|=`LC%!HuX1A~*A+ zbqqt^p2`~X!zp6V%D`4gkGY0b&e0Z1qs16tH(pHUYNnanS8S3Gp zoQX~~+DM#$lPr9vgx9Uq&32fpmr(82&L_3Jf1t)ep=H4OWqp6mO(8z!tJi;TB$~T4 z{-Fkt6|@5aVid?pbUMmS#QM`&`d7tlxrF$CR9nMnh{w}|9&CB=PI|$o)Rs_9(4xnd znJDs-K$J*a&b7F5qjY$*HjON*4; z>nsTK$%b2=znpsA8*WpMzfJt5z^Ty}y};~Dr;9GFfL7nJ)yJp*f=`<6uf9PZb_*e- zVP@fOmNJj^_>_lGTs<|HM+EXyBv0`|hFMb;)5v740(M=e?sDRx8k5Np6}#idh700g zzhefN5qfkM%lK1v)pS9ANA;nfzwlct88PY1h>-XF8SAPduu+^w(aKL ztGjz*pJd!gB#>o1GY!iYagF8r&?Bwn>#3*(rqkyMpU}oYTlO>IvWC;_(2-jTSxw2F zCm7teXYw_57N!ntq4q|`#8x)gMNb%`M5Xp#Ic7Bmjt1u9 z&goMmXhAcpZvN9g&GegAcAxjrJj?xPgGM7_JeNNt?(7SeYi$FH#X^%tM#tGc(XR|d z^^5xcy7Bq3K6|OLiP4IK8(WDXj{c~6I(#y8{PCi6T4}P9f_J&vtBS59Fo3L&ww%~)`p=SsaM^ny-203)iSx-dM)0Hxf9GIXhTi;li*32tZ1${ds ze%X6)9((JqFB3HKU7^kbFld7;Ndue5OKKuy7 zHbYcYJWbAfhp*m^=(0u%zMe~@E^oMp;{YO!8LkV%Zgc`G+VQXQT}}|Cgr8cHWYJ*y{=8i?ommF#w`_b) zbi9^ceLL<8fROBO=6IHA%{OyxxmT5kKJMc`&X}n*_?gx-ynp#OM^PxGoF|I!xCdKD zen^mITX|bGSY@qE_dYqTCEd;Q(=^7~%gp~`*M}b-0~Nsm*x8(pp`3#efpAhr2@0xU zJ!Vf49!^BFygi>0*HPwFzF8V)z)j}jj2+kk979`D+`cgyN2m)FDR3(Gg1R-J!fcy;(c<*X;xuye4;H*@)-6D}>*m-%EU zogeR@5YTL_vOYE>;|Uv=!mb9Lb4VlLBwj^a8-Q_ zUGWi>rm0I=9V#(ag-PnO1%kcK4Y##W(CD*+z?S#O(#H~YLDf_LXB$DmOUtzU zGIF1o$`e&n!>3MfWDKv(?qByIZka#Dsrp!=Uq$fF+GXS(>qY|!bLtO^twTtRKz528 zah{7Ksp>4kSrMkxbdAB!;Ug=?RK9HjqPn)$hNrjFZI&h;A1-fx5{T_oo`w0xE&58f zv-DZXg6)D)91M9#+L@m;P4gLIVt3z&nDqmKh|ny}R4Di`JQ)OrWZMyRkP*`%C!wXU z-+nLsP6@RDHg!N(UzL9#pjk031gFi`SA4`KL*<1-dkWMSaGFq+PuM^ z^ELQBzPem@nL>zCQr`E^WeP_*KXjM$F8t68!Sfg0FPYPqYw`*RCkq6tR-LMhXd}4R^<-p7(;U-o*l-JLO$i7Dr9;J&H=4~_={I8OkHOzZ{ zIwXL;jrr24j{OR?4^WjQB{i6ntBi1=#z~;s5 zy!&xozwLw_KCfEpTo%)!WX$oqIH74N=zwjF*QO#II2d@r!C*xoejf6OG&M8Ra?!=m&=6L--i;eKB5F|B zJT&TPaI%6yxL&&bTIqgz+KK~CrZTr?F7p9rQflTk^L9fPKJ~^B#M$+jQrZL?TC}lkFHXvfj zmEJV$t(Ej7=wi3U&Su+Zu`)c!sskF2Jqdof0}e%Hd3njntly&wa*B$kUnLRg zBs~f)OJ)z((&Up|-PxSqI-ao0@Gz7(0WHXlb8n7eB0NgdE)0y0W&TK~TM8akCp*9C zJ}tA?v1@Lo2qhFazye_hOmT5B|I-4X^*b|`Y_%WQ>=#`uGiQUJ5&I?KG8s*uVGEd% z;pL*7Ljz+UhcwvOud-Lq3Zo``n?di=(2poEg5#_g(Ij|daacg!| z%RCgLolJIEOC!*!LfoR56NVDzS;y;!cQ-Nj6>8*BF&(W$9krG2>mReko_oVcfJ!-| zEiYZ!sHCb(H)ro4<KH^MQcr;Pn1zp1aqJYp>iG3lAoncryR%ANYI1 zlQ49jtAam$jp@%usTg}GdNvLI9H!XxZEYt+V`37nu6xvZg{XFPtIs~Wei}XGE0qFa z#gDb7D7>1Dcv1v)sa1id_JFW?T5<6`ApbIT?72)qnC=!JB{KN{Z$&ttn3he0h;HzD zQmt>CzyYI|JY1aR=K0p|c`p0|f)6b|xd$0EXZ$y?j%YOW#?wCzRBYp= zM#SFLSWLw2{F#IxMyLAKb3B^ff)>TZJ^1B>M)=uED5190W8WyV?v!t>f^_oAm4OL| zTlm2t`72r%@QEYkRMQGU0I;O}(y+U{aw)(7py7&14R;GH|D_T4l#jALuy?sjc=}Qn zxq;9D(?Et)ESjz&4K1(@prMccM$(UJ*~awN|P$@%E^N7I98do`t)Sf_e47 z!44esWukIL0E)+C?R;(wkd04v(X+^bqQaUU=f`Vb)r_~8RKW1{lMNhVdoZ~kynlSiMEwG& zPf3MJ@{+L7-=T3dXwn09S|$q>2=%>N!-Za1jb~o~0`8u@5XEV!fqt!aUYB>&3?FPM zTX_kylp9M1x^K5X*`;I^?mX&v6m_*IMZ2L=!44HV``@nlUHS5wK|~#b*FfEA!DEc) zm9y$8Ryst()pm8fxizJ0)S z6pZ#Bp=?t`Vze-)v|+T+);dLM>8{YiG0(t%YwwIoW%oDZB0qu&q;q2@QV^Tn$32!a67CsvMa+0JwxoH|@afXb8bfAH| zK5YS1pSbyIIxV>;W(W5)LJ1Laa`NlbAVr})OCk9{?q=U->*n>1%JYpzVyWox#jJFj z`AD#62(p3r!%`0T%=uq_FYWFGY0LXQR2a+pb<7Rxvb_e>JHuL4?!u2MmRz>18dhg1 zcKAO%x>4j~!ZI0+6)?U3*hXAK9)GjU<=c6dnyp!nveqHOGGEQ)cw^CoKVJ!ymu-IN zf^)Zf&AOt1CtM{G^OGetUf0lN{pdm={30a^ok|c867AxxL+F zRs!XIg#k21fc1Zom6i3vR$E8MMCQi^WsouU)St4ViIaqcgL0~KEiI5Mx~(SEO=qa5 zsLjl72t&xBAL z&UQZTO!ZqZlfAbBe=@e7-R%AfYvPC5mLurqpyir-tJRU8vb7EiG76+uhP4fi z6LjX{_Cg@1-_hN{DOPBf%Bv9=V=NqG{hD>e>CKHmn`Bl5^`(PDZ#qZ-Gnw48alJuCyqB*knFKT_WB;6L=W|o-Zdzz)eA&z;L|^`M zXDvn$E8A*+rEsP}WeI$tWfcZ73(M~^67!8839$3ud3xm-pAjVQJKTNvYVztdIG4fp zp432%UI<2LF}QMj34#pK&+&J!b6l*mQ0pJtcvmiFW(%I&0^HYb_ul{|raool?%X`g zwuCp5Eh3$w=ktO<&QE(fwUEqh(H0t;$qB>HkEWuN;k1@$UVMK z-r>=!iIq9D=U^ddq%b6qZ?&BFEHPVw(@oewQOdVNx+K!iY2R|y5B9w+e8v)P5{ugx&)8=A_*zw-wy61IduuSKA|K|E7n_mvPJVBkkVH2a5~Rbrn4FZ`tH@ z0}oY5dg@kxeZsK>9f*tuu`bEBpHSK0ID=cP5iaktRb&Yv6tzS6p!f1QU;I5-HA9Zu z8h&HB0FFX4aGIfJy4Kx3QC`wg0DhwNg`h4)yPQC8qL}A;r`-(H{+I*?Wwh@4AA*;A z-qPH7g`DSW0F=XZg~O%0Up;-gUqEe~+&V`5+2-&H+2q2p^)=o!qVFGxeOdJ;bBd1* z%-m)6i#gzbxKd%>0}gdk74Shm1MRiO~v(Zs{bbTXLW$lACcmSFiWXZMm7R0*+n+&VeIb>pwce*(mO6 zn3r~UghS_|j)0xK`1P2ADUfGE3YgVZNHEaN(KvMSQWNSlMpwT$)I8^NoKOYHa9>yh zt*CJ6emq;W%MBpL4}f|YuNLWPx2=YpN(fL3Hs5wPY)q;h*_|XFBXEaC{NtB}E+)ts zj$u^zn|QO@c$q?0#j_0M9O?D|e@Q>zmEd@*F;Iq|{dmJDL)-GZWTn=oM~g9cah5Bi zefW^Z__RfUhLfgtWrLAGE3cZi5-@q)%faHO3k#jVngUQj&+Z4EfDgKA*?GA>MqDpU z&&xG~GF@)4Cs{ui{D;6%zSN;*Q+t_W_|G3x;7a~cTdM?+^~ErQQ(*F8s2H!MKHYzK zBEqJ;Ip4Uh!1j0bNfINOEZFHW8w%d*!Qerld*%(UC$zPYKfSV4a@BWo2Fss{>uZhU zyXxc69@9X_?)&ubX+9Uz&O!0Vo1{|A{fGHxb~7J)wU0bFTLoXeI%qi+pP#KHP*xzt z-4J!WX|dB_1x)9S87a>oy?F2=bx)e4RGV#Q67>{!D>#-LUVz@WUaR00kMi~hdT$zK zNX)=4tO^_*9yS9QEQ4^(AW6SuRkg2})7U&lc98Vm%FGoPcP)C*xW$^)v%xhlgw?*R$cnUbDuB;aGIU}yQx z4#(Qn2A=-|8a&pZEaw?&rTP7^2svFXK;sH4EPH2^ww-r%g*IIj>tU1271blnqtt+D zgS9>eg@&Y4`**fipoDuf06IGjCvw{CG-n4t_f|bE>rcueud))g4o^m1?7iMQTVh+g zKoMm7$DNn$vyHS|G7Bzpu7}GWe>fj@b&hF_Xu@K?1J`iKJ#J6{E5$$|@X8W5P$a_# z0?!j-J2UW=tNcP|&Q&SneZ$)7R-HPGxpTAQ=iJ90FG?-oAj}#|3GtCmU=ODujJHY) z^g5_4{?U`kdQz!8dHIoa;fYgXOV{L6RJ?(_j?bp=nx5CL!G?4LSSB*xi(&W2N*bWL z35L~NqPhmTE3ci#t4}|*L`e&tWppyjCHCIe?42=!=%vE_tUDJc!vnv4ikb*M$@Feu z%BD}-#vQ0s?Z)zJJslR=g-{hA>AH>xeu2XEj*ur3$yK(b3?SHo1M7^meT7%nu%f;S z#~2}(E!uPWzFatO?Q9ou!v6jd^>!FR>u2Q3IY!x>3B8aKx6#0mCN@6L?+m^D^0w9B z`?OtZc{5$pqH0@FIYc9FMKP`p(3RyqbOtA72|ewvtG6mv`}F;%ds&!0PlVvj*C1Qp zLVhYNy&_Uv6Amv+6a@OHV341^$+m_erO*OD0j$p&P!G?(6U$C9HM!JZ)De-4CfRN+ zV=LMrV}uxu`nQ`mc_llRA9UItb4Dt$7bi0nkmxJSamLTU59XN;K73qH4M%dI5=dJ&G@}#vi6oquLrfoOU?F`IRgGYH8xfP>KSAh z8oGR@`nQX~{XvIX6%Of>S#ros7-LSw&VzUeQIMvdgVQs6sOS0tgz4x4%xxCLb@J6N z6pJRai!L;uECc#Z|1I9JY8w0)#9q7ARf1Rv3MvqC&*Fo*4N%Vp5a(P_bab}JOtB=k z->XDyYe}VSZ6v~NXKSU4hZ-Oi!kMQ$Ebm8AlJ}St^ z1wYx{p?zJ^g2_;Qg!&U$KC7TVwsVem>rVy8SQFB!vvNkvHRY3!#(M_(p?DSZ4HBKz zKXx$|1#J93(z?sVzb@n8nbI74Doul{2AiPXIx6vHly!8XI#K;D>+Hbiw{ZDJtd zOie}QoQ$8pznX_fDb8s+UAN3F&3k8?R?MR~KH<~VUAt_zixTeiCvB1el8xjlI7Stc zSI&Epn!)^xhSJWeUzbssHmi4XmW*-nn`UEFEV z9sz50qxZ*=c7B)cYako_I3^2R^^&sPwmBFIRyDu-fsW)*_4+z(w+Ns9C_M88DH=ig z|AwK?6DEBLw5zMLA2*NcEC#lR;=iFOY?v1i&D?fbK48VJn+{HRMeJe}poloj1>{tA zYB^e%`g>D1<9}dcygyIztoO~$kch*?N}PZ640Y7~e`8h_x}<}xIpB>J$2?gJFTM$f)9JG?{B8t*L4V;Fyfrd{wFvgzwAFu~@nb^6_$4Q!2v zRMRKt7U8)!4`xgK&l}Dd0^w;X#Oo`$D_o4T(kDcvy$tDw;-iR=1L27G7gD^uCiHd0 zjovJ*s9mf`z2P6dQ>Fk)opH)HGt?;EaKl=Aa|(=!cJRAIcyFx?cN12Fp2S9NyjBwZ z<8aS21*92f`5&0o-*3C|bqLWv0>y0lAt1(%&FvW_kT+X?0ukB|Km^`I=^*f1o39AT z@Wi=JD|W9=*UQsh(-mEf*^G^HzP)n3m-i~0=_oiMUyuf%To3mdJo;X1}%?Y5^{ax)(g5tDCY zy`^s4ZqQOxPGS;UxG&N8_SEkd`yByYqx=%mrEBn@w*h~HEPo$Leby(F1ycr-7+VDg zphI(O9b`R>I%fgC72@r6ETA70LwE)C?f|sry0~*}pRg3f%lL39UQR;@;g0{IpJ22g zO|LVQ#&U5u;r6yRAOn+U3}hP^wJ+(tqo8njbvMo8?<;Q*Lx!Y3xpj3dWPwNvoL%2h zP#<&tPvN346h5b55p1Zv-fmVihPAO)RP!8Ine`5fP^fKAtHQBEv`I-``Zns5cyS(} zZa)C(u>?l3IbovxM}2)e>)5Ju4S7=DoS^;2O&fo7mrDT@R{ z5%*Od%@nH1B3@45jr%%1?mSmYwF zOw=vSCt@k0gfq2XiEi>J1;j4>`Y4-;+CE^cD`kqT#u>r$3m|gyqzv4OxQX-(Rb}Ot zv#Z^@0|KXxxl&f?FL3|+`7m*(Libi$W*``EWl`0P@NsW1t=3MOS*xr41MKpOYi8 zp52?c%u42s51-ZC&_SaZ|F!_uP+(k6rbGlMR*!+&aU|zASz3 zwxu{iNCAZy*$JL{0N?yY@^#&j+^(vRL4<*Q347I<;I3`d+IO1nNC@pt_GltrmUS=A42p4~6&J!|?8n4oT!zR$B&X%)Utth@Bmn^hv>X{&QL4JS zecBsywdKiXKcKn*ZZca%US2-K>*|#&d**ZgE9sdn1uq34%RvYkX0{+DQ_6YUqD;Y} z22cb2kvytfSC3kv3@Vk*kHZm<@jqg?wRiO2q>pjHBMxYkD!*bzb+{jOby}pJEQJS1 z10fG}rPnzIQXf0c=58#tDolc-#^U2lq>z0VdX{!%X{8ACxkv)M=>5S%hqT&wDJ1>< z{oSDUhvRJ73M{Vd{NFVo@BeLM*Dg`LKM$7rw1}cw&PPU_bW!6%;MAH4O${5BH|Ikw z66Q7_ahnOD%@FYxY$Iw_xnbwpD47L83oS5hj#sB)i}+FrerAD+HUIL>1zEWmvEI;E z?|lqVPYMn)W>6@H=+5RM6!Ou?n6q_sECd>ol$fn46R(*6?y}gcd8Lw1A%IXYITD6n zJr3jwOaT*UnHS_)()$Y=MogoDlg93H(EUz`7(837XQn@Ks=PQqFsv4E*?4v-hhgFnMzb@fm4rhDf+)3 z^`zbaXzXI>;`kNn2KODf2A`!r-jb9R zz_;&lqxg;ouyk;e>c~Jz&_b`x-%QwpB<^Lp^-&_&Z?^w=4<_O5w@uVejb#A9s8|jk zMVgJ<6Jl7qlZ~@4D_dq;ZmMj0qh{>$A*l>^yG%J9_%h~GD2xS`0svQF6m+)ga2bp9-8B2} z$-+E!`fvHFu8~I40TAW|dFayI(BUbJ(WbJPWr~R8FD+>~x*5R?1`DPMKv*OoP1=X5 z&JtmC)vr$*$!=9wOI36%+srm&0qWYok4ri&p9Hh;;{AldMKXq``xD52Ktj2IN%U!3Ro5r;JJ>d zk$!!ud62f>5&H|2hdNP)ixU2otT4R98UZ3ATEJ0a#kUWFR$EYmb2)?mKNBY*Xn(J# z>^BQUtn2L#)h$)|isKvg?oYO^+t)0&#WXS*yV3&GOyYtzUseT}Dv8QN@xn`+vw>sT zx9nLj@FW{G!qF$OYWo~VLaHk#Cl^tpqM{Sdr`ELs%srF>+9FA`NcQ$jv`P&4@)0l<6Uyfx7XDPgzPro1v7lMju-yle!)M+ETI%A%5s+I z*F{#*VZtiKagL`e85OF~FqP=;fo$ilYvm@5(Zq>D&xTh3-GxoVse^0F**-u1in|oK)GXLBc+1{aM@*U;AFqRK4<8cMOwpH zb3z0gIg_x`Dv)qZlevf(g5|GS;$-#eP`Vu9FRWtsc1*%))a{1z>w=^!(AFU!geA%| z^w-4Mp=U&_K?gVqYO+Id1JqFM_MG})5}nth5iHH!!@WICD*@z{rG?F|a)fmCUlaFQc?Y2s zt~u0*3U#joO?`81QS0uGXd8H{Og_Pu|F=n`7}$~$<^C!!i6B4{_ct)53DpoNC8T$+ z!9a;pX$&Yjdc##*mE#i-1U` zmXQ(Mb|tds0pwXTWW(nFw>AB`2Sx$dU$l%}YqDI{m#=bA z<%-X1(?xdczk}((8ftF}E8wPJD=#Pb+C=lP%0oRQ6OitXw%vnzP6j7;y&DQ9nm0y^ zGGt$Mp3(mH^=m<@t;+!ysF5c;|MgfQRJnvIf;Ul$Hc(1{kxCi$v%{-f*;69pAsT{p zrP{?we;T3vq|H?)&awLn;-3;G2KORKEJ4Ae9t`zR$&|_|6hCw<;g|33KE*WnW@sKU z1a1VsfBrw%7jiazyx?@3-!i2yn;WyZ|XGcsjZzd{XzN963M#{E9QX zS29-ulKu?D`W%4QgWuOG$!0GWbhS8N#(dSu?2;K}CnqQ1U-2b#m22H>$f>HT@a?!v zA&J)EgPT0o@Beqyg%5#oj@rC8Q)$$vme@BrWM1<8yt8|W#Hb{gF+aokGTM2nF29R` zl83tPSyhf`mh|RgW8Jiq0N&Kj^uTIKdH9n`-{t0|Mj`tVv{LHgxXJ%0rFSVT*7U$p zK@DW16H5^Scoawi6fnDAH0A+o_)V*VxK3VPo|XI`Anz9#J66e?B^()NjO2u-3Qe*e|!soKhZ@mF9 z{B(bX9%CQ`gMqmwxzBS&N5^IGc~^>avm`Z_>|Lf%fmyA-O^N{rmT)zSY!V*M?u2wI;I*2xvftz;kUbjaTFq za*qd!$`g0w4l-VO@B)3SC?v%bUFiS3LE@(Ey}BI`)e<)$_h}NpUO2X8fkEEt&H;)!V5dYnWQ$|JtyBA43DuzOL0gQkNYU0H9#A{i9x>Z{7JGe8?DyWs!j26}$zKbO) zTW}S#%XUneNMKOLrN#Z*syXDnQKb3EjeAF%sBdGQ@ky{^ZZiA5$ls(s@%;LcTMxb( zs|v=Ri5Ze2^xr*aJ^R@1CR>bjZ1qVa?@Lke(Q8`1i%@4(Z45o+iOnrD@ffCcp+bUOGh&!@ z;Im`SWF6|Gao}7> zkniHC&br%TC6vjJRl;N0H9v~2kq+$VqGu9Wo{jJ&o{zDR`|__(d|%Kb=vr!-sLYy{2hV)Su4CrXRtd|->xIY zq#l3HF`2Eb00LM-$nU$%DC{U#L9u-_gXoIaFIZEPtTtfn2eTjhoA3x5+rs3 zcJKw%N8ZB91H0>+bzhL0PIfak{o4L0^xGs1$dNFN=khN$C#e6;8NjVwd^y@>=;fY& zZ8nLU=jD+@$lh<+ab}WX*-UwoI;v_eyhq_?Okbl;_R)D*c0w)F9(#FR7yj(|cN0n6 zym@h+LLW2K(b?0IG`>r~<;j=hOvj9dcwP?b548CY;txI65AfJx39)BT&m*N89O_v6csUTTc&t z%tp_sA!xDtpv>ZKi*-mkN`}#bZF3giS$byD!h3c8ZC=frE_xu8hW7j%qJ5)$xiIJ3 z>ilm3AB@V*3T4Y;qc{^=l!J06Xl-x)we{Xbs-BlcQY6vt_{-I@A&0Xw0xTL&9g7il z!C%`QuIFdqaZs6c2#8u=0hyrHwa`0BXQSk6AY%3V#kqhNqtWi!nBDvqc>BB1zY^)K zg{3?r674ov@ilK_>iu8Q@rV>7`_rl0isrEBk|KaM?1E(~#~p+r7j0Z{0JC=pEJ3d} zJf5alW%pwd%utvh5*fpfxV^3(p?ujO?lj8~@7@37n&ZD8`^2fwb#xW(WCV!B5bK$N z7cY{NlUK(TylI)%n|z1B4;2Wm7jdXes`8zfhm1bkPyM37o=#YIoh(s^w$3;YabNhU z+=`=%b>D=WyM{VV#1=o8nwq|VY$a~xw6<#Qcd!h3d3nDA-5ouU8QLc*r*+yliW*WE33?S?%{h7%7dYx>>svt!5X~X{v)T``4V2FI zb_aNBOdfa`S$4}*T0O1I+VOx2xkjK;t=TwS1)Y4iN$|*m#Qf_0*bv`TdZu};{RBu$ zqH1zb7AgMfuza#}`AMagyH&RF!At*${^L(oznlikd+#?iDhSO5gxyOsZq@ES8cD0b zLfzJ=$J%=8|8z2`l2jjaII(ry^sX>Tu`)3&7c+Do(KgH{?+D+erhtdMVKOF<37(U8 zjD63CO-x`JZ2UCgx3I}eeCxiEc4zcWXls%!xQ*<+m6`X6WuDIyjkUq%zWo87cNfJ( z6Wf^3QSl#Vb`BlSt4^kTnX_9g24e`D>PAZ+?9|=Xl#qD#{+`ZOCJCOphkG75KHt^2 zh{HDz8I{NX7K?(b`GXzyd6cvp8TlrI6yKy^5-V-u{QE#8_e1_Ok^#ux zi+#bzZ*$v2&hZw=R^n#-vbbC72)*>e8`UpID#za-WPTb(DkqO&IIfYA!~aXz+Kv9x zIppAZnB3cSJ9}V`^k8sv&mcu(zH&r!UD2SqI=uZR9KbIZ9egDg*jjSeYT`vE6x*-m4 zmx~>IR^KPqVHW67*a3owKK;+@Z~s8_W53qBZS}f%j)!OF2tY&{-3qXav@?=0PYHOo7u}u_ez8J>){!fY+1hQ8C+J3FWRN! zoUr#=-9CO~BeU-Adolg;Un}m9CjX~G2jP-Q#LW*MmK~t5?Ix9JZrXs8x_DxKP13ne zhbW_(s@|Qzk>E5G4tFdsZKIDwn;rWJD2v%3$%OP8d)muJdbeKHIS6wZY5z4>@IhxK zJru8nCK~vU(EvvS^Dj9>Ui!fida^O{8Bc4aYZdy&VdfsAok!+#q^F`2hfJnD!?G*3U+u4c7D!R6M4X2v`w-|EdLh~_s2LmAo~z_EJE9-E z6292D&ZXl$HuqR)SA4kfljtAhnwDkXy%@n{jVK+870A%*en%)|n&@Xs=lEg2>kC-Y z-cxzJ2WVXdw%sohK5JQVaBv)IruuuM1XhNH3884p$g;L3u@{?fP2US1kIHvs4m)X+IHkru-Z3PqI4H`;%m{7Dwo{bTT+nT}4b>0+B*x)#=}S5m zbvi_uW-e;ckiNin>D+sjOX<3Ht>~AvVJcUTzj92LDLpkqWd1fn3Bl|iqZ`!8R);sa>C;Nv~PHu$((g@uJ)Ub}Os$5Wi5%=Ps2INZm-JN3_-yvXv8 z$(&3aEGvH06g=6mYUnYOn@uf?{On7M&-|1=VMX#H#{;E|vWdDyeAy?9`070KdXF3c zD?=40ggRd5D!ZgrOXb2x)yd3U4I`z}io`75eoN_XkZNF;VyJ%0Qi`#0huo>g@rvM_uT}RMzaM_#$*h~;I)lKg z=l9AVM7)x2Q~J(v_@0S(LR|c)7h}VHY83wSb*7J}WAbZ|yAInDkJ%t6%~{!*6F7d3 z={)()aqTIizvj&))#9ECg+zzZQxk4N7dOoMdA;aoG{~0kL6|NavnxkneuZtJoz|8v zt~7)tzAlq{{>b!LbMuGE$+=@h1pXTEzju51g2A}itjqk%EZ-ioERTyuaZdKsFSYn( z8J8h@Z{8Gh!y^q5#LdOE{llHc1`=t|ul^l4ij+*vmvG15*?aU1>i;u0$MaEYs@J`7 z{>vY>;0e2t!!xHEn~)?&LnrL1D)}^WY{!3a0eJ<4KkKO1xXeo?JK+<`E$Ta7&{Mi@ zH%6LD|2IoNAmTblVe5ViL&;5PvTG3&w$03uWSB2!R>l~TuXZyfFQcR(F_Wo%RJcl8 zFZlQoUH6I?$4vHZ<|Lo{C?Lcp|A&6@d`$lECWTDO$=(nh!$RBr@mErFIg{i7J+XG?W;$;@P`o|j764q5!Wg~%dvSmGD>#?Jp(1W>+GHYa zvm%F;g1E!{{x9Dbb(%%#=Hzn~$`a=nRqz=?a+l|dho*66l(_uR*(^t^P-K`^Ki@7b zS|#4F2C2L~R;0ZLX>>qO1JOWwO%a!iSr+PEZdee$pInhGAJ?if-KQ;fj)kWat-A1t z{H?s8!>8lZ{8L1qkTn8 z_3!7(57(l(r(cLg#tu-55A2x9&B&Flr@hng@ZZ06_%P2`R5miT9AL~>?T5zXwN`-I zim-vR3x?p^qC>5Z2fxex-C5$x8z3$6qqkSQ+U(vy%ZcY2J5z?T0F9uEatM-W5ewiI z5V~iC!cuckyJAML5$d@T-1cbj#i&`rx6cYpSraXfY9FFjFOTPD;R|% zZf-M$89lbnZHfM`Wuiwi;B+MVUsoC;`OzMmH=gAo_o5ESMaL_bU8Jn9cvQ&u`*X9F zx?Z>^V@W&w%E(&#FZfPJOhJ9vXDRfOl=zvq@Ku6am8Mn!Xk4*}o%LtxWyEWoElmF> z!DHC*@!rtAMAvN)E8MqJTQfAa~&0xie!CJ{Tg-)GO0-qDeM;&H4iPV-<+xvb(%g}y&0y} zFTH8w0krP@)Adau7wT14Sm5W5G0RO~ZLqCWA!A|Eh$=AT*3fFR;gAFea#8}xY>Zt$ zS-}zXA%YRUT=7hz=UJd3I!*KxTFe=&NVnpJc}`arMf#pGVWA{2IzLhUJ}z&hOo-#b zt7~M3yw!~L#-M>v$wJ`4l63h)nt6H}{3X^38yY)bo}R49^*tR9)?W!#;h8BVIn1n_I?r=oOOs1|W_#t5w&X6H&B{3AU zTlZnf?lp6-b64pA69B&Mn7d1;f*((x();T<-Tc0`PJ6j13xP|>B0HVysY^Mo%2$g< zpu_J2wDl=;X5s$FLp?^L4^Y3bdEIOK_qi-AnFAT7$`P_Ms}FQX+HYr4RG9wG?C~K( z&ZoJ(IM8T%d`NN`E!7TiPXSmpL(ub*j6T136P>4MO&xjcr79aGAtvF{n4}1KJps)H zdE3qd%-C=e_=Bx@2|=iC zg6#sq9z7mS3mm4bp+T$eSs9%hd@eqN8^wdTx8c z1r%HgTY{jvuh-Uedy4kl#|rOloHA-}kG1->;T3i~G?B#>5JPZP^!Z9)J@` zd_hm}_j2t}B`t2I`!33TnvzxF+dfh|uLV$1vHG|pIv>{fcg}o*`}+8SnPd>O-H-38 zQTCLnGxA5NWfayoM0E5%MP{^?H|~)ytB^kcs69NXD>o=2yDF9R{t@QX`H(ZAp`8Ks?Nm$-WV7Q6VKLO*ua=GoD-w);93-oWwXpr~mRVkZrDByfa<5mwHrQ>S$0 zL{Li3Mk z09V>o4bl{jq1k$4tma$Xa@rY#x8MUm4}J1HiNKO12eBR_|Adn`w@x#fLdGN#bCS&B)n4IW}zz z)?EwCLPcXf0=at}AQ#q|z`qVPF9TLsIPY7I(A?s>z z&Vt@&kW#)%+3{riz7?T-C^4LK#<#Cs&iMLHBQYVEAPDeg1jRM zmd!bw3Gv#2)8@XfE|k=g1wI?JtDZVaPyc)` z>@wPSt4kLRvj`lyr{5-zX=#29fMNV46ikG3*wa7nULW#>QFZ};JO2CT{qfEc8^ei5 zBa$)1!3G{6?|5?8BC4ZNU$Wnx1uf(yG9Lo?oFrPBS-&Likg6LSBY^bMRdS#|v{ppjeU1?=Zf@y@l}Elb zt;iG=7cT;o7djNG6v*FUGFbXU76F&jw|NT=52|zS*Vq5aZ{PgL`uD=_hGp;DYTfKV zDACbZ0e<4lP<+!oJ_x*9P%GgU9Faxbm8_rdRt%LNW;S2RY&r1assE4D0YW+BhM9r7 z$TORwGKTd@c=b~EP4fGZ9Ji@L9D4FAc}%#7BhYFFB)WfRXJ=O5Ts9zo`NRX7AMo01 z3oe^Al}Gi;CA;ZO_ZTqy4{}KHC^Eo9D;Drf+%w&ZX%f|&+h>LXJUB@B9xb{DuX3wb z?_quhwh96c@j5*$6Fm~)6pk!hEwKg5{&(`&+ojwb9UUE<35ojI2lSnLqW=4MX%bBc z+%DV&Zslc+kB6?b@BpoIoTN7Xne^1A71-qhRq3I8Fh>Ro`5V`{2JhC{$W0qBl3Lkv zRKa!7rP+5Wm*e?B)B4#dD20s3JZI#R#d+>rQ|_j$3ES_)7xrchTj10u+rkm_UTQZV zBxCd84)4Bj1YTwB<{o6p;X1CR{Vv)`%%gfiq}1!z&x~enwllSO^QHw9}nmb;wXG9$LSzQC>x+AU+B%Z{iM1cL+CZl zD)3KXXZ!c&>-NoiW_xXnp2og2@+B|+ujoz$vyE*ih4zs{DD|bGA_)e-Mt0NGcs(5*L5l7>eW#9lw|a4E*G2s? zZdq4MX6a+!_$5_s9NO3T~B-^Sx93BLb`7#3I0`g_~J-279a+U6Tuv7 z?qpSB>$Rm^UMQI^g4XLm_67845w`EEm4Mwhs(7Z91f8RJI13vmLwU?vAL=qgTjVyoSEXVxCth#FemX@8lfo$OZ9=**V)D5Ol zN#})qE;ou##wW@=xL|Jd!!zfSMuAl(&>C=N|K!{fkqlNy@6>!w=Lj12Hd)3%tk$7O z*x!qJK`zUn$EL4e63>{IaY{R0ZE&CJhpKUAP0#)N_tPPCJ`noLrTvcL1-+0ab0h+r zYL+r{ahRA)%nYR<>@wDce%Bn{w=2c7sRgUW&(dS6UKrim#*xsjUA1b}4U0L`8L1`M z+al@X{~B@9V$ul@S9^rim2DSLzIY4p7n$C=u<6VtE{4ZQf1l7UQsJo|$jP@(;<<3Am7FkM?SZKl~M#60zzafM}l-e70tHNl-bThSKP zpCI0&hz<9Q4Sh10wQl1wf1gXV43eD>_NcHvcW}X!>`NHytq~fOF)QH;8`1V5Hj6Br zw#nW^AzMN6G+f!I-%Te1M>#kr_L$iIm-Z7_yf%OjR<6A|%|3Fpi83q9Wg!l6;6hN< z*q((q;wSlz1SCOiHW5?0Bo~nU<^eN7=ZUQ!?lY6)t*p6h(3yFYtmTHq#W;F)3ecv@ErQ6l8rw)Z4RKP3n}_pr zQPXN$$A;z=6zhVnRg}iJfBtw}9w9FHgMD2Xt;uCXcIh>Xv3I}P*HH}|?N#^BRIYD1 zb7MA(DRTdK7E^cQfl0~L@;z%Pd#n~NS?L8@SDav_UXC=H#EZnl03^bMn>Tw^BIfih zEhc7%J1UeN(q{=2A~aPYWxTxcs6x}MzC{9BP8kV>jeHASwRyk5YN@_|Yhg19mNRrG zz?E;wO13o+9t9vII-Bimx62?$8Y-$rNViy9(f`03k<+vH6jPU+sm8&h08(8?;tWdK zBKX9~h9a);?WpDD%ids8Hkf%h^Lq$Ux>w6u{y%>-jyP3ToZiTyBe(6<<@ZY>uFI$C zBpukmQv5DUWtHjsfVk2L+T6cz_QcLPltz)iwv6)1`_ZFEFJfYfr)0UOYKvNpxTnrG zjXicam+S6UIO5|oF!818n=F1oUnoViTV6fiAKuLn$!#jjMtuz3q4cLU%UaHmo8nr(5H6@mp5aD+ z;c!Cd+X#Wq=D0dNt`|s0XnCu*aRbHT%9W4lP1+GrTi}&JwXzE3PFsHtm3;O7H&jcl zk4zK1NeI+f+gQyGy9#B7$lz4gXr1Yo+S>GjAxOJl#KnD@njKcgw!7@`%L(mVzY@t2 zFU99h89OE8`ky}zKbEtM-O0{t*c)g!=+T_6GP`-fCB-Y3)fM<$ZeFaPO*y3(J}kPl zAP!rT60`(=Wb0@@6yL!V1W+=vsK+dM097TKQOry&@#?2eu^dX{XUN7JU&X8l8K2F6D}E+pIq2_KE-B_Q0M; zAggwCmtJyJSIyVzf>Vl|cZ&QeVxkU1AJff0KJ`wVs{NvPMEfD-YTO}@Cd$dpu1%C- z3;k*eRqG%{MirW}!jVx6h4#Z2r);Y)?jT;em6+Q?o6fQbZeq#B?dIZya;a^8g(=S} zoq85V%Iq`H+gLPv@z+mFO{a&XY#yhc@F4?|AeM!03lsG+#l*~NZx4mSKZvsGUOgDy z1r#ZpolffD``y_ePZuw+hBwcV8Lj&zF&Lm$^y0)oKqbw^{)}j>pmZ!9xK`3!pTXo) zsbiVFfdm!OFvv+rAkL~F*br%mfNk8cJdR+7e>X6Qn0Ha4 zIGoId!?ESsrs!!|WIB!H@Lh7r531ka%M0w|wh&=cDl!dj$(6XreM*TH{A5E;*M$~n zBf$0_5TASFL_g1=wA>l%#C^!DSZ)xDP*-K%BAS%O07p z=%Ff-AcRnCP-fS;*DosJ7Si_r_3ocrOf5iZ?dQdwlx($~-xr<7sf7j!p&~-tzc&+c zA0EAh9qC0odE$Q5cVv<_v_%jw)kjUrO@0Yz1&ZMZ?n?M4+;@Olh}iDuY7txpQ*|}) zI^#z)G=fGAiUBUzjyER+5f`?pM(gES7Q_c%aOP^(2zu_^z12%X5`-t6=Cr0O5CCne z>B8J2Y#d^(Cchq6)RSG`$6~nlQGR`onHVgv3&;t7`dK_2<=w#Mb?-6uZ4@3X)? z*k?Y@MA9ikG-P|K;~B)DvzOSrpDKCaDC`?l!(7H*<2 zP&L@Q*X*RqfDb+7_x^b1%$XbgYt}dq5*W`N8RLisxaEaT_Jsx|3k%G6sRsY@m z>2kJkrbS4lGZ~GO%Sp(L-;*J1RzE4o^8{#=6^=AE(HooSiUK} z!FrNXS7(2j;a+W5-vEKQ+OVm!;z7W4PwaOX^87@Tx)hw=HO<>P{dDYB@-xf1VBruYozF~mhiI6pBC=JI zr$Zr|9Qy{yY&vMZ)c*~pE^+(>K_h{p2$5j*VXLQ^v=D3(vI*82JqJBTT5&3A$gy6$ z;(2AyI5fBqG%eSAqCbo%qMN4g&Y<{X)T28I?7;;d1Q8+IYq#(6F80`g77R@da3zQ1 z+g4LfP!_&PaX&m->5*&S&NbAjw!NTZyPprUWklnv%Vh26O_61X=0QyZ!G{qSm1cAT zwcG?0nuSGYkprMuf^5+Rf-kLb+HO9u!#Bkv=Dpa8VK50iLl=b15rTOhd8bstJm=>dxhE8#k?N@nmb-%=^j`qlSs!ZAsaP( zlG_~B4)al#9)3JZS#1uP?pCPi)Agn7y=?>^x7MICQO#sd9$3K->`X+ZjRVor89Ebm z_KmfP!fV>bZ)FGxy??m1u8Z(O-(MhmhYA+tMa92-xhv=A4IyLcE`pXD;RIgEZ-a!1 z-l6^+e~H)rT&!QviGOVaT$y)MnPmIz!-n1Ej~nOuM#JR>*)F&WvBzzrZ_1Q}gkb?5 zG9K-ZGA)kmQQw=4jxgF)t|+D!pKz-$AF#;m-w68I@`*FaXJ9PT8ut!?2~GZSr*#Nt zD99k2lhQT#_xwR!tAY)BO@w$v29MBVX0%>N7Jky+DbesZfp@e3IjELNb%okw%yakD zrV?;e<(os2k-!CYk?!!oG|ho&?ty>-2)PA8=E)WWJZPe6gN}Yz(mLPWSn(=Wafk>| z4utJ=gT}Q8*<(|b8%d^$kXMU@{|*~;jXvS>+8H&lJok>9Oxr>3bWzU(<-fv~OGP&C_5-$;Tt{C;^xvN^F?N0h4RVLaHCcd3&#BBh!-|iBT)S z{tVZgLH{7$91uG|mm{yQ_92RzxXDIy5b;DcBtiT(io{CmWdSTS8zL+Keqw3sJU~D( zv`qf2Ll64!HU&=z$CtM`nIx@%8Dq_W*5o#SslozQ17NVIzbgdJU?A<4 zhVPQ#90)w-z~(yWjo5Nc?o7X>5$1!;3|&`r773o}6{3^R8S=BF2ZX>X!ooeUQwsp` z+z-s2!zFz5P#J)u^%6`(nbMP`=j3FU34A_-sQv2hO4}BH!anG5n6BD1h&1sF!T>^& zAVvU303;Qo>zXrBVo6?iU-+x@Z~sP}1#fGw0nK?Dy$e4(4xl2wjpUxL9fAfu``Mln1@&9b2MjUJD;1R9epGDsm$@tY9}Fy`;e%7tpO$S`M0+oUR&jY6$r%t zcvLIM%@Z1N@%QhKT5h&f$-7-~5)c@G(Fpns1NyRc)JLvK$QF_;N?_;G)8fa6J&&T< zDNz)Vwd;tzNi^L$DTBGwpK|kYqRpc?xuXZ;&nEF$;ONeD^djJGorz#3qA6ex`|L3R zY_KrH=q-#?&JaLnlIz4TQmE2~dA~)NH83IT`o+t}U(&g=yd??l4+r3m;K>jXikgNc&YS1Vxjg#wJ+m5qCqhTKb|j#^kJd-P zX6_(I6caZ83AmQFH@kQ5CTPwBNt+ARQ~faQVB;JVApNQqbxy|8%*O;8p@vH`F&pt} z5wJgQUPb@UPUeiaq8gq-*g--cQ@T~fiCyG__HdXn3)Bk@TFH9j~7}g`C&jDgjT5arRLP!%r zb7-5oX*PN+WSo#G4H38WH3GB;kzHL>#`;7(`)}KTb8GLLYX{4^r$mhkDbxxDL4HWQ6*V{MB|?op@*M%ALbyFp)k|B_2;*E zCWrjjLLJWo^j!PB4(l&VQxp}N8N{>0^F@78L~_;lXi82f>*t}&$8W#C_jHKaQxN~; z2@l~?9KnCK!NmrUH;p^6l+*SkUB}^2e&S%=ycS@fK?0GkO@ql8vFos(yoBgZr_D~a zWj4=PC_mV{HMP;cKD3|MmGQ69vKvSp269A!J(+#Uq1ALOhiD~Cw6ko!tv}yFd*#q| z%DT#g>u1D|-AWD>Teq&cyOo`9(N?xYTg(<38*6P`tZ<5hGw9$!jWry$pWs-K? z8Jc4bxmBK}+-U=2vTwdN)P*}oJUSjc=Xo?Y9H2}%kSr99pudh}*<7)_%Qu9Y6)>aUM=2gmn<@kEXNC457s80#-WMTDf^uU`_yM~s)xD=>j|OmY5^O;C z>f6OhNJb&}GZS&`s^gm)&MZt5aq<52{}H)!vtO5Nq#$?My>S6(RG!_+Nyj5#K@+islB&6dk8 z&oens-j5I(Bp%RA?$=*1+bN#AiH=i+hzlWk&*Yk#1@LVU3Mpw4O2iY!9De8$UBxX3 z3SRz3_Uz`ClZrANJ9jMSkbfpa*i*&oO;>w$T_f#g?ViumItOL8@P#R{@Q zf(tpzvhH2U-KzPVZY|_x1t`JZLheJpL{&7BUTHYC_9x-N&LURogDDh7aDBO%?i%Wi|z>sEAxdxqk}G?zDNDJh~{Kwj{lr5XCZUR+V%OS{6R z+=icW`;iE(SC=U0Al`G}d^(jxG!7(paGtZW6zXa9J2@oREf-RW?;ol%*j*a?r--lJ zcb}yRjDSc&)~}BVUD+xN26m0w%N|Ix%enY_2Ck+Rd-+tZb))sC-GBgV+t|X2WKp0s znKEa_DDpAIP=tEU3Y9ajh;ZK*u3dF|WOjKTne*G+rCImxkj!hg!(cY5M#OT=JcQLF zuw-Cuy>>ZKZ1rI}XFl2@C>fimBjzOWPX~qLDjR2r9@YKLV1dJA3hj36M~-du=p#d& zvS%NwzT;n^;O=zRyYoIN8g4G}&24OEWuZ&?N^!W9y9q&9jbNr_s{02%@CNkNOpGthknwpwMvRqgk!P*D|lXB;tS5ZU;X&4JLNi4(b_r+f}>#3PlFZ|je zK*t`+!!XH{Q@OM$M?}4CXg1=NWK=YIU?y#fj>Li1DI!&R1cjP(n?{4rLR3gQhs}l* z8@E0%^6wcFX8a0pxGG0Bu4-95W3c5!Kc~{m`mc3~qN9)Y?^L8`lhlFO<($-an;;RR zQ*T6#!sRhN@LRG;5_B5J?(z{6LR8xjvuq!2_MoA)Tj{qXTASP~Z(V);)6~?| znwkLEiBQgYop_|iu>HP~vC2D_C=0(`uKl`sW@7uZgy$l%$-Sd*R?xu$+fx*Nk%!8F z3#1_7lR00M1(LWGzm@IZwz&ur+2^h$6hX>DZJk$1Q3g{UgSCxqmZ_WWKiyA$pS%NO z4UzwUl5c171IkO<3S(3A`-@v1ee@YG{9f4_=rZ`AjlOT>w=X_VzDO>CwFu-EniTx- zvueG^{JhCBTG%eBW$GzoP%WvxxS3 zYNElgGso26SW(5j-e0%>$EN(~T)mOeiBa*D5B55rU0q3@LeWvz?53>GC8!I!Os`dw z8PRx&aP&-q?k0lS5QC3wnumv&e8QC0BCRxpdXd;bSVtMsJc4La7kJDCS`=! z78aqbl&z|{&Znja#aH{^c^_-TzMO6U=11qIQfN$40mY~2r3@`I0+d%bMn^|U@JrVa z;Ml}{`UqKeHwE%3B~Fdnv(_zJ$DdE=9U^*e?S2~I@3Z`R^!!vhtKTVD)S@a_BU+F< zJNxhft@xp&@}iaet3v9Mo6?eb)_D$!iFq>iM*NrjXP@wZbNrMtVi!mxk?Dl9Dr^^y#aOal=1LYB3sFo2tzXrj>thP9P<{->@_G22dYm~4(d zb415Q(c&HDx~d01CBh+pxYnf4i{m-{6;qEgJ-7tM4zOeaq@QiXvSz`6>vc4i{%vUx zpgK5~Q#vv`-6dCqn2LjVE8jgC0_SvI$vs|4pCc@WTH{Gr7M>?bQ8L7T`d3h{tGs{S zmryh5xo~^Yrlo^HZS?(O}|QRFHj8^{BTVAt8Otn6|F=9lrwANDv{ zyV-PqnqB*rWqaA;>uc{iM_hmISA6)-S_qDr_}vALxlQgUGAamS3YrHp)CNmBzvx*W zX+dEx(T2AojO3=Ot)3g5lUYYs$NBddDGrQ9)S9z z8%-JpGJ@TCd5+#sWCzA0V%I1!dB$| zMd;KpVB!Tx$GG744RSo_c8$E^ksfM{QR^qqJ`S2y*(YuKYc`Jf z>ie>DxyZ!1DXxt7_wo5Wl}jIl50Z;pL@Gevk&NX@N{XE?kA*^6t0nMq4yX1zLvPC5 z_V~-qjhW<5Eti*@b8F1KER{aeGwDN3JQ>e=cBvET2S%k4ag$&iUy=ryF8>$ zoXJti9ihXx9(HKri@w!LCu8sKXIeeg`L z=bL=G410ML%ru(>_+6`AI;nkbpK=ws-E5_yV>#E`t*_u=&}mI)w2>f zrzUCY(IFyHEns&4dHrPo-7ew{_Ofv#O|2gK>9G1lb_6sH(c2Q^eGBjR(Ntb=p9_1> za6Fq4gc<^s0~V$=EC4RQroE9*i6r<$xLE{hVzYX*YKhZL;C1u@aMH>T$GxQXj)!z9 z-R0YpJN@e{)S;#O=6*8*zelk?FXCgAQ&8q9A6=xCRi8MsfzD4wUd1xZ2SBl*w+mWesSAjp!8_;t?oR`#XqFE+Ddd=@r@BA>67JRFa#33zj=59{$@y3v(Zk{?t z;X19!vQ&jV@ITYg0>rv^D9h!`D9$(V2jRDo|EvNB8 z$5*1_{6odfUCZ+xD(45!+8+Vxf_#u=1Q{ zhB8&F4_!?ND#JCwL(c{lM9sSgfz^mfzFjd>^*Bsr&vBLi9KL@iGs6+>SH`R11moiY zhURzq?jXj4jAGCE*l+@L9lQIi*9pT38wRLaFxPJYri@hK7pl2kqI2|(&h-H@F ze(vCA^6f&1`4WlwjV^DcB*o;YVszr=xwIXHejN9s7377dW&#D<>S@0&z|k(c0suMteYtcF0_i*pX2IGB9>6Mk1`}1S%LaZMw5jevvWY9P$`s1cCZICX$y{$uXdKBBx z)ss9=6u+dtTI5Q~JcwUqDob%5`61B}q>hlwt6N*y-;3aDM)>~1@IU#+17j&Xh4)iU zyTG!OpU)(i{}|i+wD*ejZThnPuozBk=wX@b^SHC@EP8SmMIJhm!f0rR{Rk$M_X`pO zexlJQ_!J_#X#76XL7CbyKbHb$o=$3iaIw*&owz1HWLk?vYNlvqqPO=`Q=1?X$UN7WX{iT zlF;8rVCkw50ExPK552j=(-oE3^g`y6I1degV+*5GQ^kO|8013(w~3RJQ)YR3NU(Lt zqerbb*)6=-Ez-A=j1`EEH!0`}cNy3OZ|rx6SMexH5`b|jDkz|bQB51z7kc1CbQOdR zc&VSA(aXl-v3qKC6paTC(4T?Yj3vW=3bRjs9<9GzFEQxVGen#HKJj(R;u6{se0)0z z`PQJ!WsT{d|Hv5D)v`Dpqc6N+Pt4ZD2SwSn1TjF#(M8`KS#BF_wG#C?f&bhB74uwH zziV@LeCEUyc8)GQ2jQ5X$<7s#%_@Fw`~m)fiOzeg+}T4^C^xOk%Y!Ty{A>z5 zTCmDMa*G)#T2Oq(d5?CNORPBPZKMNg_mXOf)00F=i@BD5LucVV-_X ze3@U_$Lm6OJT)49b}DA{8!}mwzdGtvVw&Wfl=Z^zVs0puH|Oyq9*JA(lcr*XjydY$ zGPQAWW6Ab03;ngKPt&|}8w0fT^f(FlL5P^*NzyNbesw%aeJ)ZpC7$}aYsa#aD-pcX zoTmLQUFkoTVlY$wLwXzCnp?kJ)FNV!LX09pW)sA5qq;}tC;LguuBVwL(M)PU#s_ky zEIJJ4ZcAl;k-*<5Lu1!brrdnn7wZySAnuXLH{w3>{xdWAVN}EC6x~i@u1GCk8wt{} zD|h?k%{-j0zx+D|FM?EcJlbP2`fP^nh1=yO zioLvWP+pf2aY5*dR78r5NhK^%ZzJ}60t1zH^Sl6EjO8qXTxc|A@!|NaP)vSZu~k9R9VVgi&g3t$D_H} zGGPb3#*{ozepw9X>2HZMgKk6pXPdu1db(f!@h*cfH>UA_v^@gf(;YIwf#*|Ke80D7 z5n4;}d7sTl-l}++dZ^fb!B5#h#e!hwZ<0lf&8pkmoW>ON59u~_f45F`uPK=|4oF@W zhR&ChQ_cKh<9o(73s#%mnz64FTY8y#?Q26dSA4&cf`ar=UES9y?$O6dL)X_`P|%F} zMxXGLeF(VnZm{aJd4LddaqA~DN%;eSM9SH-YjGcr-TCBAJnz(zyA2&ozj{+d+1q@i z3~p`L*I^gR&E9$-d3tIl#QbJK*{r)gqMC*!bYu35L@7wKcHK4p^eP7}nf=P#25c5H zEFBrA)GM(&4NHT*ST*|&8fPDU!nAVR_c~8~KVM5XF|m}?F_-vC=0{H$ZK1Y3L+17& z7oqlc*u5HF9-hGBd;$X?>|3llN6jF4XrAcyeDZwf)CmvgH^I^;jR%~*_m2;#sC7L< z043~n%d~(@QDhK_aa2OYMl#$0GA#_Hzc4W-JEPZC7p$dUW+rAIs-r<-50@cj*A z5pAk^iV@n}eS**iq_az-EE1gmi!kLATty8(kE8O-VQ4AUkWLt2f-k7p|-o9=LzMxvmKRedDG^!~P0G>}>n_zXP zZ8jo@r?C|sf0KWF@_6VM!G&!_0Rhi~h0Gs?*f@9|BY#h><$QtetRn^j7Kw@99#oF- z2gH2paV8(g&+fpF?x~C(%Wwnl^4}l*$+(JghUunZbwksg%8^dxO<|Sv>NV;#fboU< zE`08`n<7b8o)Wncxjv-aT9&uB`*mtZDrGuJrm(}7UU{~KMwSzbrJCC2vJ6P5cb?>7 z{3A3kisJEI@-I`~$%b<_5=`SklIx7#b=QT)(8eBJVFCRjRc)gpP*dZTam# z3tYF@kaE@b66NqIQ}eQt=I$KzqeWu@^)lN{>7%!hq#Ia(bcMf?kU@j4U6tm47F>d{ zFzLJ@V7+@Llp<|?*3Old-q@BQ)Xy%exn~_&1Ju(Rz${nZ+E*sMZ_k@{M8=oBy~d8e zMes^w7KBY>QGc$yKHzBZ~)!W6aX2OfpiTDF$4vIQDI@j*bPkyr|v<6X20K2{BglTe&kkFpEfWUB9m|@bdQ`cJP~D&yoKQPoMvZ z%q2aeB8p1hd2g*muhvnVj^0X&eo5yeQyoS=h&aH`wamzO^amx zREykK-s`p(5-&^^W4n++yX}1{z}-=zB5fs{6X4ec z+vmg8mg^rbQ0RkoKNY!--vTo4)VD`5ZT(2hNpW5Q{x|c;vUIdE%0V$wp}*7sTk~Xf znju6wi&1dMxbmtol@i0)o_HrgN{vRwdOE@nM$6I}kAYM(vS+O6C zMea;|N;`;&B(W|j+a|pPl1jwt^U-yG1Ie~=YOwH8IAUmjNCEeT4HGg}Kn9j}*}2U< zmU=pv%=R*}eot?t#xW3=^X14t*WrxF{+;8a&!_lWkd%3Ofin~zzyTTbDtPYKAxIHG znJ#oz{&TOu#zp5>ofo(eZ@yzYMT_A;^3Fe{=w7%x_QuT=m?U%ZoU8=B7w>2?)kbYO z`So0V<;)#MmmtdZ0EAjS=F6{Ib~FvtiwP}cUUb7~{{GDT>v|G;9`g)=wG3I!e$HWaI7_C zzCxOMaC^wqTZeT2MLuVI8F7U?46~oy>`=fB|M{EAa~VTd5$eeyZ}B=cnzkZ7=5wnm z{X_XvFi-0|IjoO8=AHlc$z2HXo>bM{2XKFUuFm;it7wNZ^mukfL0pQ=jKK@W@7p^r(L3+0DBJb~TGOo|UZ4_9UlWw2meO^I z0`{6W<|BFvWmx^kvb@cCCzTO}t|~ESVM%(Pv~6UzO7p@s@*J{c{v>DH5_tN5s$q)K z{r&l7UA~wO(PWZDK%uVb6-&90eMTjUA&FTj#sFN%4NkU->`xh;&$D}b?$!VFG~dlJCiyOx;da4YQfYRcaeH%(tF^*fdiASWpEdpNr1X^uVynM zZaS0>YUpv<7zbJykgChe6!rPlx^nfyAYMR7H{VS(M>l_-cqGbDT;)Y#6Fr%oh@eT% z{+6S?DigAlMO|mn1}$CTyqHNblva;-E6Qz#wn+DNTH4rTIH_$Oa_|^)NP?`0`RW1k zTX0b;?kCgOIWaJ62+^HyYHE{Xkuo=e2VnjpNl_fB?|i7tf0yrDE2)$uQeb-LApg4e zDF4_%n;oQa6&vKp*GW5&sv)Fxi&d8~9zZ$ie0tR5+5#sRH=Eb5?b>Zil=%(Ms+g$O z&@K3KHKz1Mr1kcfFGEdAEz10rBVJxFUcB%!O?bl(Bvk8zm)ijV0N{*rVYK!x*cjEU3RrWG_pd(GH9EWcd*!;{2mDA%89`*EQkTt7=kXIC zXD!(%D{mw{ej^jzTUDh|_|PW0(^iFyRip$g!|geJZROKp_Mw_zeWYnV1XepvX4uM( zCIu9rR{PZv?>CizHnpi5sgnMMD6Ns&a!H7vc2_&{Xd75y1PB>8Ji;3-V8KQQz(~p^1O> zc)VAv{RJhf?ZsbKjlrXSfn(vf0~rxiD6+mLz;({I-|ZgV*NfpV{O@E~stZ@czn9 z8%`KE{16`ekS9q=!lYBhZvM`r3Iri+e@?SM0C6qx_B|shP*I=yW5!w*9+P6KU3p&M zmf7+=Em!CJ$wK5tL63b7Ep53zQ5iA29+V3U%bn?tjW5I2*~tBVShil|T<+&EDRDZc z^W|wnD4!C+s&3qxPliv5RE&C%Em>RM5dLEZ4A$eSJ-GkF1A0-H7vlY~g`;4`#~5q}nI`Y-*nlloY$`5=d@M{LH{ zWf0{xDm6FooGv8|1l@8*LE)}GPpABF8)`*RD)$T8iW_%QDblXTH0KbC0#&AT1!<^a zWPEZN>;l@zJ)_20w^0|a_Cn$hW%a-QZBXcPxA4&i1AkmMFkG^Ceg4hPQH?=v*=HhZ^gx_y7>zeL z6MwF%%M{G>Z>+3{5;@?@fcH};zs;{AN3|m# z!z1>$bB1-M!jKYU8@@3p~=jUWc`cdw?A?`r!S)8-u5QT0LkEoW7DtpS#Z_J$SAQs zZS>EOjr+o4O5LK|%({HVJYZjf(=L)ox+j`2Y=2N9*&;LM@r$N_pRPQAcUl_~{lxhw z0z=Sb@NqVgCGWOkaMREs)sJY}^nQK_kcCkJdJIq0;XLxCdzEI*W+m_DHkjC>9hjg3 z-T&hTID(@1SsZ2i=DgdiWiQRVA{x_nUF>B9iSiStv0z|S2Y#oJ0u$^XKcWz?S+^wi%8rX{fxt!>ZFe7~KM!>PxlD=159kmRYpR^c5sJmFX z+5 z5p5y-H@~#6(LzxNo!3a!;ED}&Isv~f(%ASkYBVWqzn-RK^IkM1nEJ|?*w5b>dGlp# zPZostjZgTXm;$XZ-Z<#a`sw~|LF25KdhQb)(86=Dc!Zh37$WfB8O7hGNTEo)7^7ZR(LFw;N z{&!ax;tnFv@*3~G*n?{44Wtpsf5zaM@##{^Ksn`R=-IRwQ7#ud73nN9JM!OME}2ON zy_%ZFt$hK?e!l(@cb@)3UPnGAcBd^xHl1X~Lny7-j*Xq^lgsjD!U8E$EURdo%v6%)MH4ciL2Y z1JR0O;MS972^yGiksoJdp#CMD@J1etXTHJsT2j`{Tgaf)pqXZziIQAd+psa3W_@b9 zr=vX;p@~-I1w?X7W1SSVi&41D({K%I4dtmKwJoY$Lo_U zf1Yvr$j8;+J8QxzgM(jyLnU(Q->DRh+o}7Go`MXQetW-mI1$3cBxr`f8U8W@J4Bpv zEo2XEuxz_DKJS4*oL&#GO==Js7;;4k_OCoOV{mM+iM6S8 z;t?Ydr?_G397H}%n)!`5Z?7)pF;~bZA}MlW0EgYzQ$wKPSKEH>?(X(NFXjV4uYgQ>Xo|rdA0O{jGD=`_(zOe$=$)ny5YJ2+BPPgYQDR#SN|Ofhq}M zH<^g3d-F(fq;3=kF~HiF`nx~;KV$sYy?ghpDpkZuz4->T&a+J1*5b8$MLOEA`H@^9 z;Z5fwFE2LHD;j-xToOzpy`%>nue=BpU;g;85z$@4DnR&4%o)3wnHQ;rYC;n^MmiCsPyEH%OH zrK4!2kf>dVqK4GiW~4{`r)X(v z?*3A>(SRM!j&#Hvs!DVhwalGwC`GltV@3@fc=RJ4%dQN@lAGjXmSSdYu?p0;yUG789R-c87+9%TH*Xcy1^n3!+30x)AkTO043J@tKvJ2lkWx(PX2M3O8Xi0jx#w&(qkCv@`S1TDYTM zrFq0-YnW>gx(~%N0y(Per7QPi0CS3wGHU#1T}En3T3Qid*GWPExgBYTNmQ=Tp%|h| zAJMq7iJ6`K|LFP(u&BD{;kzIP1}dpYC<-Q^bYme(sid@`g3xg3q2GO9<-~UNTjh<}b4=|wca%2@ zSdL^0Sw>cv`*@e@<7V8q&t4yr9?HWl!z{?*!HExBFQ23r-dmltwj=u483OzY`#9Hq znM@F=kWVMINbJv&>SXGW;cfD;f$5b|?v?eG?>h_%OZnVS_Ak%BQS#&M1S%g*Kd)AI z$F``j?Ri0da8GGS>-j_9(H1*KPJzViy|R@+?^=5 z=Knjoo69J!nD2y_>9yR+4 zA9Y4Ar(r+5ecPQMm5@*D$#gSs6TP+>5C4eYyP8Iux9^!aNXB{MSfzZpgo+aLn!sO^Z+Rr9NxrAg!i}Au95p1}M9`X*uu|3&|7cmrc^+4rnXt>NH^lR`D z7w=U})V6tq;!zH1;nj?zz<4?{Vn6gAsdJhz6 zgKgn6DG2IaAshhrA8iq1r(gM{>F7?_w1v_iZ1XGkMAsHm-p4oj7HgNP9&(4yQ*29L zK*oOfJ$$5em0OT^bR5rqea5(S4oABzPW(Przz@F?)}sZF?*@82*M5-)cXU$B7vpo6 z!gaqNckmHeZdy`+UdzGv5DSgnpjt`TZp@~$TAYodh>(HgA^EA`*e*ivMv+{!op26q z-;5hLv0;A!ZVB2W zIU;6wd~)4$3549+9QgP|wS)ki1fHxrjGB<(FNmW1GoMXj$Tw2+PzG$G4@qe(wwXi_*i0eaN!$1N0RtjCqG}=r_N=W^OQaXeY&xBEDhe zG8`{j6NLB#bGzMqn>yog{e{TuHL&y0G+J;2>N@j_d_tvrX0~l_x}KY<62%v>hNdV^ zk0HciuXl9jgnn%5Owr-6$f~`tE4(8$Ru%pNI1nbMkp<(UlRPtx>3FH~_oqR?rPrOP z-!9$}B+!Aa;3K80x)T{Km#dNgDedl+TyG6 zX3E#4bLkRSD9R&4ZT@G~MWh~Y+r}I@`Pnz_X3c3;!F|NG4Zpj-+3M~1_)yOGdx!E) zM1J%=!$fu;Pl)6bbngnkx{|(fNy&UO$)kAM~FD%{G*T5YyMbpuH!kM{rns#=zv+! zs|Jkz!P23f9Or)TSjw_VfAR$Sw^hcCw*JXfa1G9f&^~t#6B$f z&!)R?FxZ_E6;Q^ES&9HZAye7Y^meByvLxuJGny|H_RHIMvBz7$3d3!gjnQKersvhB z2T8NxH~+R`d>Vssxf|)P^L!o8<;u4k5Z(VC_Ve0~zBAY}&DKbSu+FCWV>&7|NO+eT zikZs0w2*$?-}!wreuM#gd8^h?@x9@b)Xn+iA3PrB4@5N1BfDY`yw->WUev)S6*x2| z!MP&D@6UX_gz+2|^LcZ?~= zn(hN2a{0fB=uyvxjtv0b?_SFi2rZU_2tWC!C3Tu@4h^epMo^93P9%b-o-6ex;&an? zZO3kkz*PL%vYb2%Fu+3~0lUWe`eqwMk1TYL7rgVI2w{9Gi)jhv#pG+y3sV{G!ri<8 z${JDqL3A^odCBS%oK?7GGIAYx((oJ?bSRF+_5^H&Wn10GraNEneo;AxUX`BGQl zl?sa^HBztDxbQtS1qRMPv=uyf>zYpNjtS>~fU=UxyXjmgJBEu2Kg9CvA=Ae#oZubJ*ycX{J~wqmRj*kJlA`ewnlI=9c`3zMfmcIWE~{dU=dj!MHz3JPx^ zI*96)5iX4el8j{{i-}8f`j67+i$5vmqf`Gfe)(eZ2|<6I8U`%6_nttJA6sdO%TCxQ z)})eFnhZZ@G~JBvxd1eV3f#=guc+dzcxF`+Dz?p>A+g`OG3Ih);`ODIaa&aBU^nCc z0QOA@IZaPiplZJCJVuo?tWt%@YEt0UFHEzB+!MPO*N-3l{r5~#qJHR??DW^Nh-}Ip z%6uIEVYmWUKL2JbJ(nM!goN&D3IklG{(LSyMZPZi(lU$;dJW7G14)@hzY{!7A$t&6 z2W6^me2EtK54Jc01u8TKBRO>-YN}ckR>y=3dBaZ&j$iU*&WD2GtPk$9+nht5pVS!L zp^|@H=QMRO?`U_&LdE5c=5uaq`V-BIZce=76#v;k>h62oaFfE(rPXLDCe)r`JSO+s zQE#1n&rGx#gy+WzX;m(bErHH}*&=689oPCDV&j)uF|3lGrT2(KkX=TY6;2PIp0jb~ zXeJe6Pm*YRfAcI0>#(DBG*QiFmD{@TS2~2)Cq2EM?2_|EqX5m60O~Z%s^n z#oZ7Mlg18s*SP_OD&1}3?h}4=ABTq1l0}|ef!|;CU8J%oJ&pzS%n12JV?nmA>6d>0 zx!i9rFB%Lnl|&IG_M9LKxmK#vkMl&%SL;pO&E27n(uwd z-%G4lX4m#E0y+?rhLmjg4Tw2}UuTq7ab~Ls+qRBJm@jK&r&@j%z{lA`TS~45#50=S ziqcnULzbAv^Mf)^?a&;dz{X>yW_B9#ko~d z!6W-w7$-t(75L@Hn?g<{NjjNM44cU8P4k>fF{?lCI%&xt9u1V#c%0bIvP6kz1?s;~ z2U4!8S|#RN-C=+5;nnpi`9Y{0GG?=t1~pfT?#XmTq~>)cnHPDvdW_mh>2S+R7(4yB zE4ffPuW6hfMR zm$GtakKOQC?wCdLOwVR~Z%olJoCbE(0aOyCKEFA<&&{Gv$B*iTJSMEBgY|ARAx`QZHyzI$=O2SGWy|GTPVRhwAx)7dxW<}J0T zER2C>;K#tOVN*h`?o0NEfP2Po1(y=FxVlrRaLoiM)R%P^rW}zKhII7=MwpmZuS_~v zM?u*%jV>n~eYb^=K3-p=ZN(%qjip(bxE4~=2T&$deXh#vHXK=TE_bzW)x@m_u{#a} zsQhk2p+ZZm$SaFvB)%e!5ebp~zc9n!XY|$BAzbG+8RQn%|DSL{@d0c#!S~U=KZCTg za0c)R1*Vs^YDZ2ZIluq`|L_m8RQDtC?fyWqI(KN_Sr_>Azwlx`G5+++QJs{cNb>ld zQMl%<`c;&5Wx})bcWcgv^2-6 zg*&~pTtdMfM5l&Syr!Idf$r9oHxt5nGG#H15%L&LYF02%sRLamJU)^ zAWoy%&eUw(G+`oPmFHA>SEnc|U$n~8A0_@=hXh23r#@UAOTO|izdY947jSt0bS~$?`8^m_9r&dZG(RdEr z8x?^pGn_E;_^{r4-nPZIIrM@E1mlc#d_so--gtRHaxAC0G|TMktKIDo`uqoQGD ze?Hx)arjyYZ%>{+eQF#S%o!USOGyL(5>=o2(*78f>ET0@zQIcm-$QAS+KH|0WfteC zy}PBJ-+Fg%d-WQuIg{%<3Sr7QAG}kTeeHL!$y!fP$$SEDWZYxwuHy3{h#Vl8my_W5*(ZvNoK7I=My7wIr=sXoJ^A zdACOfXE^9D1Gf&eL=kkd$&e#~v?XZa4gzTo$0K51KKuu@(}MXr8dsCrBYZ*mdza00$>k8fr+O%za9+aG?SdX4b(tEU-& z4Sw{QzKQ<50Ei*s%>XAZzYW^98)R9%nrzvp68s(B)k(CufI`+;M?fafu151n|FSTN zB2aj&OcJ=i%%(KXty3TzhXpCiuXs?$xOIYFn0WmvIBzeTcBAGzw0Gl0$6?BJkXf{S z5@f*J4$G9mT$nH%rEeGK&Yix!ze9?EhXxu9lxmO-v*GP(2Oi-1##7L-xkg>)NE`Sy zi)cJ6@cNlLV<3y8%HC&FuH=1j(&@Q_?;s z_e#NZ<{+L{5IV5Q2`$Myg%Qo*s+=9fb@smKGX{B>jvhPqp?!+F34%-*u>%r(-9Q6z z@NuF*j0g@%zcNomZxwQH{M`lbr(udAdyr)8=V)sldigO2BJm2i(}nUuhQUCk*rNjz zot>Squ0ab=GHY3EC{nn{mdxh=1h01OMw|>(7P?ScZE(Mv)FfVMN&T*4oX$*fr0N$P*VA>rPfk<6V0SN~bP6EK_P#2N4DGuC4tK^Q1Z&1ZJ?>ea8^e0+Qv;12|l zYo~42n2IpRK%gw!T$R0yxcuRBf`3%>-aqSxV3Rz?@A1GO08N5KG)M^~0BU12Ool^8 zhYR~Zk%yXqi;JZEbTm_@tT_m!xRBn^+=fa9(1oeD|C4?0I@DupKRZxm=m%lU*Y9rV zZyFAg7rYvo1DiC4!F~DQTC3c#0%malo1k?v97fXC$f3#;5Sv0}*V6^CCa&N>FH7iAjuE5UNW6gE zTo?hLPm{UN4L>R?E8iA55C7Q)_~0)O)T9hLTsSEL6c2Z@ z^S62+QxyV?7Ly-0lvh*rmkk(GEM^)c8++e7AyO_G%ePn#ZtUUJT5z8#t2))b9p%je zjK31S-UAtDoJajt$P)rd4HZ~e`0>8V{UCS(`v*sQPMEsc~XnmwYrcwcv z4vKClbZ@A4x&1EK4IZm}YS6{Lg-pkk8{BmM$#pRQ?GPZp&>t}34JbQH)(c#%I$7CL zf#Rlu5iYo0RAHbXa`a^*6|^9H4!jQU@`H;^reoNDfPzLcS!8fYS`u8u1A2v#EYevD z)IJ&y+-EeM>?IY=eaiF-plB170zee6g$X{|CkY^WPWm$$T#?2Y+7N%g2cb$%j>|TF zw^*pd*!tJ+v`$r+45B|qv5`l~K~nn*Jg9HFF6|R?J$q(ODC9S+K?fix#z!656KIZ7 zB08xF#(7uUp14%qeMLQI1w{bpVO>E*Dg$l>kY!R@{#$jNiUBt}E$owX{xnircoyc2=BGQbK)Y3BU~oi14%CqfQt_9gw8Iax={J4~q&o-m3`f zYbx}Vt(xa^pHu&h6Il3GUe&`|8`s(l-i;W>i&nmdMGHW&5XC~Z*>-y*o(UaTn;^00 z3bQ-*c{Fqnh%|PNS^q>TAx3n$xZOBheS$3n@HI$=OLQCNq4&IgH*VUx+$~lSv3(0XH z7q9GbRA-+)kS&B+s~mfD#`eRxxQj)7pij4gwuu!-!GSnn;Dq$X!TTot&YIa~5dYZ) zw5zchj#nVQJHbuv>!%M2BZZmzsof5$nP=iI4iJ_vS{x(kOx=>|mGv)iT{z%Yhe{ga zS%hOjIaS9GCa`NT3o--Y*qRYF{)kgwG45?MM0qkhjvQW> zdnf9_q=np`pUkOJrscz-GP;|ETl=QgVr|A<>4R*4#E@}}!mU8R-V{W9MR7dJ7?vWV|g-0EM1C}BMHnOT(8&jug<3M9R@LBzz8eO z_IY<`IPwWt<~fhqxO$X_OL0X~cOrI{)lClBE3DH@&Ke{iHJn{f!FXg#0l;|gEvdg{ zmc-Ogt?Lnu%p#D*NLqgRh|=0%HS0zf53)bwZ9KC?^~3@~#-T2PFPmVF}qQt_L%BsO?%l1g@Ko|CTOZK8%|Dwm+U2jv)HGHObGqJn+ykTcwkN%P9repz|5VB z?Vwb)c7@HJod(YGJ2RC&_s`p1qFQxvP&`!vr^?z%0xUX^HP@7BX}}$MQyi`sJd-I& zbfJQaoj*sCmTj>MuVg|I`u-;(z-4jpS0T{nA46B;UMbCG*E&V=ejpAP8rmlG zWj~mi49yv^_t#r~#C8Tbv#F zZG{8ge{#TEDImCSseEin{rVzxQkCAXfzJMZtSwWlZ7Ng740zyWrF{fGB z^n(-MS#8~~m4;m?Hl=i04yorn(2)Z{h!w6^3MQHC1}Ttj+|yw#Zx|w#+bae0VKpyO z*IwDqg4CQv?~X)tEQfafW-Iqi#|;rAz2?6@q4>}DZvxUx5Y{UN_V8db%uW4j*s1C? z`{}r2^VxNy;D}4=U?N4O%FXueg!LCeSVUf`Cv|{+24ETsl;Lh`oE7u3>nyha+DX0r zARn3o9@o<5AeH3A9VQRnG;n4wx~4Llc#pLeOn?NgQqUd|+~*0> zy9b{5BJ_X??6pRk4C9|ZIOns$J23E%RbzO^VsC{x)61^jhoyeduzvWp4A8d~TC?&} zXP_k^R7$JFf^th!z8yf!4xR=*h(jiU*3DUJZsq3kQ?LGjy=MrjkQ@~i{bbVM2^7OF zm?i>xeD=EHW(;tw=5L&IVqUEfV&TxM;ugD#ECOL})ITADD{?ygV#Zc)my$^We&EoR zoEER~+hZ;TsWXSzDy-d662;m8RrXdVP{VC^n7;Xio}384RC1;4wb)~GDVPEtq=Zq= zPt*Mi%3PQb2X(t8yt*Y~8oN@0ano@^KfsPe^B_xrZ0i>esxA3t8|B^p0Zk1cyMiCc z%A3{V4(i;)v@^M>^VF&SVrIqHeCZ?inoqD>N~pOSgWL8xONk3=axA`^eqx4s)25cUJ9-|JCez3mNE8{8X!U@XKwmxo11*L{`F(3#Q<`$W# z3iJ|%xrl@NtXp!9!ZI{2Up5+VO?Y!#ALfLEcB4d{6f`ri&t^`TDD5Z+2JDT9yLf;! zIz|%Q0?HMmmc{hT^x7Nw#ESe_GDq-*wOz;+0#wXWeX* zHxqE%F`nsSur@+@TT~ceVDXO?7C$QZ!SlRWgP}-oZgaM6pshzYXVTn37Diaj%cXV5 zIAj4O20*aW#=CFOh2EJ<;uMc(bR+i$iWiN&anZ{+ZF{1%7!Z)agj6K5bgKZ{{lT~^ zgO(_XJBG=;Mryv3@85!DZURO@m5nawEtwDM4-EG&TTiBW81VP3!5y!A_UO6Htg0u3 z3BHQAZ8FyMv*>);O)Vx7qk5a71s<+*)RL$HvMP2v1s zmxjEym-8zJ_QDg1$X{J?`9gu4{?kXt+_qfbVK1iBFy=wcR zE`6i_D<~%kBLdJ`@wW=DWN?hRR=8gQ^;uyq4f9)Q5FS|GWCA#R$o`7pO3lplx_X$n z;Moo8!{eO0K5!g#KZQz~Ujoh&nD`{V0LeWzxxK+Kd005G?p+WJVKzY{tTqbf@Iw0= z(APp>fHqes3xzjejSuWc{(2{ggOiP|08d0b#ziUah1W^=EtXp)VwSG|4)Cj-al2m% z69swB_!mL{WBC6J_qkDc-0ubjbp0Wl%K#4ae=;p~fkrI=v{V?h2I5ILAUgti?~b8X zMo_6e=3>(HLLg;$priChw)@m<$aHfj`*2#z3LVu^e#sWR2z)507rm+yKa8oY8Z_GEBhF}CeCK9tf%lg(abw=apTHf0 z>VW4;a~GdpZyishh3+i`eu#oskfeYWQoIih6OebF=8Tz;`ZYsd0#i^pH(lh zogaJVCyB>>Zl^=B(I4j}g^;OX!NOFodmtR)&QHHDrst!#9&oCT54y`D@%XiFTvBba z@>AdHw`wo9A2?U75_2%s?E-66&uPBh`)=%e{YW|f?D>mP7h=!jO_}e0`SM3_i}>$_ ztl6pX-09QJ(;0H+&SVj?lzDk+-&A>*l!KD{-#U}2Ufl;cvSs83^GGRQQrh#BJqse} zOf~l`ABlmmy0#W8bzM#v2{1xP584-Rxr}r6xqCJoz@Sb$@B7x^msh8_-P)?N*!Ysf zH?Q_T8s1$hfperZ&2@C9uz@LV!zyysL7!1$X$K) zI%Dr;vU6Mg4BkYtt6PIdr_(~w&V%?;z}=e-?Ua#b^n}ti!bMtT?-@EmJzV7MtO=>v zhI0K=upN@ezq+Dl7HUX^zL*^*=dp`oKr#t4p8V^p$x?mDEJ+r&#j~uZndz$yrU6nr zb4oawA2D4*NL9|^8?p`EFO5~8w4i!t^>#-&W-~vw&#Ir!t~8-R4mY%pv~=jJ`uP?0vAE&mm|oC>;e_ckvFLPGnZPk#lv2~?jlm{Qv!ypJCh zK9{R?emPfh%3~?<46f}B{%M(a{k z!n6S)qP_qR8aiP+?7Usq%3Ygd$(4}yjyRnu&4?Xr&ot?S<(3&7U!3G&&{ zaY<${qr}~?md-9Pvr~Jw9(q{*dvX<9jwRDCc8NG*a{LK|3+c$8Av^dg-a~R?WeYre zbjjr!SxYXarTfZ4r`JZj@k11nf4{AcRauM(7o`qG-vgh#ND0e836alBV+EE+|G| zv$GsXM7DfNe$fwEo}m&-Sj2lPby*Y#;Crn4C1Fe{S;7$`c?FSt=kC#vJf4rfJ++&b zrpy>MX4UI986Y-$A_C3c7aeq;*go$z{kZQd zb4A)ZBfjexNpVDQ@-R#874#e%8hEQg0?rtHR5h*CcT_ol5O^KGnP=(Vx^ES�Os* zd|l&Fo!-B)(f2DU)r z%aT^mjR;LnEb^$Zk$twFV7`E)59J^PMGBBhpJ=WE`8l!u+F~|Ofx^Jdp0(Imdee<~ z*cHA-a%L6fH~4gnU!^&<-mj2fI@RQ-B)fA+dQ?jP@Xt1p4(I5L6|D&YTtT7k2OLE_WuurjtzXg za66j&GA5@0Uo(+sLU1EwYRK0vHXWjZzLW;^(%0mav<(=>55GI3hZI(RoEVC9y;_;6 z8>dTQ1FrvoYk>t{dP3|got?uSgrI3c{2OJ-qxXO38l=jpid1}&+=y>&co!xv>p0tZ zyrFREloXZOYVuLufm82r9o$$p!=IJ*Fnu#_f>n244r-dif?C1owufzstvFn-RcLL9 zX<@%9F1zc@hQgsE*@hwnii-NLFltO2!x~*`7*H8ivv(02&ug2S4f~doR$x^r2D?Jy zl~%bCeo9MifuTd~)tDQeZv53y+WIl?IqL!iRAmv??oG2rUx6Q?@rOeZ6yT+FmeK zM{kQ>5u1LVG-_WNKv?Y+rsGGl+o@dkj|UEneiZlkHlX><2337cyJ$ARv5}vp&pkgt z{5A?RwVGpGv=eI}ZDC!RS3&k>Z}4xi61s7pctWBEV(2!5-aLm&Bt$KbsCX=FkH)MD zz~*?oQ@;}{55mJ@>`7s@Wk3m~K9vWCj$+=C-#koKC##5aO1H~rOq`?c^Ki}c%gv%R z+1wy;WG2;feYwCzHoDf?i0<#dYOCeK$nVZu7e#AcW=QD)9`Mtf;Eg0L-}Df|hasOR5r<<>hb9US{1 z%E{Of%iX@rNn~izk_zN#|Hl&dqhV<|X$yxD_y52hP-VuiX!9LLK(>$oW6tuATYX!; zp?s}0j79`r*X$|w+F=G)XZL+AzTO+9lYMsESAjkFF(Vmbm%B3rkZJ6%6)t`l`5 z!82#EukJZ9v-cYNs-3l;rn4K!q`;FDet#97pHeq>NO7P8TD?oj8PjL|>Ij!^N?L=5 zKjEV&K#%{eEipjfp=Rwe+%%p%-h^sB!rtmDiGZS5;~pNIiPnYZSyh% zXP}+^F(hA=JoV*c=a2>$KW;SsLZ=feJ7>rP0hEb^;%Fse=^0BpmvmxR5%+rX(x}4D zzAml`rPfcKd~A`UEni{MeG2L zw)y4*ffOQ_S;o-u?G9$V+1N=fCJ&Mz5-PabB`Ph(Vw1VqdX1CC@7sxXafmk4<_Lo=7)09a4WQOZt6f19`1 zjEuzrCY-($9CFG#-g@x}LXHy=+Dz_T*S=lnK^dw(n(heqSwa4rW6XFzFiwu`6L&4Z zsuUIiM7m61Z>AT*AFVVi=0MssoC1-Y;cY$Q)|^{Xq!%34#p$-9!(OvLxVqCypt8~b z5%D>v;`hI0QpW7K zLetwD(AycV9SFNC+vK|<=4v0~jd+1IcsL*YS4r08&|^d|$LZ<|1GY>3HDq+D+#B%^ z{&S^nED_c%L5G>Q<$;{Cm(m~f1GMVZU5J$0KWSXC2klq>A7KS7x9RhevMMpds%g*)de+~(z)=|sTsb=JGgKJk+6QW1?uvI4~7PiwJr7wf(g?NatIxkf6sP?UT8KKo;_~;wp`88Mr5}y&xNtVvvCJD$W!pZQc8-G|$4k6? zjSxY)b*d~0cPs?DPR-UPj-y;k%Tp8KynU42lKUUL^%jT zWRd0=>{tRRq7_g?itI+uwJ{3BI)_ds++kAU&bd;~s%nbO89VQCGqq9)K4&A#>DIfABAwepCTd6#|N{-Ba`EBE(K; znQs0?MggM+!?=9%AphXlZ`qCW!HlL<>%b`*+^QSwbh$=1_=}HJI&QiuRfSuw%-Nd5ym&JRxDDE#IMO~VAJ`S~UXY{cri7QXE3CXN*zF?6~qwlD_=Lsb1K zP=o(hju*q^hs3aB0e1Q3aP1C7n>%d_i7&goP}z(>^^*1&@cI}%-tU5#T5WrXt9a9t z{fvrEXTqqPXUZ^ik4tQ*3dBD^OiuC)Ts^A*#*ni5(_2T zIoc*Z4?QzR1*oYBjXtaHqZbl8$czXqk(^t-JPD0s-uGruhKMDnv`~~3I16OzGRB2m ztHw#pV|C@8JT=7(v}((5z|f)g+7I2xrS~Z;4K_BtM-ZzQ-;bRuyVvf*zaVn$=>siJ ze7o!4YiH9?sudQX>?7D1oV8yUK7X7XCcac%#Is((eU3dw!Qk(uNO_N`OxOT%;ig%e zDp;HC(jV_a0gwKg!0836OFg?av>t&2Z83VVME-s+K7hUkJ}Qd^hdf$|x#=?j-X{qP zDFsOpf%mE{QNLtFsHbN|SejlY&5X4u^iP4Qo}$M`m&W}?`w-f@da9AWmc*#R-<#A| z-|1)KeX~-mM0TTVOrP1Z=6E_hoQ4gJfHRBVeD|5iol7#QzOrvizA-VTXP}_U4|=Y- zJi{n(mUeZ!ZNyagGqu6!=`iMig9ds8!f&KO(^beJ2M4eJv2~0o{q|}oeZ8x=Y)jdP zt&9}N;QeThw(1)e)cGwekfn%h+_856E(qA_C;uKtA@8#7e_%P8jKPdYx;OTA78Ne4 zuHU_PgR?G0r$nS_W}xnKsV`}aZrsFc2}X|7faWpGcOHV-IJ!rlcnXW1!YdOvJ8wSPcx!2MUg!rVHvE7+1w8ji0uO@ zVFZ(;enu?wVZ`~t5A<6aNNs-mYD#NnJvI;YGcuYy{vZ7u1DboWN){5%yG>#L@MJMLz1*F?WQ8ww1n*#wTb_Zq}q{9}^p1;@jPfQ7T}1KmI9R6a|} ztqQls>u(agHsZN3c6SAOqW)`5$5JsJ#VJDs9&|-4T}GFWqTSG$qCdcg={=S^0yQ;2 z!RdG5m|Vm3>%Z5u7MqX`M9|dX`yOu@IESJ(zCMWa6r025_?GO)jc zAT07X=ZFmr#$J^}@}%OqHg5G7r>W-U(l@J{qW>!55;4dx2uwb7<66bnTq_wOAS1^A|6GlLYo^; zCr@x{L^9$C_iQ(ihZozne()orRENL&gV-*(f@Hrcfy$*n>^vK_YkcnQVahI8^0iyo zw~nu6$H}*b2+7+<*7M-fWIJhN=fJmvOH~aKo0z<(mZm_+w#K`!BNE0t(r}Y+DH5+^ zJIxloDnFjF?&~`FS$rgMuB;({@6tWzww+)pYdiZ+X{j;K%w3BxnQS-qirHja(EED4 z-XQI9!4Y(k0lCx9(Q^a*&Gf>>>CYx|?($3H>0W>zty5sFcQSM-k^D)ub@3iqWsJg~ z16$@S2zc+s$u!%0TTcLuBIE%DVy4Zsgi_nshnw#wc7CyyeNIUJPPJJId#>)tD9zxU zMZ*Sb!o79n@df*{_9gPvk?)EcuoS@Fxns&}jI+%RROa@a3U~DlB@xJ+R*pqO8 z+*$zk;+6Y-@OuQik*0wG(5>eHL-?Dxp38D+f&dxaDKvHr>f8wb8s0Cgq17w0`N zG2YFyVCB+3{PA9z8O11Uy10sSe7$H{+L-AMQtO#9Ch}x9F0@CV3iB+Xb{d7L=7oQy zr#`~nE`YlwzLe5_mKj>rpSqW!E`g@a;iW5k$Dn4=`^?;PoV`i4xA{gq3aw^=RmCGq z36V_`h%|Uu;XP9Pw&5^!HU_j!;x{vP9Bo}3XD&{69bpxCW`gQ^|G@mshiyJ4N07jw zmXAX{4IWc!3D5tdl|d|-OSctdE%2(#40)hy=y`AeO;3X4NUo9$1epMqlNld-ZUn@G#NIgB!~11UGcgd)&}fe&0r+cKFMipB!Fw z;@SI;68|Bn5V5&O=c1|| z`1Nz?nf(RmF5@`0YOb+TOCfV+TLn>wbJx=>#ESPsBLx;zc zYKn2?`0An*1upfI2AB~83i3l~6yNt^Yq3SzKv~&HK?A<$f5x+b{i4Dc9BY3PqW|xd z{g<2#oeasGj1xi-n*SKKH&+)$r!sUv;GnF<)NOTE`1)VoMcQKa;;bmzjZT2>LvfW+`a3%Slr6MST@2&1~ta{^m z`$SBKJ#|K*>sIOSy_i3pixxb>vrzaE_5h7oe)CiLtA>D_ta6*dYuNXjwL4+ zBtOAT2)XPf>N4Y%X%P=7hH8<-y3*W)fPL9?9_*1A`i`SsS5YvmrDc^ha7xrehAG=B z0H9i*nLc1tw{E+##MTO~HJ90xLx8oa+CnXdr{z5ykPmCR3NW?L( z14~P`MEhr`tLRacYksrEum7*X=>poA9 zCwfjTU6`~CUKaPhw967@>}X5oC*s~vMcxfsqJvnRxAmS`kFk5@{(!>eeZ$-6Q22w7 z=2&FZ`UxV*6FW)SVZt<{-*_VWNgJ6HFQK!eo{vKJtbYAoj8F8P-v$5iK;54Iz;&yV z#mQzJOiRQ5jd<$UXaAWQhPRM+*%x3NqbZoB*&00X&Ozt#??7v@iz!r9;IPjs7Wzf& zC9P8EM&owuUgdZ!G@CWGnmoHKE~QpsrkIdXeV%BmP`19;@#%j-#XwBy*XK3bawib0 z|Kcr&ITNSfBAD;6uE;G_jbNg zqLR_R)f35Rc?JTTb+-FX0Jym~F$gT(z&4Zfu|W zttG;OKU*tvUS0RM4n>yr&=4<&c0%=ePVDm}iE8o}Z7NuDwMJ%_r;p&j??Kwyl~cD# z5If8#z6nGIW>(~H&6}$?akKfWXmVKkwy>A$mv@PEHRLZdTGSp~Y3N@`d+6rOfAGNGVI<`$9JTz%x1D+Ug15x9!jUoSS}g_?4# zo%2V=a6BjZX71r~=-pC!_3TQw8ReqqLZthUv-`?~c_YtNy}3YKrJh_P`wES0r;!DRz`;PKg3Fg1($HI3 zJYkh!@QLTR7=bs-HYO{NLdynY@v&coE*TR}&BbJ+Fm(3ViTO3CWekqMQKx7k7Oyej zpL&vSAVLq>rQmv7m%riF(M*Xwd*anb{eKi~`I#%A9w;FsC0NqCr4F^>BX6ndEbQV* zGH^ePFDv5=MnvlllR{^+C9v}|yr$9;aaPuL8gaW4xaGF` z1#mrSml-33%Kd3y*lMIxafROQnZhm<1h;4um%Tc^^?WsdB}Xh{tDfNU96Xn1oV~X5 z&17Wv*tF$J6lU9~EY-+qd_U8cBixoXtbL@SN-c8}U576PnNja)x5fUni+6v1+F@3d zZj$4E($I4#w)-beDBHpIh`e3RN&BHd@l1JTb^uoD>Fs|>Wvc41gKRgx2H>0e%PlM=3?Xip<^zn`meyV|tNtj0Ev)5GrrCa20m zi7i&A#D)pwSo;q~j?dZdxF2 zKa2!qOg7y9_DBCXU5CCB#!jl32X&`La)Bjr%SL}CK3LWz2ZZl-fmm)^5V$LK^hWht zkcGjFq@Qu+bav5b4#@xQ*b;d>!J9a1OTL}$jozYwMLFs{`{h`=8E+LAG!AoI_&byF&e_@hFtrojJr^*t z`u$-_EQf&G>?L|n`_gUCrM*y3K13R@$)2_y=Hc69ZV&g*qTmPb;rE~0z}Rs;{}?tk zJC7u>XJ;9EchfnkV&ksi+MREhUJAJrA741wyGSvj;Q#!)-S(zhCx|0wSj;xsB}gEV z4qq?W54cWAyP-@8k^a5blsYv8aAbq)GCPn4>0J%+(a%Llqq#*z>jVwA_J-RYrzoTz zbf(x1H(?3lVhyhku?>>IkzCr%i`v6yq2pxEGM8&ev+@o5u|j>m7@;=~PUrZJBTEzQ zdMss+^cJTB^l+~GUkjxqnyZfZod%+J^7-}epxRBGB*kFf3T_*>$N(3A=(7&1f`f`? z+0ETO^|eWw-Av?hraU=xDqu*4kgHY0iJaIo?!tFGZ@m1@_2Mf1`1FAS`>L)+E=nz4 ztSr!SALtx>+4VwG{V|Bfktqjdh4r$mE`>YQUpneK*#qnCQsozrYWAt@c>fDm+V#(M zjuyH}@3t4HV_t)Qxi^j?0UrQ!Eo1L}X7xWpvqqpC>ZVPb99K{q`u^NmaU^h3Pv6ho za^{-@y@^`>3-?+Wu!jX)K}p`m5qm1&upwt(#06C2>d!PXhMxjE zFq`{;F3?3((aou7ya9WsB@d(v_zXf@DUYzvt-GxFvI~qIN_SIpVjFd_oAGCr-tE1V zi5@G!rqx%bHidXK8noDGXL*1DpGjwhr0r{3=2UQI%gq$8#3_Hk5MB;~W_%C+AT0}H znfg>_s=D_d*$0xomg%m2?|*??B}NB}NET?$Ywp-rTbO# zp}3EFPdjTM?5^wf}>8-C(rj9>F*`dOz#XLXLC926>% zU>|~bO446j5r+`v7sF>*TJ3!k!t91J$rZ_dET}gT^3Q%3OH)I?6TptqRwX zDm5XH({*i!f%mkk$6)=L?ujEO%?huZUKI0kD7K#yK&ep3?YxsStfIgn0ZOX<$xUEuXe-$5HIhE|WG2kH zV45(l>@LCuK%pAe(p)cvf^R=0w8tQvNwAGfnk(8M5WdxWM%SAagb)tQE|dP%cj15~ z>`%4T2V7!sAiS?Ht-$@H$IL^GOvlon*54)yIk{a9C~>#xT3Y%vl*%NhcB4AferQ#* zZZ7n6hbdJ8U=9|*%|FXg#1ew+IQVkA6%wGU^x6M~IO09bX=yg6?EYm0q?`X5L8wg) z+$%l%C357^(3tBUQ2Y1H;A3-+;V}?_m8r?hgOZ}+Q6Qz2%K}01S%@b?P=>LUn+hZB zlf8O~?BLoCecv#5ZwQ5iET(MF2rM%JlQ-$(Cb>}=z9MdrKM@ACZq z_B+Ksc3!m(P&>Z!+SRLjy+AEw1(;xnfL|wHIby%180Ncx0bn%~L+?y*UbRIJeSEsI znr(&%GsOwf(a}eF=H}?IpImSl-i>Xx$gjI|oXCd`V!Ttuh>cv3r^`rFXcjSp$n8Gf z*kf>u>63l4UH*`R^Y=)>5w%azgg(+tm8W%?{n$bu?A0$JqP2N4V=8d}4;l8EQ|*6w zimbDVIjK_Er3o*3MYjBQgr!-J%(Kq43)pp36+s67N3bLwEF}U;zXyN~B?dz1+3wxD zcT`w-D@fGi3j^3dU|<(0wHg4TP(@(TucP$!RcPXpJ9qBnEKUBFA;_F9`db!e1|sT= z^1NcJ9)SSB+an7-&q3jXt6vs3BbUah!v`^pNtiVk2*lJi2l+gl`(FNL(RPVzr{L*R z`!aLuZ7jdP;qB zS3AodJ$17znvTz2PqC-n1p;^1Pgr(?(C1C+(*ycha-Y$Mt7lt4ae;~Y?82F-^wu1E zGmq(59<`YT>RNivJo|q8lQr(mdaQFplZ?E7>i3!J-l|5Kn5J3a_stW zF^MH|v8AsICJD+LD|9by7y$ux@{5fXKZ`&LqfH4ijvz@C%#M`W-EaxyVi|7Dn_~?O z`Q6LG!O>6MUKXOp^G@v`=K!c1QT^aCBDu@;|LnBPi0h|@Zw!QTdg%|83a_(JN=o$( zOx2oGI^{Ry&Qz&z?dB6vgT;B(H?^Gf^m5il?7t+&Bv7(e%y{{`aQ7zD7+@Q&48EDU z6Qpl30;N_gYIA1#(r~1OmbG|Lnea3yPRPoID+l4w+@Ma1=Z|g(GZ32?)!iTvX#=Wp zflM%chqxgp5dFXNt0;Ug&{a-u9yzL{Ju+ZDR57w3FzWv&KR0zp@EZr4+Cq1Cm7;LB z>ZP2HyP8d(1%qse^<6aBw}+bQ{*e;2~D=_%FT|h;Z2hQiD9NIz>g$)i|xe z*)?V<5@FWd?W9e4v-SG&@i>XF&BbVgo)Clss|70@uk$P$$CI==BkOofc zwRnG}W)Z7D$7&~!KBsDT5TRJD(ntkZMqGT@4@R7!2QEDH{0UV#z$0^2n+DRz_@K z|JXo@6DkaU1%`VsZBcx>iHV74T8u~}(u^>fN1i)9BQB0eG)ap8zxKX7D(AiJ_ZJ)6 zHf=IBNQ4k2MUw`bU8c%dDvFYnp?T2!Y}*h`D2WEU5GiRw8j(sUN`s^*Nt!gzbw1bc zzNP0q?;mHKwa!}Stn=LKeVzcvr&!nK{P>zQZ%&s=1T%fB5BfHfM3=C8Y zxeM-lG9@Ci5fz)Yr3)OF-smp$k2v6{&i-TTMrNXlnO2OxVpAKc{_{Ca{_sz6+w*$H zesoOrVq~i)Wz2nOu{KD_WJMuoE`zTo$5ujHXJR~$eAD4P*=kSEo9uf74i}Sac6SYrI{6vl4Xe|>zz)6Ol+xp$9kwYX!$Nv?K`MYPxQv<}s?Cp^Prbf16ugT3K&fb;J6slytz zQ8yM7fcgn0WS+lM{?EzmFXSm6Nk!X)WTch-zwANBz>E!>9E2 zo)dqxm}Z;ryvvn(mBG)>JQnj-GhM%Nq8C|}#P_2a!LwJ*)8s;qe+j(gorFF%*)D^a zN9N(yecJ8N@k?|)lve90-4(d<>R`Fmi{+LtmOse+_;Fvagt4?@N}|NPaxFVcSt zhX<(w#OYsuu#R-)K$HCr#agr{oZ0MHlB}!LgmJABTbO<;zy)V8;Z*WiN=p`|T?q<$ zqNiLYdLjzOo8)^3N|~s-xw%2&v+{x!j38UF=kFhUVSpa9pPP2t7im`J)DRB14WJ7 zxVO#8IeG42c4UxhM&i0N4i6@IWhUAy3QZY2qPC{9A#e8WRb{`O)+^GEK47<;{l-~< zl`2cejvH6a8``~o4`!)tTk1c;Tko5j9=o`+h`*&VG2hO~Z$NtTG-jy&gl4u|U+>e{ zqlXrRd+0wO%YCfR7meJXzHF~6tfqE?At51K?%IDoua;%d|I8q>+DBQ4+5>Q98cj^! zCOl7V=}M26R%+8TvBkyTW{-Do)=ytJ*rx4TT7`Rhf^6_S)(;|A> zi5T8~98pu0n= zHZxDLuj;A6z_th39%s%tTDLO}B^A0U&8Nm0c}7TaiDe&EM(w-yJN0Hc=Hq(>!vWVz zop4hO!cb#6ty*{Y^b{CT$cn}^!qm#F^r2<-=5%VViAGA^ACm2}zkj#zdr@;)+I0Jt zkTr7D9qzJ}iAIn^l}D^YOVw_8cGQPvssE;Iw;w_F^uqHOost!wY|biUoVy+^kF7hY z$fqgwNS})hj3Z}XnB)L0t8ATE!~z>R*}8C1SAvUo-41=vGk5&A2U)eNkg}ecCv-+E zy;Ws%EuR>ZRvYoYEJSj-%PxZ_>^aLASz{Dg_JMK!Qf}IkD3<5;ta{3k@`~0Z{#S2C ze+)hLuBbIh{zgnTccVLNFB);r8za0+P2Cg`@f~khy&X4pn)U4I$olHjT)yLQ&z|4{ zJxc)&0NU5~T=K_Pd?Q6fyHuNJPi_9^vZAc%+w2$PHFV59^_k|}ZOoeC)AVuVO;U@j zmR+?!P*oiuq}&_pZ*@h$y(`iAu14J*tslsa+=v>cx%|~(Y!Hz=+o!Ga3yW^ zX&CMiu9POF221ho61#92pPq|m|9C2uZ?0YC)!F5r6+*fOzTK8|%ktY6Di)wS1=d!Z zydo((ug{_kIz_Wq%z_COE)S?{al zsth4}EAxdKp_qc%GDbAJUL#PhsprBGMrb)xktC}8-Yws;=)A|1gY1h;9$7tSN$`T?5i;n~t=^o@hz0==`>>!j-cP$kP4*CYj&nVa0R@ zp0N_S$M)%H%Zxuh-tB%ZFf&sjKXh)EpX&~zKmIka^x;w2#`C)O zzdTK!CN-}25f}25s})yM*0U;JWA;_?KUmE1qduyJ zEAUv{o-XOu>({MmGDo1<@xyq@+YuM)I@otxyn4j7XZu?%`8FifA#^qXD4&fIGuZGx z|7>CHMAh|~l4@Jd4(h*=V6XmsL`vbwEx%3MeAZ1tR^*^G|Ep5H!!{O?vw~%<&0dB| z-l#5NZ}aiH_K0jHb2@Uncw&1m64p*;!IgsoZ+efg*Ih9J&)hmYTJ?U1YUcMdoQ#aS z;fPez$v0+3?+>juaxg#!1I{RYTSa~ZPPsqfk@17#Lzy8_qxNyZ(hVaxwu?PCB_-;G zeDgZ<>AdRco9_&CxYrn2yt03%Zc6p-H;1w;v;^EYkJ`sRV!^f%WC6TLQBLQnzSUWI zseSU&uLhTLQ@*~_xHrXj+@CBKJ#)nT_@N!+79C&6U2fBnFLS;&=YCORCVTyVUxK8` z?qWThjOM?;|M`;T$?;=*4b2P^xpHK2c?5;&p61AF3Y_xX`HIs zap^|3trI6qm@LA5KRm>>6?tpK-LBe6DAkwlKHe+&L5MwE?oYWpLC?9^bI79AbIV<+ z#2Cj7F@4b`FTH#Qv%)58vcHmR{HF}%Z^AiU$e-q+1_7qyshfQtmPXzQe29xQd(ZVyB)&I{;KW>{`hZq(jzW> z>rrYyb<(oxAsP7K zuH)X9S0xwvTXTLRxuB7vCVl47Qz{d4?@7W^!hXklWp+zhqo=DttGel>_GA z&Q?+ACT5TNeomkG4I_vqi=#FwHdc-@=7!S8N0`Fj#JnbD3~&#G)reaD>BZNlkNWsL zwP^Yx_8Hw#smJ~SkLmv8TfOPf%v;ZYh=3IL0{FLU_j-4{`;i4QYGIwvT zfC|LtI-)l2zcACakT@^0x*cuZ&P{o$Mg5mzO#Gdn3cU{JQ(}tT^}?78S#d%#r3WB2r5LU*HjbzWwU-;xJLI)dE74UVrtt0XQh~w zxZS2eCKl+#lt@q{*z0>9R7*Q zSuSgJ_$ThuV}GhI&QF&Za&X4s-}%o24J-KntPt~`GsIfqVd?lkDP|xNZ`0Qwyb(HU=1f)KcJ=$`GyEdQN2@612r#W{ zD;VD?tz+GtePx)>CsKG0m0l9x%a1n0Jq7vi6HIw;+_=%PVk*;f5E9>d9gV{M2gi&& z>yhDrUt;n9y+Whi*DQ`|{`XgB+}*gBY<#b_apUs<*9r`W zDFtlFzEfSnjaZCykr+t9o!>-ghB{vU)jey&e|Z<-xt}L7J;LS;|9u)qg5^nTZ^H#k zo=P)s$3Z*#ilU)qRP)pg{~*0B3bIi5jnJ;TLQzbt-#Uet=k@I8|IG@qS7oG+ob34N zq;OvDyXJrN>(6ceztIAn59<|Tn0+R8O-Z#`qM^>MH$vTN#0+kqHf0V)aSuz*xc?#> z49?GAXYuJ38a49u7^eI56T05NeY!>eV|GU_$p2T4$&yIYe|B2brX55ku?p}N7B64! z8mD@)@`_^{q;IZc4Z+g zY>2$suFln_1q(m|44o}!bs)&%$#_e&_y1zKo!PLckSU*6KDUfCTO|d=IiT!(uQRHFK}!PX;PJ^TXFrE)K1+s1MP*e z7N4H%1{GW*3u5I||qh$#mtB;mtYNxgOe?>l_z3GDj4Bf2Lf>s-x8xI?t z`|Gd29IqNw04*Dwz7wCfUB5Go*9Y8NfO3J9E~%HAEdTY|!>?iIs@_))+Rf3xs^d2^ zF{Y)uCcwZO1EUt|yY|#vmNC}{t0^tFr2Xp~kqRWY`X}kAubgzv)juF08}_E^c0|Zo z=#G^K^F!v)jGo>UOe$c}oGp3^tz)l!(nD6Qy}m?333DDiQ|Y4pP4?+8 z2DU1|NOy!Q1%%C?FXYzWGF#r}P({;48D`Q`dM@hSj4f6MXYOKDzG-Ee%S53yvZ|i5 zr-rL~ovlc9D*5EM3%||yx{;l-qMed-?eFeJD}P-R6W3~i$}^Nmjl~GJqIZGJ+h|zL zp~|pkv6z%;F)6K^{QUghe)UXP&b*Lz@7NtNSTD zjC=2{-IYK*q*ZAyn{&NhW$tr<(5X}FOJaO5NG%f%kCl}YQzQcklf_XmYW@7YB}c^P z?ekXiD>>MLw(n1;WFyJg_6Vg>G)!>z8V8GV=eAeJlXp}w4M8M9{oO5+7?p+5dRS#_ zzE?K5aE9d%EjtudZ*VPMK{N4@20GtM)V@ehT0l!WNK1Ol2xnO>$ZfC(LU_K=Y3b6X z?07Vy%tdrD_u4L)G72%v_3meOw^SQpx8>3?5f+O!B@-76j-N736$&KlOTlIdFU(~t z?wV~dA9O(2S6^4+tzo>NIGyocp@oO3Sh3)rYx7Hnv?nw7c#rqg1XSO9I{6$lrg6iZ zl?OIB*D6$c%v*PAeSU~yIDWcKSC=1S>onF3^|x7qaF%^eBJFZZ5OTnjS+B-9yL(P~ z6tl`EgJ)bOCVXkt)^>6QT3-3VqXYaZ1H^`A2OcK&U6nSShW*qevBRXZ8Az%gPB`{K zo*1cjv}3$|lzJDFyn|49_l+QQg)vTf?9FQJb16I07WesTK@w+kjVHpNBenAe0)T)<~u)|Bq>`cnYpFC;X zHzx}!z%me8Xd=J#;@sR^v-U?A@ucY5m0VeK@D?5i>ix5jkQ6c|ZpRC#6X3g&v{ z=jRuzvCz?WZs%q$H++36>e3(wNRI;RoS_9HEA(pk{Zin|k&_Ar-Zn7WGz zNHDczXMcSYZtXafb6zAIgE(v*Z(`YiVezx`$i*01N?y~$Z9FVHhKa1kdRYjewt=OM=Ru(Zvt zw64_IEB2`r*P6rNF4}VW_reIx{L=T>(%la&_LIr2@3VvO78rlb_!rw|A1*^R>I}~C zYRJw*g+h$HTyj|0{F|DgLcF3Ho~sTQFX*JPT||^sbn1+{m|QbSrP`{aNIP58we{kr z!>LYP-q4{Dxg}rFO$3KbvtZQs8v*+KH2QP!)NPU0vBDo9a5HFvonJtJXlF3_A+J`I ztcUSAY+H#5Y^+tHp-mWiqh&H7gO&4VK(AEh&|^2G4-Ib9($X@{|M>VsHAt+tig}al z681kmCHw7Gcol9I85eQu)?$6PfsU^j-|3YV|RL6lHUy3tG)GdR^ zNqj38oSHm`AJryzTRW0qT5#IlmdmmM5Q7Rn<8O?{IJVNYzSry}3|%y{uv)#t3aX z##7uWtf@S6hNf}e)Cj&3YfcggUr;^?2IPAFnW-XHWLqf0CNF^>szkk^Z=l(2E^vXw zG|dV|S{xR({cMKzdTL*PV1}sU|$(sq{zH|*;5-j zcZzbq1+h=a!zRmJU8_8Fe4@bWWgzYZ^a{nO;%y(EP-q()r(-dAb`P8w>NJ2Z8m zuPeW8{SXiZ)`%U$@FVRtm^8Gjc*2AU?4VFA_EMi6ML}fVZOD7yx|toiTA7xb>jYIQmNXuojd&k z`tGK*=6Y6^4#ICN>J>UZIse zgBv->h;ZuaBc;D957cS$IzhriGoc3Cq_=gl=k6i^WOvKOck6pE32$qSX1gXA6RS%E&U9Jc z*32+}m-b!?+Flf{f5&>!`s78MeL@j|MwAc#s-osh zs8D!-$FE%H9254I%Um!56^ykZ#aI)>baF|3m|MFsN&-_%TLc#Id_0G>H%O?zo4lx4 z=4hE;Q4&^DLKox43>9|>?fMgHV=`6rl-m@l`xlR$A|yykBt*1VdwA6ipPeO&n12T; z4v-LovOVHN;h745pp30xAqg9LkA!)ZFMde-Z;#)ewVu&izs19U`>-Q74Zr$qM9*u)el}L*hFTQp9`A?C7 zE=}7sl-HVsQ%(5k@Zw*k#b5Rcv1P2%z6|%E3T2Cr8JWEZ#jG5a8L!iL0Bfkp7R2Za zJK?C!yMyD#7_E~c7^SKb9PC}D(U?hYiDmtAJPct73k+Z1p`)YoGEho1 zwiYJvWubH;X9v!HL;05bsc&FAZ;I+_d@mExWzze4;KIVqKVRIfw=i^C{j+Bj7dsuW zMZELTns?EbGdSSdI&-BCZXxYK3!?ILm%hFbP5(Ob;Zb5iFQT3>&|{B>L|VZSZYhOO z5jPN1_kazsQJ!k1V{8LaybXpNr&z!dP6p2rI56W>h8EFLh@)Zu%UZruyn+@G?Mb=PL zT=Dv!bw-(IroKT1U{F3eD0SddZ;qO4k-@X8n7;B5fRYhvAJ|D?ILUDjbm9+MlBS^f zVN_g8(ZIH?TYWpqcb%v3|JXa1?Gu=Nq7N_|k^)0R&HI{5Zr}Z2_kMY7nq_s?ZV0M| z33Kh!MN`JP3FT!*SyQ%o3MtC72N=i_TV*7U(u~YBnkwfp_rewgcKmnYBxUBi4Yom# zl_j3z=&{J>SOJ*trgMkyCM}{WBu}^iL)}#=G<9^Z{f8MQL6)jEaP?Ka_-Bw=ud32I ziX+?Z2@ zontLqC@ZMW*egCKz)}|q`68`dZNL1ouNF|*nKNYawp@{35*vYqYcU_{G}j51FlX%a z=}pO$T2cs!_=?x*^dy0qM5rycr?;x75q1Ry1)C11_t!{-qYUPF$SpGnZfk3+1L(en zK#(M%6G%UQ>!+wjf5I&BEm24@)D8_g0o=00T;nX?dF!fhE~1K3sa%cfi+j78=eqU0 zFfg+%t{w3P#FLKI-?K*$LXclK5rMZSP_YG_2d?lktg)kc(plzFz(5Maq4(L>;7^Ch zA%(J$Fg1OLPbVMN-Mm^A6`yw&ejb&LU2ZvX9x{4_5XLud-G=%uuR5%C zBXQkixdmB1b3O(IXU}xIF7CXo8o!>d$dmcB6_W$06E0Tg!%0%mU=awSvkoaQvM9E z53kde)kpc2d!B2?rLBYUa5hgLuxrPA<>fD5y7Vj!C$)UOFkt<~Me1g@m*53CKpuFN zd*Aphjh-=M#54v*q0f|unL^|0d0sQ3u3=^X!J$M&yNDFAdG7rE&8=-2l;nk$tFT4iG) zs7bG;56Nn%vJ8VgCbdeyAe~%tOj#rwAc&+%UJwBxiFreC-snZ>Cj{*lTjvV6+bmtO zmyT8v?bhK&5?Fd_*qhLoNY$obRsxblH69o!cz)&u=OxPnb zpMp|am1=P0@4N|J_y^g|b^G8#3QvGpP>-55qo&p^e&vUYrWy=fS%nxX%5sIsE$W;; zeR?L2!A#sUx@a$?`HWk?P!odf1}HH;<+lNo@YWVbXc!~#oTc^T-&ZId(%%7dwI6`y z#))&4)_5y4J)FJDY^M!8l-P9Z+PpV_AxZ%z17z)1C4`iaC5(G)u0mi==-9y&>zZ7D zf*l~Ev%;VpbzZ?j7XXz|=W{}ZWzr@${hd3f!`D7Wp&?m6iK1kz1eyqV5Ku$jFo8T9 zFD`mUP>r#%v4_1z;L3%V3pw-Y=_xT4b3YHU7JT5hde(yHTn%NUXRe&IuQma|yKIf$ zjxeB9v4GX`&KY^j-7N0HIh;Qq!Dba&4S2NWDM+BSgI6@zW_wC^)j3?~S*cdwqP$s*Xxy6@la#ANv`*#TWLYgTqgi2*dBnJR>0;)?(YpXV1v zvr+D-WnwaO=FF_W$Mcex1+T)#b6`h=24PbocalF(Qjw?gloeA4xEt8Gl;ok;*P@!% zU{rh+)dgt;%P;JV-W@yN6?0Qdz8+yio`BGp8Xo4*ft4=x`{0S`f61}Yv`src+dcT| zmeHk2tn!moCK>>FZA zY>|8)j+F;o@74580*{NOAbss(Vq)jw^W^X3PBAB-&lBrab3F12)?(5+@zC9}cytG- zhUzmS-e-^^(0-?lTmW?MSs*g^vh1PNY;q6I>x2xP864;<`9=t$43&?}mNZ;%SZQ0b zcNSd1TXvJFr{4x;%9rZow9o5yPVEV-(_2{o?P)I~txv}?7WREMoW=e|bGOY6hw;!a zgXH3MH6?G0LkPdqe(0D4?+PzLv9V|i0>><<0zrtIdcy$zW>|V}Kbth$e|pZPB2U0o z1GMFr;UC{fTzg{dGsIjMv6&hb%h5DM`6$q*LJ4hM8BUt&&H2 z>G}?Jw`Sz>D8SPfwVwh(&y%l@x~$~l=&v}}wR=CFPD(?*?z&kpJT*r6hny`geDE6< zag~I%LmRJq8NueKap1by*}Ry*%iBlxt*g?_Z6e>w>l)37QWYX%oNL4+ak?D<$W>F$ z33&2?&VWmovc7+MYV_&JNu3Wk_63cN4=TNJ2(@*^U=t5lj}CY^ zDKA-}al9$VqjHl++7(8X9*v@ALj!oLph_ncrwPFYQE$*g6*G+( zOrEaS%Sv`t=D2g8_$zSdMo<)X;LrU?4J!JoffSfYqu{+I%;m7?LdS zwp2@;T%TLe%9Jt7456?oa@QR*8}fZ3CeM*yzjp1~M8|wU#z8N?10Yk5O@k4lTxMb( zEH~rpN@zjcJt(vV#hW*6YF(KP!Mn6OUs{wwE+?x|d8kd;rBos1_Gr+qhYLVx7k^EUsIzoq%4yN6EyY(lVh*=YkM2bbRQiSj=GfYkv-EGh z38W3bg7gMl@)xDr@Iuy|n)v+r#1rGDq|Aq*3lem4Zli6G4kHoF z6f$=mzZwipdZ;KbX7R1MQ8+1a{?f_Gh7N=?r7XQXU>yIWMPG5oeD#ZZK0Ltl*4mufQX8{7HcYn`ukb^G9fFe0GM~8zZGkjQa%^1j zQejv+xnLgmQ<{(&C2DL!2?C=^N-{j`{dT8q1+t#ktmtqXy1;4>xYpPPThU9)x~rHb zcz=c4CKPd70Deerd&4`a*fg`ENd91weB`C{`JAje+AH&IfiAEI&Ma7jRXp4fJrch{ z8J4B>GVPBvyspK| zmPJ`Tw}-1w#d?IoC+5?_wL(C&dfSlqIRxq15~`G%*K|d}{+OW)DslOm`=}EH4Dc(5 zfE1p6YB+wIqs+@6#%7t2hxZM>URKB+3C2V|eNhto&>UpP6x0L{!0|V7d#j$ELy|_% zJk@`9C4}V%xNu02%vJYbS9)m6MvsUft4-wyFet!{cur8_y>O&xv!Ly+bT5d4XI*rN zk{8kwDWOHtRgAq7a)vGaZTX^|)W@QT1?wAbA^P*^fR!%l-h$oMAh5Tz5V%56o^M@$ zTwI)4C?GiiP+aH93|V524mjjB?Soq?54a)X{?hKs@J|UG`}+GU7=ko-cbp7^#+sJQ zhwz@l@2wazp9H92X(8OfOvi#kwWWA<0+Tbm5z6`P&ObPH3kl5HadZ4)Yw@%%>Lv!} z#cXV1PnryCDs$Vv)B^mGa_vT{$k@0A4&=g4GA!R~dRY>QV(`K1CbAJu$pU*e z4CNqRlaOo$)LY$Yvq?Y}=w zB5>fz3Jv!%Ly%}(BWkaVQRp5WG(NkHkwvX2#`ioDpU$@Jq6YpO=GUL(AK=bw+PFLbsgyCIG_Mel#9CSJdyyP zbcan*>J~So#d(sB&Vb+Q*)XnVY7QvYh{bJ7Yqi{f(TUwggGFmuw>XA9-4 z9$Ri)KRejr!Zky|2eZd7x*}Pg;c&4LMFd{B!5Zjc?jxoRw<7Ykn|L?6R9Px$E`!#&O+cfDNg@+cXrt6Y}+gk5)3D zBd(0fAc7C}!1zWNEFaA_Hw|4PE?yBX)d($^V=xMCTpvPM@eO*RaIh#j6RsGrTyG{+ z&&Ix&$R({T<8>b$8a(#i&~EB`hGY$bB+E-cR9fd%g8(yFfi^aN_bYB~ z3qMquHXsyw7?0qC;BkIrWaPA-RWQK`@t*vvBD17aeS}iq8(ei6ol!z+{=Po+?rd3$ zkKD(GWzIy@8qgVdC9Ny*ftmaRG_8>YTB|5uh^eaX{R@$!xi$%R~AA5E> zLy`-MHDy2jP0om_(r_>g|xx^aCWH@%-$u`Ypv~N0L00|vb)2~yfSC~XbVET+1jc)=w zah^U)@BmwOv4MjY5l!jxSR|!9+jZefc_}M8Xu8TPGX07QlZ4ahm=O!08$A^YluCeT zQ#y&Du<`2mP1ySr=0?$1nF%$fNL8v#;}IT@yAWmu5{^it6tKxpN*(vinbyK*vkZb( zA4*2R=75_^m044tK4bwRTn=`B|KwzQpT>OlY((+mzPVn4aw`Gq`^V{nqea-0s^bSB z`ozrj>ww+LMt)tYV1oMzpWv~+=_vXRC&m)URZ5N4!Sc3esWk^MHr^{o^54lYe*XT? z?9qiRA%8josf7W1;z|_p{1^6BGJ@sA9lDHy^D+~DnPY;p_S(Er>cFbE?x1ukIy7wQ z0}silU@+;C==~$_rWs{`2M zyff$w&Fd~-C=`daY}_%InXGTeuj1MZbfP+;P~#lTzC@!nMW2M<5GmpBMeh|lC#kpw z!Uy)dbZJp>43eGH0f{;ql+}u-byp<}eY&>@3%!w6_61aScwF4d^ZJy0zk2M^?W|gA zAESmR>AW34M}o3n32x$dp^}XLc}K21YU=|#11a$UQb*@EXZBTgtlfpr-O~(HTDfcI zP9nrmld2`5rrBX~Xskeq@4H;u5$zCBl0A2mcXxHo`_@X9iHYCw8PT(bJgWSE|6 zTK0$#N45_fTpqD7WMZlnVZ>(=wgR8&pDYugHgl-Y1Jb!o)&_lJh26XWCb%NYaMR@r zbqQ;!&Th8#xiXl>JN3=AwI>L}7PKqf@AM&?mGf#;?7L4y*B< zttj7zlroFjHOeT7%!hlSRN4K@zR-83Ob_vP2Vnm zD=!2)LZMCa3^cF8i#)QRhCuGJNBYIDmngbm&Z$r@Yw2G2vPoghO^#|COW zKv*Nv2k+&tG01}o(B-78F5y%=5$Nf`E85iBizs|1WtG|fl>igrDlG5(S`OFBp)s+f z3Z1^(svze`P@VnYSP5912twNcB`SUk@OBw(VUbfbDZ?P%oUv-gk%?X%^d3tri*7bm zXq4iGc>Yhoo%Ve%DJr70KkVtpV*@JTF?(G)idsNRYv^oCev!tLqX~q->!ODI5}dJ1 zok?(gSi}!%aKH57;$=0~Wa=m-1K4{m!A4#KnuzKt+;?SFW`=7e-&2e|}{igh~ z_6c|q{8*)mTI&XB_wstU->^gDl7x(A(Q2dJ2ra-%(4bI0VX+S2 znS|fFXAzU;Z3FS{?>J}BKOY>W=EmZ9go4CLQEjeB9lC!G%R8N7G-AE!HyDi4gcHs7 z1pwBJ+)LlF;39a#$YjY-z|^;LaEK$a=X;u0@Gydz{Hu@5CjWpoj9|IyHsW)DzSdxy zPWBzpoO3m=yC;nFhQC}!!@Gc)Br9{cHWYlMmeb1p^Qu{qbw5xl!}Oho6M@DxjmHLb zQe`N5c7SUb|3lX70m^oh+Rs)VwDih9R+*-Vm^C(E*&-3aObhZ*2c`Q3_E!Q>R=Vw9 z54!hcX<|^5F$)mi8&?*A#cu&?MGbLlT-iAH69K_v$rErtp@(IrbOLcp38yRW#p5h^ zoW>*TP;_^%0(Bwmt{fVuyanB<u%R zgA*`pDl;j61`5P1%B5-LDFa|6HLNoHKn)6?lq;1mvtw>A=N1mjUn*H#F{La|H zPhofJKnK_-O@RB!PbFDwd0{ZPlJb+pXooKKY`+C-hfpdTt!@m7M~(CaDcCTr=<HCDG~nw?F067Zu8 zGW9EjhtJ{V17$4r5tp zTWSd63pokdFl^N?B+@+rU*3v}@&p>EM(PL3m+B9Q9}$knBSk`lXd~EL$|>$~lQYG6 z?n{R<%LFlPdoiFL0puh!k6kl^5G1k9q_Eh_^iyOhcSo^0l)*D>*lg+?2Hl3#_8GXh zs=y)0jV3PFA$X5Oe58~VOo2C<07#wHK+W46Qu7M-O`cdN@`y?KXhrRwN_~o;lyE6o%xCs4^eJeO4G5v54_}vFIdNE)4>dXS~o=RnKJx0&L8@fNghUieARvd z+&A(g?DH#*;>eGR(A1yZUf6$dUo-!|mf9X)|35vz8A$xUeLhb`wD51A9FhM#(8vY( z&kBuP4TMAgPn{vFFYu7gLi4DtUHe!(o$~j4d;)9{t*?CxzDHS%8%$b~5LYVEeqkT? zZLPkL!GXB%)i(z`y9aztxyy@nD0K{fb*G+yva2&?j>c>L!uiJM(LcXSQ4e)0)Y9ui zpZaN_0*u%66ChGS7=nQ06nzvR$b7KbF?rD_&X=v!e~7Ak=25r}cOQL=G&@WdL+tLu z`JX(jA^;XHIgv)8C#3~Hd2qhxzK8dR9uT&iqS(F_e5Zu6GOz{tKMe!_n};+U=KoJGXmw<;zsIzG+;*m$INaD;v%@mw z7VF-^fBNLn`T||4c_;Bp-@0!HW?VKXT+>2+`sm5)v1 zOkf14u4bnmB^Zh4^zL7+TLD;B8w}PML`Fx$m1L;_!*4d>=bK#;XPkvU4E7=0cr)d( z9T-2`;J*AVnyX2a^4u~CY7inTObY@EL7$P&L5$H91Y%3-$8BOB0zYVMOswq5v!52U zD7^#Ry|flD^PPHh?J6)a)Q8u@^ymE(h=q>JU}dKa2pT6i`its4x5IbGUCzwXz9uaQMv>U zs$ZhHYui;?yI&&Sxlz4{aU;co@H2ji;GWD2J1>*J&3-0pQNPM(=VnDj&Ha_n+q7U5R_uQR zSCPW&8(P4$XmkWz8Buvoqa?<6;?E_}0hqE=OY0^}fTTr$p9+|L+tEhfb(7iV^|3lj z#l)%!S)lIy)LfLx*5Pe@a5P7pNDM93PeMAZidZ33%Yazta^ms&qC2w?)@l%BSX3;k zeq~rB$KCpi{JcG=_h&yA!fX)}agY;gQJ2L_B-jKKTPj76Nbk2wOvH9%Luvy$_{jYM zj%7}O7Z{RPVy(eiC+>|UWk`usPweK>cLrBcNz;$4kac1rd|hG(hp#(5nXj4KJo2;F zPY=lAnjV;|VFUcqhu8|wFvUCZ(2nGb=k{W44c^ymbC|)cs?rkvCTf#R9XvGnz zM@ojaFolEh@cCJ6{J6)ub$@Yv^8{JCNQz zigPc)4669V0oa^i@+jlbg@ThiP@=&{i3_dXyCAAjc7J!0m9bWyCJEX0VyLXC{{H^s zHMo+sVC@epAPjgz*Uupz(YI(t+g!ZXGlZ(!i^qZQ3>D4SoD2_F77?`}6cC@Xf_A|e zcTg{kV0V6A?VlB#Ucq=g!5nlbxa^Sc{E)|idfm2U&&A;fp+%?83EXmGDwsLng>!HD z?REr_CE3Ci@x71M!}f&(Q~M3ujj)0$=fF#*ydYa^3(vR$=n?U;v<_<0WD+3wz*?ys zVZ8c(^ICMc5b~DRbfCm+Im%})x4KX%1hA7MF^)pkFD0Ei(zZAvm@F)gpSoQf1<+t| zN;FD=x9CH)K$IDyoK#sYs=0)wPDNntHC05lKbq`BH`EzEu${4R30Y3&D<))78QO)HAJr_bW3* z1!FK9ejR{hvWUG3kiSi-1DOnOWHM*V9NUAo*%Fjt1l*IQ6s&U*yo>7-8Hqg)S5QgW z$&-UzIbZ}Ao7Md2Y43jG4K(VG;@-~2WP{UgA_e2z^%BiyMC&HzI^bn`@|PTj2hoyT zIdBY6;Lst|Xt8aOLG)Vb*rdE^*5$jNJK-~OG#Pbw_Zjlb~j|-{Oa}XJHoX`Y_a(i(;G>T`}mhI}HI*&3q(`%S}L&H(a zhEmpubae^169YY=t6C8Iy zeNBAw^f@OP|had%* zo(SnXaphR}D^=zpq}#L}p!G|K`~@@6>je3l?ZqE{y!E(C1APWwT(#M`4iM4?9RbwS z{dMsG)uR*^BbL0{5(37s6QmOC)Qgz4~WGFHN&ehxpt`2X1(sg`E>Wixc;ZtO_~xqywH7HU$EANFXx*-<-~XXazs)D z&g$Va@Hf#QjiXVE_6CLw!WnYquUqdXGivJz>7W{9$}dxbk59p#x|I)fln~Td1(oFu z=fb$5;mSk6|LkY7(9eb6Xg}HlJ%PeN3mmU;Q86ivr~5GYIv#M8PNFL&QwJ@;QcomDzMSH(o@N zq5=mZ0ur70TS-iMzKH}Np0Sho{Z^L;FR4>{04Qud4CPOy?)hXGU$I!xjqPHSTlJ&I zPTXK|rQsVaeOWJHq06rqBroMC?QSBHQ6(icT0p7yOoB+MSQk>*)%_BlpKMpTHQ|>8 zdo9~CppE-Joua(Ptf*BggQF5Ys{B0j?lupGR0Vg-F!tZxE;&jphvyTwpMd9>jUrWI zh)$hKnt|F@qashN<;etzOq9t`&OF(+7@CtZlAfgWbpmZ66Werj0^{^|eC7JUrRm)* z>74yx#&4L#+{MwSjuvnt#X`*)jR=6K+mI87aXq>P^j#(RYXnhOU%#kP7TuK&RJH|i zt%>pdD@yTK{wU#GDr4}^VaJ1~Zd3-jEN`RrWN_6xfFDik@pPLHU2rLcgZr?(U^A7B z5Osu({N8FOs%wsVxxFy@Iq1aCHyLm)DlGFuCot2tZr^?(ZZ%Tpzlc6hgT$|g!rW1e zs@6svQctQero)L;$dh})!x3h-T&?V1gy7<0Yal|@1y~pVmI`wJ^fbGOvPPf2xx=EfOb-Ym zJj5GOvp{l@RbN@~!7mvHaiDeP$1`VunP-Es6w(=pDCIzk`6I?6+j|Zb67e;2`gAg% zy@z$krD*UMj;4Y?HD3Kf(3NA?Y5dF|7Y|fmNR;pWL4;$*36&@xHtK1uSyEs3q?q$G z8H1D>XFtL(i1+H3NEsS9V6X~&R0@ye_RXjOKR;-ugGDy)n_xPm%FMZufnNvp0|_7C zT*1A37#PTjgA=jFxDlnF>J}G1Q|lI@{`z%*qPmE^(o=Kb3MM7Sp#jh;; z0f;F6T%kUw>m9|=YH%cU>i)V-6(?|&aEUK(ZJb)BstKNdbUR?O$NOA;Gf@ZHivYQZEDgvdV zovge;M9}Z6^eTI`j=aCWyhh3-@WH5B(mUt~u|Y=}e35xsZh(Ua|hITjBKk*K^N5Gx-4g2P6y5CCFr}u9rSix`K+M z2`3MS17?{s@AP%&`$*)0(-Qn?qm(%cQJ@Ec;?nj#{)>NfL2@-f6CWBWSyT+$&PVhG z%HY#MI8^?y51Z%;4M6P5<)Kxqh6ED%fmdlNq@77^~)y=cbys@riN3-kHRRO-#hrFB0MT_#u%r zGk2(jkxB9G9bnc}d3c_36B+D%cfBCqMDr6@xyia0<#uq-9y9I)Ij?lGZb2QZ=G8+j z(G95G0er$c_wQ4?Bj}eWyv7=Esc4P?mF#+kDq;YnUm`(#)j#C6|EDeSCC1_4_tVOm z$bR3?H)+(AVIBZ*pcx{59TX757|Rj+hYBqR>p};YRI?@$3R3%MG(fSIn4#X7pDOC7 z{rv@cY#G%>J}9@^Oz>b#9=U0#i;{VI(YOR+6cE>m>QREhI_vro7*Yj3Kgti!z{71W z)LCT;6;8D%`pAz{zlFGhYVGviUAbkHr-JMC(+((4hhE)PHQ08Kfd~r7HLS(ce8kbO|>A~yyh&g6}!E=^~ zbyUlE8T3(bx|<6Fk%998Y$2oSEyzbwjik7!NW4}A&;%S81TQVm#1lb2dPblJ^_D8` z?c* z!>(VyURDN;L{2wQ%6#NY1rUhex!*~JWfa!^Kq)uq{=`-?9+T&^L8q@L-!0_hf*w;) zv6ehd$Nv33IEFp9?kD~pZpgmjE!CDnDSZ=)FD1H<&Ssve8QXgU~d{*9TATj z0y`krQg93BBFutUlQOtsu;81Ca-U9OOfzUhuY;yHB;D}waQ7f)^9J}f$ChFwhe z%wSAGrF3Ict0Pi@lqq}ztt`03UysNhRO|w<9A}>BN7RvF+z#$KJqs%Q$}nRmY+S!~ zXVOOybU2@B*paS3L8`Gk?gFR95=d_CzOZs##K5%7Ma7`@$`3zD&d(d3WSt* zH62f$JfR7#6cdlzQIiG3F9aj}zNP~J9ANmau)w=zV>q&MiqvR5Anu@jBv zLCQcz9~hGvC_HYdOLV$_m@cJb!??Xk2=WNsm`u0pXd^0wd;l*lT(d0>P+b^2WNK@+ z*9;h%I^RSt3_SVB$s{4}3%j2v0o`pHr6z%pG;i-i*1>AUwm7B!?@tLIqNYplZ*-yt zMq%6!l)fipc+R)x;Ql=0%n$YY;}=E#YcJ~mT!i`0n*48_lW79W?)HA2J%)9p OHvXxx{_Y?9{`w!yL%PTS literal 0 HcmV?d00001 diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_v.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_v.png new file mode 100644 index 0000000000000000000000000000000000000000..31738f464b96d41d9f2444833ebb38e15d987f12 GIT binary patch literal 247998 zcmeFZg;!Nu_dk3PTM$uD8U+;uq*F>nKqZuJkdW>!0Tl#kMY@#klukjqq#J}I-O~M= zTlBg2`;PZdxMz%K2s~W&Icv`~=cm?w_e??r`#jNk6bgm?_|Zct6bc8vym0^QY4|6B zuJ-}_bJFs`W0|w?ayqN+3E!VHd!%TILa7KN|HHuhC@26w5^M8_sEyq?x_FIZ(YVkVg8?Ax=(T9`TzL=>d`|K z*8ly%W>g zUWfm7)A2f>{_8Wx3-MnEK3<3aX49XI@!!-wUWor7#PK@(2O<7!jQ=3S@k0CuA^sG^ ze-Pq$A^w99$LsJHLVQvuwdvPj()<4DgMV;v@RRnFC|6!JK|#T+qs7B*w7Eiwz&%4^R@LtR=Hfl-)YN?jNz_VUK|w(%o1vWlw4ldD z-+?^c5Oc{FBlgo#tNUy1TiYfLeJYmX=}P%D=iMKKg@8IxRp3-ejJz!r%H|3wDe3BZ z*VC-!pJMWf?QGfP02X9hNj=5_u3iVOl*4B1^Z|uk~F)^`d zKC^VkIUr9%K&Ge0vLdP$aIodL|}*j?3kR^=k)PWBev1vx&^~ zP2&YaCf+3_C1mZ(WovEQGjaY+MQ7pK1y7HqlPZZY<`++}h**<dsu(AWtV(+4tr6QZ3uqj2KAyyXE?vG2a}}tq*52q~Se>+O54?I4t$c3GQ*unDbtcek%jt_K!C+3k!7iy47yyBvn;; zKXD8Dkq~wziqEe)txdI>4;dF?&mj8KjPGBK$;P}^lWD3oqOhj@=x5;5iOCT4rFtP0 zsx%msGlq(7O?db9tsG+{#>U1$(I-*dMsTB6n`pDv?bN98G<(w(U#P5m+m6~N^>JUJ zlAx>k;7M#+# zrwo7nx#RDfct7j*(`XX-NIf9mZPyMLTiWijsX49IZcjy+?rLD8?vE`rY>{%`yQc~J zezo?R`nSP+L#=__7pv_qhb&}HD_@It=hC#AKHg!{{N@=o+S}QAIq%!F4yGnSb6+1eO+d^uOypr2L44}+)FM;d+MxgY>VsjR@Ts_d<08F~47w{usTzEDqmyYkd$>|n_@N3+(8Y`GsCq1pQz3mjtwL zcvm6%9arVm>|ZplL7P!1G*JzM-h--Q_}`YiFfaOLFNyyk<>~T5sl{ZI0_-=JmJ_H) zahaL)^rZ{Ac5AI1Xee7hX$h`Lj>G)S!{#DK{+O=L-9y~H$hL2TpE73*$f;LM zGn!9)W2PGzgnLhtpP$bgZ8}=UwFDE0nI0yC>)rod+1p{cdFO!2aQ>4?B&*hczYCd;xhPM%r96do3^AFXQFnVHL*r+ zsFoKlwj=7zM5w-=o?7>7Y6`z3w6wI0hKq8{MIS(0ml;Mb7Jo+x7gy zva+%&Rvkj+qb_h0;^4(Ug@KB<-kA)kpX*6O#|KKxtyy~2YN}W?-dctEfc=9R)z5^( zvvS|c);6TfvKC+dqkik=3v5?PicFZEAEx2Gs`C75pnRc(Xxz$wRqN;1x}m6!;F=EQ zwjDy(gy6~#ABsh=XY}n6vm1F%M?0D%ZDF9aIbgyllvwFUTDEb$bZ*<-m`CR}(-T+8 zqE?0uR%&p{4{vBx9vv*B8z}whx?+v3t*pMmTNNE8WY&Hp7RvZp%)7v*^D$Lze~y;u zsQvc1NAnk?D-~S&Bf3}7C#R&`>CI9fn=e-vsjMe=aUyZqUoGcDhEq}j25Nx@rnTnR z*Qd;iV8kt z5??i*hwX0JxOQ~7Rf*g~<_s7FuAYA&!}Ip;-rlQe@>zcQhJAG<*7HcS=zt%Mxg5P* zDBl{DR8}V5TPih$`Fgv~kCeEc#8M24m_5BSPopZopr8(VwB|^O_3COpxrnl|@|XO4 zA(*D!-Q5qNjgr{?c*O);n{$7qMr(h2mB}uffByacW_Q*i@5WjpkAtIbjHlyR%!`nOZ&MNOs9A`BO`;!VSOfQP(h!V!^8*nKQvO`-rioM!^M`D^9~LT zX=Rmfdcoc&U^i0ehI)e*id@M2=X;U5QO9M~+1Z5?P%&Q$3J&+#HWv%W4)^=N=u6AU z%GQ4WEchGjz}$!v_Vq%V?e;3##aZ6OVy&HElLTtw_aOe+7>JIt9i8p6G$|T?%emIV z5?4~<;M%t_va~zzPwujBp5{XC0!5nRe6R~c$)~NYjR0;xvIgSf;#j2jSYepOaKgya zTA%4aJ`w?w=EDU3Q#RF0yVlqT#)tbm<)bN9s4}OWUuw%@k(@bLq7LlVbKONyh|o{? zU7W?jSyO&*pZ=~LQYxq*SLg50uaRnyO_Qs2Ib4fTD77($UB<+2JczfrxF|`D7Ylvk z;=P$qoIe8uHJ65qnVhy)cumklrj?`!0)sYuS1w(lV?Jj6(D2O}96z)lH$5^`pqP9g z2i~szBygm=T!D^D?mc?t!hY)VWu>zi@mt{!sIK3{!)0~#dfgdxfkIyL{{3}|Px57t zWF>QOaUTlY>2$yJWajMW+V9-2Za#XvytY@Pz7*oE-5xd)HqhEOec&*O)0#JJuQPp< zDzAm5K34yw-w&+m+Aw@PyywfK<(}`}38<)$OrX*4BO~|6h?mOC$_|q>sHmyW`txoQ zgd>n)N<>QPGQf^^$;s3U19@lOy?d9cre0vA==Sz41qH*Is1;vH_9L!Ri#p-ug zsLZBX2(@)|QpxI@n=c3m2+Z_m5Jx-xdi=$(&rh62;`OvbOHbeC$B%dqg@kV0zI_@l z!0EV2w=`Pr-Q6uyR9YG*7RF31orq=7m+1>{go2ZkfY)LDJ`5pJ)qDC?_4Q}?54R~F zJa`cB{{0OfewRZY80c=2al(YpMrw+GZPd?pCFMA57(5gaL07%PeDwHnj(xgR!jsRi zG4%Q}M_ekQu_bBbXMR=WOR}1@SH;WZ*Ul=nUDiC<-H_8dfr%+u>HP8yjRR+xhtU_k zj%wE@UcHIp#NEk~nDUt_cbIixzH9@r+F4MtH#V1AaNlyA24>qQ#VH3qeZ@Qv60;l_Mlj@kHwbcLJ~x^0n?LF%kF<|&fG zIy$#24tEWmV03WWE=7)@@lz$^P7C{!`F6yK#97UDhWpY^&`b+GRVovK4toZWpa+{_ z?~mRLebhr+>lFuoGs#+2Ou@S{6CGQ7ApXAS{irjLb)wbTzhxkEI!Vdb+}5@pdNrAYwB5spC)thqpKoly=lE9Zea*X8kj-X!)b}ah z&dK?{tilwbf-vT8)M<%;MBK8ac9&S zja49*4WE_}6|KptJoFNeVAt5&TzvHC(RZFRD}BqO$nsE%__@Wz#L#njF&p(W0$l4i z5QA;-7MoZ{OyD$24cF8leIoVw0;7S~unV!ErAuvOGo!K<==4TP*pNm3Ea(xd-S|PM zE__xulhb8sdp0RXvn7;CDhDoD3wzT#b7om(au+RNZ*Q+qU_^M8PQevO=WKWyY*0IB zrX7_oF0e5q@+$3p_qlBI+wZ7at6g)S_b&iyM66P3(`q2LIG9hq8$cJQT4W|*P&f(~ zeUg!Y%7)58c(t4s&?7(Fv6u1&Jj%xX*%)wZOQr&>7y6k_o;o$KJ_wvr6Z*28RxpFQ zA2jv>RzCO@c)h1NfBXe*STC$OKB_t^JDX7?B()eu;d%ePiCS-*my1xO9%su+{$>G! z1m2v!LqwHy9t3^XZiOKfI!XJ_Z8NG{8dWo102b3wAh?cTTx z_WtxLMW5D}MwD|D=)zlYo<4m#>B}+t%w(*>cp>6>EufL0A3vU}y3nJj;Vp%?g)}rg z8Zivs$t}1o9?2=Wy$dYea5H*%8OBc#-|2FLnX$@B#;tb#qjXUdp*t0pLu#2e!<$fm zt*x>;t>FnW$wm|Vr@9$a{5B$@W@Dzr{~#QG&D~Xlz-Qm^_oQ#`R>tfi(F-I**&IlE@^Gtwr1-hVGcwNy_3 z`=?i*D?=_+rpjk!sz4b8q8Wcp56k|qeGL*bK6hOqFzijAongiolKePY?s&lv8w*Qj z!;}n|XtG&Lf4>5${~QAl%dP`m#i=x?+b1R_nXUD>q@;ISI@07Bu*bNL+gWTZSD%*b zJI~`+1~$y1nc?ERsp8gqg{=<5LR>Zr z1cP7n-vIvl0X5NWG`ziS2i*xDFcnc>`yMh0pqi^W4Y`RomPUwSlw9%4fhHxJPdEvU zdS{jF3JoOeTFOAz|&)rJawBCI{2>g zcbI$&qvb>2%RF$%g<-~L8}!f!u6c1b+neh^TLbEG_=-uZ?m928Y6wYVVTL}aEvCvK%KJv5Zy=hT!z_|{BETxvMQ zdh+?NjN_#U+k2xbUt{N zBte?e51)vVib|wV32q=779L8Gg@TgOnlR=tgyp5gY|~l^wTjF7tu9nL_4$d339RI) z@$=`;Gnx!@YN!A#OdzvT&}$C9+tA)#NYn-OQdB(aQkos?ySS;>5$mp+we{=Q13kUu zp3s&SF#uLInLK}x1#>@2?9Z1s1H!`I0T4qtl9|;VA&X!l02V$}(RS4u;uN#9v&eKo zxD5Brqc@S0Wt@5Y`%deNL)Soe%2+DK6Z#5Bn;eUrPsL8~V=%Is@W&{*xCXK#adx5h zSG%R37VrC=93364CeG{Z>T>7SOwNa1D!b~?eLXKNJDm8;i$8#r+2zn_eZCKekdUxs z+RMx9!C1vhHq%cGCJ3hMNt3^Th7ENF8e|$%ugzKdk5FgO0U!4z6@sENHq(<9l2|Hv znJdo62Md`IbJI~?RJy$NnH2>w_pHxD`=XYJMt2u~h=qPU0k>aHi-(t& z$#K(27Hu;4sI; z8@ymm5gieLzWMPz2)V2LHbl*#@q1m9ha}!9kRVTk+{)t7J5D!UJK#&ma@w#jlZ{mu zaK_=PzYDOyT$xIl0!?3{d~#}=$XDSIz>WaX~S;I=VO;T_)L2eeKA6@&kwWD zn_qj;5i3N%ZIk|)JI!?P%Q?{EE3ulVePE;B&R3oQ+1ZWh^XJdW>Xj9Y5<2x7ls@GA zWYURZOjd2UTv8?`^rtV9cme|9D#7b~mlvfauRg>8V0C5148a-!PF3pIejtBfNyP9O zD@b&B-_(b2+eXCHE7;nHGzYF4-+}CdlNkOI9gnK5^oNo4KC> z3ISXn??}6uL+1_ewsyE7B)I}C?HszgrY52OOHkgv_=WyTOvb9y&yU-V1sRziz3blv z4HJ*%QQSSv=i=hhohFYHL@WQ+-yi4KuU`S-;a;@znLj}KYG`aUA0X1w)MT`pc?Res z*+CUy`Y^z(=DN@M5_1UOzmIZqazZu;RLnSF!~Q&796-k&TJ?S@M0@#tYJ$E*Y~SI( zkj?7yVu`$_y9GObVy&GAH4U0(+Uwh`?KM_R1U0=Fo+homoB*i!?|(yF81TckBiLFr-6dR-`h%8 z%v%A47@0w->htHd!_DWrQ{IS>zmzd3yCL}Ytcxibm&HjSl7XX=k8w=PH?D$^m9}dQ z16FUWg7==yf+wt7oXz4OkUbh$)E|?R?&;}t@d*hxV4ol(2?(yHmR64AmPyh;v1g=z zObj`&3U3%ZtOng@f%*#o&Uu!jDP-s9SObg@T2qnZ7Cm$u5BS{UFc3JcW-h@lcr#RJ zDmvW+W0a+x=S@)&C)AN}eO&Bb*eXfs?x6G5k}A*Yw=0jt#AFVX5M?Gq`P#-@k096) zP@(}JKD-7EVFEaGHK`ADS#R(Wq>9kwTrt4*C~w|8nUj-K-5Og75kT%-mKyIzTKS87e0Ue4NGo2&7_xiB39 zD+C-<*4NM*zMqd4d<(|I>({Rr$dZhQ3RX5Z3wAFR08TzC6aVmC@|iQ<;$f)(g-s`n?C2aSq1K`GxLb;_ewQxfKC zdb4Bpi{`7fBO|IM!Jt{(0YAyl0w{1#F?5#!2xVL2K|^^^t?9fPW>sw#a=m)SnB zWJGO6+_O$iTob(@Tq%#U_i}k^D$#0bSTT&(vEcHxYe~?U`gxq?)X748LXOuVOTyq=acP2Zxf|T&-pY9l%{?ouCm&LtX1^Eqem+ zp$3Q{9qn>xpP*7~;nIACnAmX3{Ek`AFg5z@PN?mSk|4Wf}HQJorVNQd{Z5fs;a^SFIqtN+``DXv%s5w9BE zu(Xuf`8DaiuV!agWU=x?Ai{#`)~&}QmlQ}0WblN5R0LGKYHV&6-TBqbV4Rxr9X!M9 zMkM7&w5+V%nGuELGAeD}l#OK~y(Xu#REl$dfi;=NXIflb+ytD%y)_1B>WPFz@A`I@ zTDgJs#o?nDISL;U(Xa_>bFs}4u9yHMSIQpvUGl6sxAK+1mgNNN`Ck1GhG4REu8C(6 zfv9x5WdjO!AgbQSQdzRac9^-chL~0F+0U)r_1U;@wY4d25fKq-h(Vj`?7^U3p%SP? zFM&+Ilr3Q^^x>O(wo7y*c@NyrKe4eXkPwmk0`zJedvVJJY)V=dot9_0xw)(v2nv@6 zJt6TUwd4bgew5Ko5q4BxmbyAnM86LK0iOo8x4vOaE)DtFu(jB3Z~BR_MIB%ld~ zJ>d)Ji#Fs#HOOuP!C9uncKLA3DRU6DfE6PhuA#;czl^@CnEP<9T;j_$lJ5A;6W5PE@VG6hL=yk$ zPo6WML7H7FJenRKe}x#Z9UUE@l;n$}L7T;e){|SvgYwG)y)sCl(z(1l6r=(`PG3Rk zMhd|d12Y?Xj|^C_G|qq^x53h1Y)T1^YZo=YbnV*K_akz^3NXSoR(^a15hk^6ePyKz zXruY|iUzA;uh<+Lhw11yaLi;TaS6FBehN-ky=e-f^#HuC1-1jVdPUiYJ+x+Dz&|&5 zcvJ`?A|rhYM;)4%BHL1t85{~4thfa<;nt}>BE>f?jue``#m2qp0`TZqT=ra`^KAp7 z&e3TlV%6__xDg6E2my-@R)NWg7xRmzN98)8v!t%!>2h&#f!C74xCGXY5bS*!UtaBo zOByXPE{E^H?w9Q;+H7iU{0e9-AR>Ymf9#V0CJD@8=rh8NA8xT_AOeA>kIy&ggezdm zeueGQwc1z=t(gqeFht*E0x|*cL@0#k;(?)b>!oq{Yz1-*4BZu{zy#biD& z7Z)MA&NtA@+S0NHK17c7yc~?>N7k8$+X4FEHta&l*oW^bU#d&ueXFleBMTu(6Y{>= znFDOEfIEgTlOG&2Dh;2IkZTZKcm)Py(-coHaLP}*?a|v{L%^-^z@-${JKT!PGke>9 zrD7@cODk@{Vc3fWP$HxP*XY;J#z#O7ZWiA4su?yv4d}fea2H_J1)?Nq68-sx*OUs3 z?%-G2t!j#!be?i0cizSTo$qoT%*BgLOiVMQ<)ydnF9h9Hz6$&3A#g+Y96%X$#g@~o zt;=*i0C>g4YvIFr?>j?>{4qZM*$^8LPJg9KWlv~lf@mC!ADc<0-`G8Ea(UT*q|_D- z?X}P`9Xhop82oZBHs_&r;Uq~!<#Owqug+&xPC&=UtHUO}C$rIy=>LGb+|0eN-j(7l z;MHl11dUzdQEh=?-^DXHWM5|A+Ows~q`XF?Qb5SvY&cwPp#10Pwv+Mf{0w}%zqm9# z?EzJX4eZ{%`d%e- zV^pwyG@t#io6IaM*vW7Ilz`X2N&w6>ihM(VNH>b_M*<8?a%70!jG*N?iG8bDYIDxEZlOCRP^LymvgNlzWw5io{d~SRBRq2r*ctQ;ADIP2yi`=v zrRs8;2T%?En8ZdubQn8uN8QXpWB&@ZF5_?N4IN7ZA{$aUU%!4u%C{-_Zkna+kw~IO zxEEDMgoL)8gM%iF++;w3Jw>lypP*CB{q`wU^3X7;f8(2u|?UZ>X?|Bg{& zQ$TtX0yJEkOCyGCbzNOo@^sq^^qs;+Tt-GlI>3^QsO$Sc%YmAnoE!(5eOgBFcn9m$ z{tqf#9xS$`f{7>X)EdJ-c4PS~4iFt2@cgWjH)5s;5#)iYQEK6-HkP5xF>dnBq3@Z32k)Qz_7eWa z*>mSQoQ9$4iY|UZq<~gS?l>418i22=i+(r6+x-Zc(gKku8#Yixo%}q2zK0;zF=hhx zQph(5`rKOi&;c>E_;!9?(HMs5sCS<&-ebbTPgUPIhQpK$oEdj>fWoX`O{Xc2K6rB) zyP7tuEOw_zn zmK}BFx7>k?drl@z4jUTd=eXwVrWu5In?Wbghy?3oz0J5_7ZP3ZCRHHWRfFknl`$z$ ztFgrS25w@k!^T{R&j{#;Wrw@-QaRA<^0@qCsUdih$(RY-#BMer#HcN<4)~sy^_C(E zn6jDOn^$TNeG6SHS_?tnQ7y5;Wgi<<7KA&>C_Gh8?WH(fpy;oh0n2_K!Nv4id%L@u z00^p!pkrNUVUZ3YifjZo!~-^hMx@vkQ^^vmS&Doz5n=x35d3kJqebawUp|y$1Gm4vm=1ps+<) zfEq43Vs^_C9T$9CB9ht%p&J-M1WyxZWfScSs6jxGv%PQ*3+o~1C?JlXAtxtSH7K&4 zzY5IPgzfhA>!{XnwmdG6<6D6ZJI)ExG$m66oMxXGZ&Oj#FOd#MMa5D}aRh)sKnN4B zkjp=QM z;e5jo(WPj`G`YLuegTM64_nBH$OSNmoNXrc@J`{wcb5^-oSqGC;04?Ena+d@&_l)1 zm{UZtD~2)BQcYHen;gh@1}DxRE6l3INMOU{_nU3+~>5Mj@l3 zrbY&W989Lfd7Q8_r_?H)RULRfpgjTlv1TpTZ`7}96S-n2yv&X%M`{l|{WK=T4sB+r zG?I^ok&Tr6nI99QD7rPW+`nS#`nUg02MXHLIAlJTZ$05G!AkSVTm^7g^m4C&F%x9{ z5(q9d3=Jt8TuT@pRvEEPr z$_S)`)SOnEgYo5M2A_cvYg(8t@%1;E;`ozThsx-`ZPasZ@9aEgGn(7j>IF!+0$3d2 zbz79-mSCB-4HG>*Hwt>$uG$LEX9dHHX(wdiA!? zJ6~V6PnTiuRW=<;I0od8-HMKmK3c2rChA^K7GN)A(>bowCn5BAH@Ial0PL#{b#pt3 zNn`ET`IK_#A-fq`LGA;0u(_~LHO*cdsy4>_&N;KzXl_1OQh zrm%~Ieu2HJ=e++~z`!YmEK*lcuoxoGz{Eokzp6d_ZbC1K2nPy;dPH*u2{we@7d98M z%zFoB>`A!I9g70`f2hent%BwOq*4(YA`+qzL}|cdxAKXxZfIy|g>>M7pr9nEpc=!k zFwaV7Y^H5FXj0L6zOFf`N?`k`P?5p!z<%%uka=wyACQ(mx}M?HelmE3)Ap3<3_Nh)__+W!eyYaCA@LbT@B z`-1ghjDDj&WaXv!9k1LLs{;Kyp*|s&Yr^tLUhDh=6_-elI3iaLqkh*6Xw==N!#&wJQWMBlR6agHbRXKNzO~UYr|5Uc8r`IJS zqVpUa(}&yNaM{TComB|BKoqO7vAL@a>ilQHGaAFNOO97wWNl?7V9;1lG*^5UV2>Qz z5)4y%pAG|gVP#~Z6Id<{b79gjMMIJbl-cw;80}|3y_00i)SDhTV@p<`K!+I6iEItS zVus6a2>vt+AVeyCtIJfDg4;kqu#>+rX@?u}^6)S|uR^t2?C$K`prCj_VEdyAqX(xo z;Kte>*eh?7)yhkzir+=L&nVF_F!*zXT(fLDUfCT-i75>MC6-+Q{rD(oce4s%XHtgS zefr3mx&7dT#AgwIvQRd|tGRi3vc6A`nsH$OnyX>L(!LYJT!8|Jw=oJ13JLMx7;};) z*n;%r6>K8bZ0?wrnrhcdvfjBz%zfK`hF@ca2k_Q=@(=!k_0mg!0sxPw>FBV$VmWL3 zASABQZw~yrC0nHc5D3)HxL+XZdx5bsX6g=D!-MCvpbsK3C)IiCiW$p-C zLb~VKoQ`FFDSyMl+0G(!Emqy z6_B_LslluHX%j@Yp>g=!+A^lk`9umMVf}lW2f=p&-Z~ql$0`!xfkQP4=BUEop zSX)k7#v;(W>QHdZOD+1Vak(B78`x~f4(Yw9oA*a(S}F!J*!DoeAHqgm0T}}gLq7G_ zcXg6gt^~qqwyKT#um)C??u!@W;6{W`?gK_Jo9n)l#)MBJQw4SuTO+8Z=!Qe?(|^nN z5yQWG2-sPqs;>h&*wiYV2)$y@qJi3K-)D27azyuoBxIEl2i-#?u=t#)A-s13TimdS zjq^wX1ANO%b!;F_If(JXa8NvO2JZ^y23BgF0<(BFEUr5kztB@at^hauIO6nCw=bmu-zYA{i)zGQ%CbdHXg6L>31I z2Bi9)76j}l-q>hyK-kbz35j5XXq#_rDU=o;*t=UE|8C}aYAz>FpPoobivHmD^wFa# z0MOpRXl}5w;(^>+1vpM+(-JF#5RkXxG+Q6}v=n6cQWC}UabD9k0R%ypq~ z#4VcGBXTkNopYBz8%eVtH?vx2&8HNwkoom_ESZd zo=2eFeA(14+DY4nuQwKB8^+EyoS{u4rw_%l_BF645+&_9NJ- zsULN13E||%l&;(mKW^Uf*ZyJe_+R__`Z{i%B~(QN?iEn2gg#q*iX!C1;GzL;SU(0J=u5tnNoFm16q z^;=hpGz!dwA)wbN|SIZOUT?+ebMjw9U+1oOUES7$5?7V`p*hz zu0wTX4flDcljkKxrf&~59%e`br81%Wm)ef8% zKRp=}LE46mL_ScbHW2mt&w%UJ#AG~f0l1R5>x1IrqQZUDj&W}&iJ!l)m>-!@_`@*1 z-mpJ7IB;k3ioH%rDQHl(zHa3xYC#0?JwJK@4(8TuNlD4-P}rm2zI}rr5-@c|s{fezkUHrA7js;p_js~37K0J{0}c~jse?8{4*Fn8FGbgL&{zBsiXZ5d>k=14 zuc{R2^bjX7I@%ABKHwCQZR*JL$J{*inRoBr6(>N$GTvVb{}|a0k-CJ5Zg$k#E@mi~ zpZqn*)h{Q0IU_ zY5i9B;BZ_Hmxv^Mnp^nO4IX?=tbb_50_7fAQ}mT%!H6RNA7&wQ5@6WT%(oe$7bb5Z z~Omo zq<24{yPqMZQ8G0E%Y|foK>^VMTdSIsTh*P#*?GYWM4cG0Ez)o%Fb^G`-FI>-6GvZz zz&|9ls*8|>HefpT$!y_uMco^^rYQQ0+^FUXkKE}$md2yIhx43&$_@8%;J`*zM{5?d zIL$DA$Lf0jfY958OsZTC+NR-Q5x?o#*>{lpKx_h`I&hSqL-5ZItYU8;+{N!hAXjSK zg{@fwxYj6B1B8NV5@v2P@4sc$z}lrmcNL3_M`23|aR@+2ZJAqsisF2^%ZlVJE|T8s z4|5J14(k_`~raUgdB*^_I%cfn0fPx;|5=02u7ax>@o(k%il5fhh&nE!Ir8*c9 zwvD2Y%>jQ$8KDgipFjU3fImPFdy>ZQuUGKz7WkeujM&}6((*I4*UId!gZbvj)fomq zgX&;?x)VPmykS2s-toZd&Nr0Tz*GjIQMI*@8M_LoRc)F5no*`ex0_06joP2WBZGpi zhERmNIRr#XMjq~e`uS5kr3m`UzzAw#aq+HCV{5CBfWWI7@_T}r)9^v-AbBcVUI$5d zBpallKmfh+6MuZPfY!fzeJ;cWorhNuaGs9vs zc-Ov$i5q9TJj&^?PF-0*p#cJ2 zjspp}ngqBf6wyOS8&9#JTt@amyXMv)rTDv|;B0;H5)~Dd9{HA72s-``I9ZuvSWg@l zBk&_D!n8Q=qW&FjZeqm8^vi;i5HMssuBq8!!0Vozu+lgeJ5HG4?^2u^AdL3yun44@J=e z%|l*!6LC3zW{l^faHBZ)V2+6ta4_D0+Mz*0EKI_{%R7>?*2Io#=IJ>Cr0@{Z-`#fc zF+g~?_x6;1xnQS)P`>$n8B%9y4T-AvO}5lgP&7ht+l*4-^o+1wo*p1f)&b-C-_bDf zwi^JdEBAkSgIcesq(lVPyG9=Yu!dkS%X}RSi!wM4QPQxnm4~~u9|8k$ z!TV*X*gk=I8tXprDz-*YIyyDZ zMcD6iRE=D8uowErKHe>TV=hT%{}VTbvqM7kr;?A}MdWb;2@}Y%7^EtwC1c$(H?+02 zXYN%Hu98HEfH>pM7ukLNVT|vWHS!aLm^lD z9Gqqr0%4(c%3K5z^KeMfKp}-I%v#Ozz+3`)4XC|A4#|3-Vas12pZWz>;wPZ?omzuW zrf!_|+f}qoIQ=~A_8jn?S@pBWvm@;4U+(A$wY4B_6+*AtSr|Z}0?9C%w&)0q$Hcj< zgMJNZI?ixzNsxw~k5A1(tkYl2asiBInFAM;nWbf*0X_XqgR2DzZyx|)kNC4J2-EYU z|7rqB_d4iw#?CK6*GZTFD6DIFk;Zv_^v(t-M^&(!+yTJ))b$iQ|S<*pM8olrloCmg){`H&{m`_FwCn% ze@!-PLE|pzm81qy!R2r#=|*wO>*;_#mzMlM zV@@TD=_B7oLhO)!Izqe-IA+ZS9g5;$5RT7;42AXT9q+-wT1^2Ml8h2Ie1Imddc`XE z67o8*f~s(nExJ6?`pgf+h_aP60YMvZ-iv2KoA32wgCQ+{%qO%j{KF^Se*q943n#3r ziy-oZ$Ufk^okgP59gt$dOub=9(sR=pjsR+ifjSajPYZYgZZ?h25G3{1L*rv$BAm00 zEruW^@@$f$9T!Lm$(b%)S)AFs4(Ea(!}}PH-hVpQJ5vqr919W=B<=V%M|Zyf9Do?# z(7F<&$-9A+6WGptzY$SKl>q zcdS|DA(1HKI|P2JhM1Tb7GlEqitd7d%}GPkH0Q$q$QUzQj1*_esXw#IpkAi=PhleO z8y=4VW=bnOkpvSaNAAuBKoPvU1&E!5g@v(Ce~JZx;hYwvH2A=tgXwP7dSlHs6yUK+ zAJLL6+*<_@ono~q2kc`Lf`%0vCDH5dQXn~+&%M?%9;rAF1kKZQ} z0SSxNnvRsnPJ5}ufGP%(3_b}7oevi{AwA2wy1H6$il*8efRIiX<_)7B*kc+k5WWBr zLgzjk#2YXa5^Z$N=6mnnq@ucj_G(@|PQOa7{>v$XRcl;0ckZ0aP`Q*TqJE7gW8!5| zHJ9c>k0q+uLmErG3EfA1i%NAQyu*YLanQeHk%iOml|9a001!^jjN@ee+X2nt6uUnh zYtk5oOxh=EFTqOaeN@(BfGKi!4&dZZ6yt3GB*-~Pt~2=JQ#u=vHzI!4s18AB>vrTk zu7=NGCC=j4;tbwstu^!BGa)b>+F`LG02w`pNhy_sNP!m^%AQ-&tGN(N$NBSp7z_*M zPun~$tw^xYgm8Q#`Ca&aqv1qow04t0@-jU-SrGL6gGwdnbLjJylub|X5-cF6k6O?GuPqF!5cW8 zgs6cjMD*$vK8P_vngvJjq_|s?k5!l3_3w>?Nx>X$3-avAP?k4{QbFQ>7rAiOVA4IR zy{lRRK4_GCUS<@iZkOvIen|+6>C^w}sg4NR)fF`|k8<_#@u}oJ>9$aBX~YNYwK^0u zJ>rr$dqCRbeO1~KU;`tG;?B||NRCt|8dg6jJ7n~OD9dRqg6lq_kaGM))TeViP~ecM zSpQ8&U?vpgEkO_hMC{=;uzAiv$c4Q}FAWK9!E~xF0**oato7)9u@2Vx^UR+v?=_a$ zBIftJDaJ9xqrm-FYos{_x_EVW;Vh}E!J)s=norA8jJ6MyHF5Y;ovmm%jy&1S z1)Eu%!eQTp<#(toP;0o%UV2Vv0oKWCd340p>)UUi9au>Ij?N*7PO-p8tBYWEO#m2S zpENt&R$|k%;AIOcJ;c6d)I^<~E4ndN7J{J3_~5c(>49|X%=ELIjTmb8z5NX6u@~7* zh9R%wGEi#EaAZSwd(>h6E`$X|Yj?M|f535yJX-QBexDwML5a!9UG41b#7eHS{)2D8 z9C`p;z};ME@dVF{CcN=6Q%Ir(m^k$*!5wgC5@ttSw(B=;d^He*--QOOiwq$9W$iZP zEGxX;^Zp|)JWK^z`egBh6U^@#8}@r45b9eyTWX5K7tBHUyh;y)raOhz?Og9?0P6!?-Ku<5RM1EjWA5aKcxLKaF|%&)KC0vVYtIik@iuDMF~z^JoakrR|9e!vVx9=-Y1QNMaa{ z>SpE#IKYD|zLyu@VrNGlT5`1xI%D5d(nepp;uR2TuhxO0toi+u0GxKpx#ORA{_NRH zb%5Y9)H|-=3an~X0UlQR3Ku8D6^O}AE<@`jOOX9piR{S_rBu;Nr_ti!&RIb6Ybs) zELl;Yz2VmZTOt9iv!o~6V)6+*2SC1Xby>dL!CIpQcx0j>HfR&b!(psjHFSUjbi*dm z@QI~<%Tu)Q28Zvyj!xo|eS;18%XM6&BOCpq0b3S1!w!%_{{tY|x?)=o+`aXv9W=MJ^1r8Yq5ug_rjql&uglS9; zo@hoLoFU6nSk(J-X0rCmzbF$Mq?*b=Ly^kKs@P5KIepI&iEowoflG+QeM-6o3YsB- z00(}oh$}yRLdA*rzm27??uV#ze~=*vDN?PUz!ClmTVkPU(rB(bh4N1Tf(zciK$=`e zI?~S1n*InJc&zYkkbs#Dbsy-&LgxP(i%0>N&5x>A_vB;MkW-=I6iCuK!jv&s&J9Z!LXda5!hp28+xF$= z+(2FuqYf~e(=sPgbPfR-cey@UD1>KVXtZ2;%JbRf#ve-I@UQI>QMNM`A;ld9Ko1QE z{DnX$O59mnTSFd>08l}dU>@8R;KqjGF<xqK(k~ZsT@LgdrNWSxBZZ`dx+4- zc7ET!m>Qx6r&3qv+dWXPz6gnkx>*CL-b4A6yO`zb;saV>llus94rgr&^Fa`Q53sGK z+-HQS8!{c?tq-XrE0a`eL$Mx|Zu|TPeNdAQz*EPCtv|g6P|0s88KtP9_rm?}S6c=C z&NFE}2uux4X7)EPX}Kdt71Z!ETpt0nOHN`Ly2ujR))$7w=6wMy1#0xFnb_kp`(3)H z$o?pJ6UQs-w_R0AWdkfkV+S(WLHDMuh-uIzpuqeUgf5BhqH@3^bA(pVhzlB!s36f^ zNxBmnB!E!wc(3$Xoq)2u0X>IF9l*Zy1~456d(S!y@k$dk>YvlhyMDG0I;g;l%3)<1 zWe0#MN{oYN!*y~RYF3{RRujbFb}F>Wpz4zB?Ebxb-*)jqZ->4SkhDRyKS_EshS~ce z^mZOPaRCGQmXF|S$5S@k1*}vo-1TDtw65~rON=7Q1%OLmUmrJC$EVl*0oL4`_|T!8 zl?7-Jl7w)DE2&~8-hgtM%fb>3_R4tOJc*h@V@8FvVg zccPg>Se=0nj}T-4nVJHd(dT1UDEkjDWHS5nUCgV|Rp=R@0R%h+C8v=G&`o{=Q%9+? zW)I%Q2|VU6pT9B7T-OGKnMGgtv6P`0J8Jy3J0ie8yvlV3)urjUTP^gQ_F~fB|F+i6A2E zK+H~%*x;@pTyF_Na`W9S0#reO60Hbl0+iO?s%1ou zW!CURpap>1S1p7Tm|IZL15tdWee^jbMp2vp3?Lx81^1%@7a=m>kWM}$8~QJRxJglW z4M@g2n^8r`PIqvcg9-nej4a-C&f=eJZFfi?(4saaP@6N5Yr{bfwjA!wby8D-6u=<+ zp{@7%W~wpZsqX#w`k?a%>RdVrt+|i9Z6y zL$&K;0d#KW-0M6>=kk*PP!2K9+9ovdgtg{0Bkp5(DQ(9;Nlnpu}je*}@HKlXLT^qpH`wUu7W_#N-=9qmuBBjnFDb zkAq~0C%l0kH*wj;07)AR7VnFF3Wzu~J zQ3H6%jm95=G4m6h$Dvv3rGH2~^Fh>X3^C#51yewPdH{(?G#Gl+=JGj&oqgdw6g2-4 z7N&(Z!AkI)-vO)&If~2gfty3t+#KAbv*7#1jwRGU(@Zqfh8%#f50Z{PD7>`yGy-dj zERJ*SKFs>C$kqoaYnnMtLWfiwRjfFK)t&%T|C-P~)sZPy@abvr7v6jVYnuG*G;0p` zjIK5NH%(}*fdb>|2?`RD+tqc2i>Lqy)N$v1Q*=uBVNw}48eb9V8yL_-n;s-E6&LtX z8g;sl2FlnHpk3lAr@+~>`d&=}{=%uVXAfcldM8HZ2JQsnCR14utnO^D2hhP_keW`Q z|I)$&Vhe6el&1p;1s)iH*Ts* z%Ltr?o5c>9t*;<;4Xlh`rnLO;{;>X%OXC?3AO!(^AY>=V&=!NT0}i-`rGSGiUdI|p z0f5i+Z{$^&n2d?(0k#ifnlSpXPsD{E8>mlh73x7wp%EGdRrH{!my+8AbfMUo58jy?On@=3~+^#P;(+Wk4F2%JbEcF5Y= zVtwezT4_JK`-(@PPIS$m*q&+3LWr(gZ32R!A(n8=!k^U?#tdF#vUA^)>@)j^3VuoPKKC3tyH4 z5%Kg$jL#kD4KwS)g1WzGIZ(zs@$OSha`IW&i)645y%5nOtWuZF7szW?fbF0h8XAI+ z^AR=U6q(spXw%^75Pzdg@VU-uJD6!7Xgy;`#K^$@+5~{Jx2dVVtE;PkhqH!gfWvJr ztRJ-xYi#_84-E}I6&ooDEaS z&!C@CUDd#I`RC!!kkj&n)M<_hHaR)D16q%50M2ciog?n-VlI^vwHDE3o8GZ!0AY;) z+^m_yF$rl$joewYH;7jgFllaOlWq$sx`?{7+a(g%nVEnl`Z$CkMspV-4?+%nrC+LM zCZt5%1%Q?Vd@lh=Q_}$^NXN%NC~aKfb9+4uUI`$AJ7BKU`tqTK2ocm4co%BaP9tvs z5gG~9InD@-1xS=Ga)|~CZ5xFi_pJ@YQ9XS6B}||}nEMYvi_?O)>P;);Bo48K9ykq% z4a?odor;oD!zLWO9A3A@?5LqhVR$hNZ_I{pW%?wY$>dW?adBm3yS`GFi85wzwjg9%Lx=ew6M)Hq{!OzJB3xxm;F9E|E6iIT7 zxV~Qp%*aK5fvJLx%Ieqeq2YIsSa4$($9KixXhBz6{h&<&bgX^lp(3x(HxYjQMNwVssJ@g9=3vK!tMKw%%E;?gt z(gD1j$GkZSA!9g5nd2*FYtVegO(tUio3ocBu!Q}N0^XU<2DiLAEEQ;XA#!$|o`h&F zHN{dpJ1DrJ)vwT9uh7lmk3^!Ll93U`3GBGbHS%s>e{6K)HypYR%QfJF(JTi4>tw_h zbTaw_L%zPvp~VKho>JEtA6;MYV5;1=mfZ6lqMkf?;xO{&>EN5Ew4ayP)wHZ6v@AdD zBhqpW{FsuS?w{elF+LNN;SwM1t~R@hljq{*t^_9W*5sfb&E&W^Mz?hwo#E+C{jDzC zT-O2<4H+33F#dMO9DQd}FU!;W^4>bt%r~OzG|ZStnAUp20r2Ll)Ud0q1(1BOw)2N9 z((pvbQQ%`I$gfdxLB|BHDQb)W#V`iLd<68_*S`MGQFzBAWJXiDu;fyIU;W)=^*>pinrdl=}lCS8>D~g9wm)TGL*YKW$lc+Xx_g$j@@Lfhh$B0ls$9{phqr_3TYdKFc(>fOb8g3yV^^G z%b$LB+z50A=#noiG*U z1Rt#m5~$YqCqOm6O-rk*$z-61PLPuR?f||YuXs1+o2~7(ca!m^3#L;m|omGZE?P5Gj7odTk{24 z+;9-{nKtEtQjqpftcfgjU8{ubvSZmKB_-vNf@2CY5T|fKh(iX1bI|~eg5Sun9;gOA2$*gEPe%k&8}(eh+vy4+f!FT< zBsaL}t<7m-p=(7gk&*47>8cqqrIUHx&$ry*I1qIFLT`et!HGBhh02k+D-rQP|W;-0L`F_uR87;63nUKuo zh3>a3yD!0G5Pr0|M_t|MS^+X7VQ3JZ0nYN8nwga32mV2=G=p#$fIj*@ zpQ{;qfaSiWQVQ@gnL}S~-1-Jv=JV&zgOSctUYh2Gr-xI*0(Y^?=G4C;)Wx z9SEoR1c+7;p*QkqfbRXD@v8GIEMBbX1@xf%wSEpugRWZtB(g3BkukU1d@LQJa-6&0 z7tlB0GM<)S2~HIb5{!5$hOA6@wlx$dE<}PELimJ1NIwRM9Tnm<9R7^x)ImulR&)=W zieEXCRaqE>U~K;d~KcN2C&P_EG%Fcj!m z0Vp3ix(u=E)_lI0{RR?@Qw2DGM7)r-`C}GYXE@;m9RRbr61CMybb`zi_9=imykMEO zJb?|BUyk?Nzo~Rs$h}y>f>b~-eQ@*5esO9r$jEGRqq9`d0^Na3I676P3f7GR;xV>) zhcv}Q86t?&A20>@Q)WundZ#NP;+oBiF@RP+{8XW2D?o^i^%uoSKh3?5*K$9Y!A4*S z;T@9Gh7X*Dke$nb$NcP;{~BBgIPhawKN9A0xnXO)0fH=B7jPx(u1!RxU<$xT0^6L~ zZ+0HLe%}h6qwA=qx?|XMPMUDjdZDOEj3VwVHug`5iUW&JURyLb_!T4nFdR#&O}&rIP6ifY{BUm?X^q z64;x9srTcEn}F{Xr$9ZpR8V`lEx6dBhj$4UGTeKAOs~Lk0e?gB#UEKPqV=DF#ODi6 zL13BJZ{`m`cka3mQL`uVEeyl0B%%H$IE9YnskbjZ4h6;P5eMia^9Pa$j?D$#EiQ15 zBjQv@x912MbiUWYjzg$6zh76)8aE_=TN5VSap{@oJDeUC3 zIi$OJ8c2RfkZ%7HB_aaY0Xjsl56wb%hXlcH;LoywZYez=)&U=&&F3;I(F;a#Dq;3*qnxx1Vn7gu}CGnS|n-$8v9a)Xyq^$LjV$52vB4|Ra4sZlH}EC9FS6!PgIVR$+@B?aM; z=&G(Dbq>YKN~DJK=zBk)+%9Co*3kh}Krz4!&rbn_j;iP^32--Jva&dU;+PUbRNt;H zC`aDC8t(YxH5ej8arMp*OX{t#tpgxSOOH<80nDUvsxDR-B7IVLf|(CQbmDM|1b8%3 zC?bTD1FRt9Tm_wZ!ITtnvMqEV*Tb?Ja1!V?An!UGvd zD6yi0Y1w%G2ce@lG9aEdu-K}_uGhYTlP74I zuJr@T1P5s@}6eJfC83O+b;97e$BfWZACI-U&( zGHxkDe~i;zjJL=5(aw3G=B$LRx>QsLucilSU&l~pGj`C@zQEmq?MBqH7a_MSD7zP) z(Vg*+W5_+|t=iNLD=Z-KVPJus$f~^qC27ZSW^Le`9L7PkZn3xsnX+kn34Qo#_37P{ zYT$n`q+ZAkIB6K(G%*Qr4ax-o0k#Eg;^hJdTuA37_9pcvLTF$sFptJ}PYE#P?kXm|hSq8qLsq9iYO*qO}CtUCw9pf8D% zs24j}0qd|}sB@SlNE8w>pe}noT=VrEc!9jDBeAh>-rSDL4*}0LOTQMiKsZLCU~IGc zU>O=>`??`6Jombxd>@4t+#X3Nm@5&u{ScT(3+_!n&w}sIWy-PeVbXB2KTdd$u10}B z+SSnA+&4UlvNq`S5P0$6;hKY{kZD9YleZ};-NTa*;o*G;(3nBPH89qIygI=jht7L{ zv8tk>00%%jJ0Ch7xk^{+EPhzUaQ57il8}HK@@Sa?G!^5`|M=bwI7bOitEmjL zC@pO0W@Tm7gA_eF>E(xG)6_bU10&6dJNo>}oWX);t_xuY-K71|?WW(Yf6-me9>_l)J5U_oHL{Iwr>Q0p9OP z_y$!HHYl7~D^3IDgZ2lMM;qplFf|JPDUfJH#<-kDbh6Q(*MCSn z`h&;6yXPM5e(cmgdv5Liy#4Q0&)s9vc7K12{*QM@zx>}}cBcmO|K{8%BKJ1B1b4ZgKET2{ z4;w@0Wk`sWnAoSpQXK^a5(uQ3%f#bufeC8r=vYq50JSIy|3iF%1XEGHu;0VQvV`Ci zot6crny8%$Gy7rZSG)yqY=m9ZvUFqz_?J%*Fx02KnFeuC8Fgk(t|bUHl-5 z(Lmp=wX_%6j2;88?tGazhLqvY;r{au0|VR;IJ%Z@6~lP@UhVg|!psJb{vTHv-GM)} zF8b5|?$q50`d{_4I}`tps-OS0H#-abzqWW+(*IZc?aqY9zc0ylEapISUw!FiWU z!R8&b*j{Cdq9txOm+n9z{)$H7-a8+kG29sm>^;bPdiTrEht>?#t#6}C=Swivcowi+JsG_9hg2pXc975x2O*4^(`%Vd;LgvdIxgoYj|Hq%oo zM_@c6*n9QRc<&0GP)+F`@^3(<^n6Urr0- zmEAj6=k%N1Q~VW?iC)|}zEd=C_Z&}f^{sY)Ngv8_$YB9RQTXcy_0IF%VEpaj{P9al zva+2|Vs4QBdX?*I+P}RYQlg!o8Dm&Dh#jc@7<~5|HyA@xe>+DKm;ZS5+&vd|Z}58{ z`Z>%^f?uy%A-eNbf!|^3AMejGY5(6I@tG&Q)PMUz zpwY44bE~jBjb}L~{x8EM93mc&-1qyX_U+6L>4E?9j4)-NJb0SP{@s-*56+!%=oHE8 zA4RYCm+!uoDCMt(`tNI!aEP!^@{e2mzVCl~D|(JP`%BuFe?`7mAMFZZpfR?)<5dLT z?u|V@?!3Qfpi#~ri?usGBYm?=zQPu&D&enRtD979xv&4sA2=n+pY?U78`JzKU zUEFV3X4W85DBm;B^C(tR#gX<5UITaxD(zIHF&;BjTauFxeY1<5!rXQPLkaz46ax zgI-$y_WSG#Zc{bqDM&kXgwP4*^4m=s-)k;Ky3gWXQp2n`{v~d#|CThgmqm{hul~sM zUDVC`Cwl`gr_n-ZQDB3v8`txudT6YJi^*#HoJ890rTZM+bPv*0Jl2FYv^_N0%vH~q zX+J;OH@cN+KdfLEWZO65o|w#W)ZW`b*}Rx)sQqvX-w*--c%px6k35FO7tkn&f@G%FVGh&9v^R)AMG(KlEi)LFX6L0 z6i_K3@ABaVHcBEhdG$KcEl74hq+C3U|88Sesoah-d*54WR)ikJy0+bQmdU=n_o#*Q z>=s3umzpxHYMko4gapaX*PcDaZ0j7-`Ch8F%F4-4Y`Q#xU7i`**1B1?oGmTzpkDFS zQ(Y1kYIWL7hd>9 zGj``U=3q;f2wRTkyE8h{PzHOZ;XPrlz4I`C48o${kR@XC>8!>v{7BCxXn8!%_6R^ zIZIhw7wP#o1x?}$i3M!oTGR4CzPa~;rk%gDOF^F}>;W(IA6=RTUDPHWyBF?gUrJpH ztQr61P004brP1C#x-Fcd`K%gWgza2a_z&cpO#XPY3~aw{AAe3?O6$+MwAtRC9$*{x z^qS5|kXU8!pHuZsP7_Xp?M5XEE~5C6MhNg~119`(#iJtQ=S2}?nDuY9=KdeFW7)JX z6_|1g+jQ1hHFfJMd`$*HOuo6$80_#(Djj$e^PYQzScjmV6|TAzV@1r0G$_`faI|ZSi`Fdq(S~>4ZkJETqsOQHwE~K=X%jFyc zU2#a?{8HZ0cAQ12we|YylvHilwxGX%`CG_N39DRojU}Ya;vQ`*xan*FWL4D-;(~8 z_9t8_midG${ey4x58T3F-sZ%x3x+0B(RTC%JK|?2TJx`MKTcF(-}tv|!*zR|h!KpI zGEX`zl#_H(WXE)WL5b`o{L72l|9W|E^6~)Nma{#w`GmK-VlK7WqFJH8Q{IOk6%+YO zUOyk)Z=uv$XdkCjI#6PYUZu4y-EgtVDOPAZMJXEcd(gH|TW_o_nl6|v*6c0!{Lst! zcq(EfLDS~iiY{d6=y?X(rN1 zqT;?|JAajD*!>t;U9UeV$fw4{N1lnzILl{)x{aom&~@NcVc1bTKRI`PxN)QD{_;76 z;Xd;TjMj8nD5#+%({_fntG&AmaP9XVAD|h3s0m_9RXZd=q5ff*IR;Tn9pl^vLm&ELBGV8(?0AhVYi=pm$}v@_{{Uv zpR551265)r|Hs?YaJNb1TQYs~x51pZbJa$c?`)cOw{M^V&9(s=n|Fjj(q-pN&=SIlqCKon9eY=>umOVMj)wIE&k`7_r?7+?f>|ekN?ZF zS9`o;l<+d@aSf))xg=2H6V*fflMYDlPN}H(?0n{cdDD?nKgov`Id4Zc>|;#9NL;X0 zf3Dro;%jq9Y1^og{aV?$>WqYgAM9cXEfs8ON_iI#} zj+^`Q9C&({2^7}7$K7$Pvnu)5|KVEq*Z58J8ZC~6wS5*^(7x0VP) zdPs*|^d$uITzNZR)sbqy$3Ol1#gZJU9l72V-4*bw%>=v(!~;z0gY{B_TO0Msc{Y2_ z^NaD=vhK%t=(N;JEe5{d_RulECpv5I;bcmA-@wxoskTFA*nsK2cif#0$60y^ZlZC| zrbWn4>^>dcu8JgJxl*K0)}rfH`{cQ#T;e|{4ien;kN5A+-*k!$lsK=+ zb&wwxHAJI{#^=rjy7vBfvnUJO5H2#FMlhc*^#T241y#sO=o}+`^ym?E3i-p~A?D|9 zzB{!D2qA}W#JVS-qhw;911aK>`z$8kY7c%eKS}8|`6)K@)}pUsWdJkn{Sb zAF}8&zm{Lw^P14=$5+>GZYKQQlwtc`NLydb$NEjXPCHvc*H0B-Q7IRkTt8Z`t*zla z8T>s_vAgf*6P|MD4(+Z)jsxa`b{z8)SjAukRjjL8Ne{;I!#EXwcI0P1SoD$>)x9Rk z;B%RlW8ZcK_>(i5i7{8dJ(oG}1)TwvsCc|J%f59Cz~Uy9P_BL3KAs7v_T^#s&0$_> zNgI5n=kFzRzA#Rf)jR+-2ASk)RJlc1emoGdiFd57h0vGslRspO&2G!nW~iyUp42ol ze-JjD0sqYB$fMeJ)*vbcgqQHrCu$1|rfr76V99DFXY1iy+M9*<_1|Qs1DhMZIRmvJ z;-K^WYR(ljF$qPauX`oE$QHWoxZD+VZtoMpAmtR@#XnQMIg+Ps)jIaHTLe@AT*}p= zi4>S;?fN0wiM1(tM9@^6-n%FI$xp|=IPQ553Jtyv)yEiO?O*MZ#pKq@hHYLoft1P z@f~yDt(qT&;bdi&CaZh!&v9elo-$E2IMho$9JsXP$t4qj?JSQM+SzeHlI4OL-s8U@ zVG-rJt4=Ob>gc-OyJX=f+x@gkXgI`Ph?0baLdVh2WmZO2YWZC|Du>MTsQZdu{_aiZi z!{{T?*`-#Kk7go$EM8q$UsE>aIa;B)*)Tn5XfL?_eL8-bMdh`~=-DFBnA_?t?}$)V z`{Z`WF=B<@NgXJ5!kwoIl@4y9M$;M8!HR0?z~|%*i1QABiEG*S+Tz;}{e>1gq^qj4 z&f$9<;fvlwNCa+NJZj!W616;I#-_XUW;)dy+&g-D+4eq;@h+KZjMjz2jm#?&?l3tQ zBb@HgnQ`)Sf)RsD`4d{*3o6h!=a*g2&nhV?85(I{{m;{K3P3tIK&#~0UY8wZyzvThTFEOTS2p3<;Taw#Qjo1 z>)qH5%_N-2v||IStqa`LBc^mUZ0$~!Wy#RE8`f6M#d%0<#{c+{bJQMw4(k#&N{*x2 zwDCk9#OF2DAO^lAxCoLD*E~PLt!PtxOEUCjCXDiBIM$gCLR*U61a#vnQO>Gvp zn6sAj(F=L}9@$(ueVz`Wm;5AuYCiLihnwq=>f&_>88j!MJgd;%0OxID15A-`yLa*A| zzr()%{*`b}`-~P2F9))p79=-KrRcES5^lMHL28Oo`XpO88LSr(&m^)f}%O4mU>UFx9kOZu0fe4LR@;hVQ~7|aPUtms9y7i<>jQOJ?T#XY6I ze{~&N5%r%J0urd$;RCVGg>N%XCA7NBA1R)HLAq3QSbyL1e7y+M7d9C4yN}yA$Wmy# zj&1d`PqEqh3$~z@$+aB|bj=Ce+$V{@N2Basj|bOM+Q(=7EL>to`RJC*h++V;UgJVY zNH_z%n;D~gsQ;XEU4j9=P?mFp(S?7JAtr{#l8!D`$gS7}paaC`OBL+a^k6qX%hFZl z40P(%!Eb+$KFB~QcOfdjja4t7V*t#c0Tu2ZX;W`q&&LF9ZCu}G-~>8+duW_BvK@^l zgGMpo@t!2|<_k~KfMSkw^p!+=ZzFO9PgK1vL7%~3gdik+n}a$bWdow1RWB1DNO9Iv zAjVc*#)(`)hFP}g0UBuz+G1#lF-#g#0-+{cS)R6G_Gf6ajd(6_ZNRQKi*UM|(R~g- zVj~XC!`i64d)NFjw16pmE`H&M*lvP3U=Kkw{Nii@K)jUouD2S+Hsuv2#Pn49uHl5z9Fz8GND|!#i_IMg#;F@u$ zSv+Zu4!ZDU1NtpL9geR@&ZuZ13RP!U0eS4lZTEpDO)Z7+T`1liD@V7Pteb zlM;D6f?!AkHWs_t7l8moj{P`1el$nro^lrNZ`tQ+x#~@i_6wvJPcA`5;5n~l7};ey98e=Aw5)W0tJU4S zujM!tWL3x2UJfmBXN26L;d;Ac7LfT4z2iD~@aX)4@fkFQHi;i;JfaGUjWCNzdbuW& z?&FVtGQ=7e8IjdZx9!6#E&i2qorbItVuD-f?ii;Rph~2nd)X6cIueG@=@b{VZ~-t( zST-(Xb8g)JcK$13Uxts}M8)y9Oiy7dr_CcF?>#;4yti<8%nXzoM}kaU~h=mw)79r4BjF3KNp!uC$m=-HK2a|kViFJQv$ zeFX_1JC%DZew(zjFl; z8sLTH-+(4<9>1R?2b|o@O{z z=-k?io&+<=2txT4Ahe;hy3kav*>sqSD~=qb+_ovCS4S3!O3$K`ncL0$C@fIOsrN@I5uZ!>%Cy4iql z?Sz<^7=joeN2&+9)~x_TT!p&w3jj)$AXtSw9n?kaGW#Ox+>G2;1nJUvpWj01Cwb_| z5xaYC$u;oCIgh5PFkNpx_wzhrAdzstUaD`YDY$8$UQv0Hme$McQIQ61qAKbpb(XR?{EVX?wYtmhh z5W{H4tHEp-vG?;}dfzk|**G1**t|kp>eHvXt^F3aqJ_3rL+?ex8=r=5bobpB?{etW zgi}Yqy!zP#oE7EZa^V2Y=!>EdK+DoVr)s~8HF`5&)KPqqpPzp;9H0(cln8@?Jibm> zBzAGnPgj>2sEd0un~|?no~#ZmN=vNWloXFyYoNb^4-i>q$YW0X0UsXvIEF@bB4{0R zngk;k3n%o-2~6f7B;?N8ez{%7jrWzfIkB_1c3FI>3o3Z(*ri3 z!XLxo0~qjv1(LQ{LllI{9k&yG4gUZYYRTeYh9MYx7d|vK(jazM6$_ z2%K&R=evaOOh(8od8aAlg7Ng)C>fig9X|3>nZ{$zzbS+PBN#eV@YaiQDI*!VLQ-V9 zyE|J^hvQJR2XM}C3-zUAegYjrGY+;k1p>n&f3XUN?3yo@cO6rj$<1(0lT9(Hvj&I) zYIc-~0@U4<7qtEfjW3~tG2z(j_y&0{GeDg8qz^;aF~S5NN&U-Xw0h|y zpQpp3P6-(tG7!Mm1jFQsb;Q-K&e2$j@C}x>I!W z(i4Ul9V6eux#6nflg5u~%H~^OD2xqVKaV^#BO8fxZWYaCLGv&>klgiS{@AFRx=~R+ z+b-YpGvlcOf?BE3_mlT}B>s@mT~$Pyp4N4~=|IB@Lb>R!ehoRhLKth0UF)5hvd0$9 zJEG=)v?C)I*5HACkOa-IBqbmm@xZ`9wi{mUeBV_&;Lmz44>cV0v-;@8R4Ej2&!=E9 z^a}1=m-95hKN#rU?DS>YY3^75a}n3qszB#xH&ZXZ*l8gh?lOBj?Yz|$HFF)ZnZ`$t zD*^9yTra@Ut!@AH^k4eOd`)(oUbVL|urNRv@FXVvy#gFOqMg5#k|vqyG=UL&#zV|m zV>lUHHXvZ>lPAYLI1(M{q)t}QvH{CKpNjO%hl4d-M&KguG!)q1y01>GZO!zx`m5gy zsWkG7u@(8k0WFEN7i#A;`Qw`~iOy{jxfgO9&2NO~*KXPv91VWb_&$hFxt5;7xj4aMZdAipPBPB^U{ znQgd6Zlet~SvVXi8vrs>$Tr>qC%fTAF$7_Qkd;Xo*0QeSGSfg#S=o2RmOzRFQ^Ky{ zE)om5o+n18?-30!5)6!Sod)9-`ONm`W1*y7Den~r$2Ja7r75E`Agw{Pd-}j)9y)rI zM@R~@JgT#hti~ne2Jqh;!++4zC_RfAzsDe>bSTQ64Qi2$#-cl0jz@E_V5coEMQp?%qGcn zgqw)kvMg>GLHmc;k!`+pP?0mjj5CW9cQ=srs#c1`q50es7`a{o-Vc_PC~aX&=BlI1 z>wHR%*CAthWXsl}w%tknZ~VQGT%kpp`8S8`-=`M`&0bQ}h?hPPc z9jq_y{cX-)!N>EYYud(J5l5ndy(A--gx69E27?z4sDf<71sh@&shGyQ`v?0@)5q+T zp+t`&$s0$xE&zPVJGemGxfQ^;LO7Oy9~Xem6R&Chx5G)8`piMpSJaCxMTg}$~5SVbMp*?-;zBE6E=j+~E?$!;J1yiL}8l~yvxv!e;5Dhey)8r^VCaCPm zw~`X%C}16Z11@zVtefleLRz3~K}GnRlMFfU{RAEX(o-;Ec)m6+aoq>O~b z&}A_s=t!q|FW=YE)9?u|*xBflm^8F4rqe83O#vln^bv>1WRALyh)Mrg4a2U40TKT2 zzg6I&O*=q7C-iRm=pBH>&HUiOI)3%%n}!5XEO(!2B- jF$-qAjw$6>)1-KOOe(} zwI6r5){UkgYi0J0>!sCJ#QJqu-^ALvudy?m<_^&r3mowZyMZ9`S{;GO#~*OBuCfh< z@T!AF{Tt?Q903n%Q2{)_U>29KTN?nYixM98=F|ryZi4{1wx|UU5u&E#z*G8N)%;YdX|41IhrX{VxR(T0NR`^lr1o(c_nbx}cox3zwU2YBDjd)Pzo z)NtRBAI$C6>WkL+325bjEBZ4CPC7brczHfiq<232!-o&NLobyEr9@U0Wb_cbWq^{r z5Eo>?+vbZQvv~n<&COpsB5YviRzR#j%R3tPVi1zIV{uD7Dgi=^H}UC2;Ay=$1$jg1 z2DFa{AJMJfdR~YY{Q0#T0)5q4{^W1kW5@|ND%@J!HwXhxYsm5=r6Ot@=fpofp5jM! zDDpak&&|bb=fUoFk(WkD{7{k#J?#u^ZI-_EA3TuIfgI@!llv^wOmKejY1Is!-uWH` zB1DA=2OL%Z3CK2^IZbKy%?6|Vy{3*e8J=Pyzhu%3u}L@pj}RS-MeiW?P9x3)!AhW* zTn9JN=cvm7VdmYM=LH}ucN`oXzK+}VyDk+Vm?UtsNSLFSi6&)v|HVN4{hehk6Ou~@ z_j^pc-gUm$%@w+~$}y#D2+{moe-Me>6C$Hw`NWpu<@-bmxM*p6Ua#$B5V#2=bTFc< zrRziN2%;YL#5wz%55l&dFI^sV=&aQt2fkGoYOvS{mV1Jl+82_e<%q_nU^F2tfpgeL zXFg{6Ye?zKF>-zbBO_+Ssvy+)k0VI%%twmS3y7WwIMJ*SnirC~R0x@j!0ZtAqdkdd z9^h)%Iu4flL_@a1*cO?4J=K>mdLywP&Hm}oova~9Gve3L6?)j)U(ZNMIXE?OZ z`smn{hy*W){Z)qAnMM(X#Qx1v4d0eIp`R9X=~Y}y_k4MZZKAYL_XQ}ed{7zhKSTZk z$0V{M9S+0>hzsYs)8=8Gp1%>*!qf@?w~vXe)X3ifKew>zZ8CaJgxd$3UQ^Yl7a%m~ z+`pz1Zu3M5k zsS-+}G;|vyQs`h#v)8B-Df+D>!-o^<V&d1%&W`fIIHQmblyIF1Z z82JH4nD7X-uu}vsJ;aOWIMa8!8A`xOA8|s}JUmGYFuEchxBGrp%io?>A#5(>wPz^Y zXDGbXI&{EO^GZp7f0i5Qk@36_C|v!_lE_FbEhR|1Dm0nXjAtuBxb~UX4K8PZaxCgD zz8sMw#&G$5ZlG-`;m=oUbb0n#D-T}WX?oZuRwg0r!?CAv77Oe2&jHXF*gMk24pEN_ zGw3LP8SO);Z;S}q9OWJGsP4K!#t-j<*N%YpcA8y6V0r)xLO)pvKP?;y#pEtDTg`y# z(E#6;I&}E3M6f<$kHF_@mkJyFfTg4gx$(f}b+>pvp50GmHCE*7C|Z*dCl_JP9Idom%DXo(cqIiqYkvt7&Pw)a|3pLP`I3u zVDM|B!0P~vHoka`WYt5C`Ir-plKjQ1cU;qk-H9K+s$JfT{5Ov&?oJ;syC{K6=hvgy z{dm}V^W&|a?s#_5Pj_Q9`D=j}CvD_%x#e`zO1bSZ=fzsv;2tHZ)x?j^WDgg=W{Y6o z_EkjLn|59^@?}izJ%(C()_9_+7T=JCx@Llct4uhKEX=m$`R>RcHI{dG(RVYrl7`ld zvWJH7LsVD_`hDaQK?rIVMLVJ)QAS?c>*^HnX^AZcKAkVlDW)}FZb9m)Fhdv z$`rToUv+x4vkQb+Bq}*;KaYB7itGAgECZdH6A3L>FT!Sa`P?)2h1RIV#@Gno9RX9* zcL6mnpi7kL?g9RG@O({Z4yE|FPv(nMrHClmh{+|HjKg=F5rzChFBuJprlN56KJ zlwKN-+8eo`&qUd4vxi@grQfap(neS&@MJfoaCrA&<2;W~&)S6Im@%4*X!k>IwR%U|5wuZH+^>xP(p&#(e$<5zG;2`M8k1^b59^>1c z(Paqr-;#5zGr3aP)_Xk|=ylex?j)wPy^#)F=u4OzZ2xip;2@1dBClt%N;gp0=wl;x z{upiKRR#%X1Mthd1OwKUdV{{ae$9?4);D4lb{O?j$hXIjbBl7P?-o5qI(JsRT?$Rc zTVbh99%-KMFUQCznQA1MO*9*FKF#Hp^?G~VxV0|)4K9_PhFDSgYfa2! zGce7HVJ7h#O3G{)t;`|#09&$bCdBeb%Jfu)f8KlpA_Et4`0ziBNV8nY@H>)^p=BTM zhGe4Fck<5#8_D~gLzy@vXvIO;Ir=7MIXGAISlV9nMNINee-JELj3=~tJr%%+2uyVE zEVD0dHJX_lG>(xgiK{v>rKK7Z*x{bwD!f0sl#3tYhV7rT=M*f|x3A#JtPLhzZG!eJ zwD^0L+2GrFl`;2z~K%VcK1?SfQ zu-G~BtliIF9C0--Ug+4cu4CB7m+U;i&P{bJ;!ZMU%$SU=t!W&^sHGVR@Ay9r#E(pH zQ>tec^9`xVEmmSrvo*x-)V-T`JK8}9z!@i5S9+~|lKq-hS*14f8w~@4{(hkP3D&bW zEeJ(i!1Dqn_R+x1XI$9Ge+y9RAbEz5X_%8lP-cH zQ~R9rY~09}?&9bAnfI>pNeYZsQZ8xgyR&Ra$v(Ed*0i4sTqV}G*Q;K$KS(egn~}?k zZ#9J=nE$tMG9S0NyB!l66sKDFEXG6AmAj>WM3h{TXIP~=ox=9kEDJ%qJ$I@GRbr~JJSb)w``Q9` zydL166^tBqyr>{PzV>>z)v_7FM*N*&Ng^CdB7?pXop9t*?(&sb$=JBZ_@PAiL9PY;1k(8UI+49!!b#?*GuLoy_ZdC1=?Mmo@tX%- zJOjJ``L`xXmmx@|sM(89q8_I(s2MumtM}dHb(#6dYp^9WSgb}vT~rs*{e#M#FN~a zno9xRB5qAFcjtyXo(m>nD}2Vew-wHHJy(cU@R!X;8zWK`szlz>iYMwMBu#HSo+{wA zcK(STzGKtN4dZ7HZ3#CsJSrO026mPyH;3+jhjZpei`lE5B>b}%FCt}}JI$V=@}cPx zgLs*aGgUpQ-fO%n1v3=CmRPG+)m0}3WiHbk5_j8Czd+fami=Rw+#l>OW3$Kjd%ksk zu$}d6-fjLCGUosHdKIf*1KQptE+^@5;vZnFTXz;D$@{Ul&C*TPgmO+#^%v;%=&Ae2 zZ#e2)<2-{zhMg0+IT(+#zeGP*qg+P<*V?)?#GGfLe9lr6|AIU>=SK26gtZ!6H$D^5 z%4GSYmEY?z2^AQ)UZwAfq;zwxq@eBxmj?%AmQPXneHYsU4I%dZu{ism5wi=&0lt9i zOA@If_LJP*bfLTP36t#8^9s3EPNqX|L)holU(T?|Jw@pSqx_hLrcbdrtXE>I!rX*( z<@}K2o4_4e{&NQI!VIKN*D9DrksZK<{N(%fb-s=Rgk^000)0N-3CSW=@%Y|uc?Yg1$P!LB6Ibn-Q4Odnq#hQcrUjeHC>XQ{Qkw1js0Srz<~pMA9h~-NT0H* zXSJ7vz?Rfa#CF|kp6C39gXXx~-+8BEqhn9`KYGOfmp2FfsZ*x(dkdiBcUzxN{I zvTYLEli$})2gHdnxmvWkmUeISX=b$ZQ3tdxxRy4Qy*Spj|ndjrn9}##Cw0AhtU5=)>lA9wY_g2 zMBySLDgqKRUL=%Ox>W?Ek(5@EmH|XM2E{;0MY>eFJEUfmk{szCN;-xfYT(<0;QjsA zch+L9S*)3J_I~%9&-?6sj+W=YUup>F3%94m+ReppGh=0`u@hWx3&HAe$o5Vt4P*Qq zI_niAf@f~%i}Eaa_#8g=q1@5Zpjo+ZFrg{jDxB@$Li3{^1dP(J%`?eM%Os;> zR)6YgAG;&PeW+rsKU1tcOEmhP?PDhw0*FLC?Dlulpm6sZVpMt}%{8d48yZ@41Hl7a z4~70dN056xT3+a}qbC@p@eAR^_gPC^o`j#5ezjSfTv{g5Xt=x)doxIa0(JJ>p`AV? zfV_me&Xe! z;fE}R!q^)s+^rl1Ce`n84&ek7OH*t&Ti0-Lh05N`AmkJzTdw^ex^wvL7M>#$=}FS- zW0A79@f5#7G*pE9YPAM(TPyYFm#aiLpjfe|FHVoDa(Z!UD%8~-{_vN`f6oJot{oJ{ zT4GLZ4YeU=?-ecsiQZZ~&65~WUZs(8|H=UaNN3tPS8pB84Wc;Om4=EIXr}9|Ju!Oe zqAUM`0lg{AnYrnnE-nEXPVZF4xkul({IiY^o&Soo_1RAWNhtQfSi91H6ANsy{OkP8 z{*|xdNvA}d`c9lewKq{g@naU^hcoOE`YW20V$9SHYg4beH@n_77f^rZH%!9H)fVAV z*KjT5AkaBz-Tuoo*jE59%e=NE_QOw5C?B~&t-NiZnjO@304I#d$Nbs^V_Y&^x(8jV z1amQ5WCX9$mCob!o;K~R*LGQY&ww4K8kS+YCYH_BCbINXWcs(tN+R0pPHd5tS5)UI z!hL-d|Id`1(4L(b{}%*XzNb^q;hx{?@As`CFh=NEcw!yyb5~6OGc#uO3pg+vw^(tu zcG|8|dVkIYc^tr4iME{dQc~@So*vI!czn@{-ea5)93t@O>q% zc4eT74GWNfm3qCH`vXWs`^AY-%ig@u*$63nv!^4)$Q_15CwlAlv1*BuhI_1hW5C9& z3vh($M{8#hiQtm25)9Pmx$lLZ_FTls_nQN0u21lE^u z$sUU;Wp6N>vepGZhE#T^PrlTh6*d436`^cvQot8AzXX`AYr9BYYN;@k3zWg9KJmpEdL& z_1mxqohKSWtB;~dUv32Ha^3g<(`rD6at+o$$d& z@X>U2@>U%Z`Ans#x#WWI5RRP1C(~7$kQ-hxikhE^ab5^K*ya_MUOnh8m9k5fYWe-V z!FShmHwRxl^aqq*{p+|~(X@8{9xlA9V8-;_S>1|o2(Ay6?Gfr-fdu4iwckCHHQIN} zCH`Hc?CzU(USj*3N~H}bqPvHq5;#sjY<}q4jfl=(?@9^li|#H$Wm9Z{J)$`aX6uus zivh-n5GIHxWK6{?{Q4a2{(jTed^0?ABmVFne19Fxt6V#TWrt>(3c+VnptLRZuK;^V z`F^Fz=pL{0ZoW%;jHi*#XX3Ipl2Ko8e2q!40d~+}*XvLx9ts}o1Q}`gZfN|SS-HhP zJ63o!@5h7eui2$mFP?xjg+!Y%sn8|gz&+2E)kzr0c)?_;Ze)LOv3P_4FF}yb(Jm8I zw7RT%ar)d-C}-U0@|m8VX<%4pX^+XOT=HWi;2$oGY@R#;3Kx_8dS9w;Y zJI-TUx8PG3v$pemMr;q>5|VLxPUyxb;J#FJ>MppCJT86tV8t?jvZ#EGsIqIZ;UR@2|DhH0fwsb- z@E%ZU;GUHl=vB_k#~ZgkQM_4BR8|eyYe$O!H)UDieJXWk!Dvp$c?J#kdi0Oo+41$u z(eyiccthF3>+&=;E)As@Tv}=Sr;W8$bqTvWJGAm&VG8?{ zs#9(e*+0<}%0IWPQ7Rq9aA=9BfBvpuI?Kk3oX<9 zirk{V8XTAsl*2)Og-~%?WjwfzHJW1!HV{A#MynGqe;FQP%lDwIs8oO@mp`-_TRAIeZQ{x4 zfRQaI(LUuQ2-2Nf(HuR$JZLJYYv1eY)H^<4qW`0|md86S&5h&VfQ4g9x;*s|5@8LMidrcP@6vt3$31qE(BBV}de{ z<5EjA6BNTG~XF zFNvG+TjSi6hyUMONwrJE?*nn(b&L1VDMWmu#d{Bw$tE}(KihowI_Ch7m6n#;c|*%$ zQhMzO7^yjOaC~bQaGCP8HUADcXS%Apd~w{$9Uo-HJ9~F6tSVRZ!fJE(C%PRvgCrGt zyI}|T6l26WBo5u%V3AYh@)E#dKIUn2Pva&1hm)}A(@d`GEuFzZFz-#PZ#npMtn1^- zov*eIwLiv4Z)D3IOZwQSw={RY3NyQ}2)TOSgUV*!Y}p0z@6ChhUuA+erkVfJ1tJGT>mbhcs~nb~p1?uW z3I6!qBvTlE=MI3RANPK_bNE~V|0AR2=T#%N=WHHH@<{taH2U#Jalaot+j++rC%-2BeA@mGQKZE~+;~zd7%ION?!`(1C9@n%OY3fCSY1!+d_#gvc%5ejwNllJOqKspFc3K2^r~sw zTRpk;qZL=zyEH@%GU9{wTy(L4L(e;gi6Nlp0TV&WOr>G6MM`No^z;yqmGoZPY+R|W z;}?gR3v((CmQ=vVvt+fiCvZF)9CW4D|al1wRY?n0IHU2N!Fqb>u+ypeAnS_;k2ZYH8>jV#AKDOP( z2$WlG&hbyvzJBeb;HZb{&i4-(0inQaHrt`8UA{J0YMQK_XTA%7UEsPlx;$_ggrUe2 z2CDQ2M_V7n;&-cN!KJt3z@AHBU1IKc_> zIbp=|+(!aP0S~Cfo$kGg4MXlq!`Dk33Hv=lo@!w;C?5@aK#H zAJ5}4a)2P>Fi5=1fkb}~fq&Su3zvQV=8U?4*51sPsi#`JNAgM1kNhNhf<%^tP5qYj zU(4#(f^@W!h(J)`ER}rFp?o;9E3o4sHocfM=Ehk`t}?8viXY^5Ob=%Ne6!%q%L$3M z@wpY$E7+F5qx0n|us(shfCBpGfZtED_{G&=`{3Ghd=({kxB%7R9e*A-8PYq{(o?yw z`1?|zwreuTuhOSx{DTVmIBi^YdSrr&vnNAB(FkzmpDIBV<=-+F>U6 zu;A}ZohBtH;rcM@@yiW6+nc{~OO+H+OlPj=vZz6>AenaM z6%q7xCs#~p5a&g?zd?de@5l<3!^(ws@CE8X$SnjSE|L)a%{(Qc7&Si_Zq8mIS zPD+)dEv8p(6i)!-;n3=1C9P>R0*a%y&-Z{G5&#Y$D)XGn zIMM_+#l2kg$f{-8bHkV(bR7~=e_iGv+o*$N)j_V2N+@SlvW+=2i)edXMrZ@EFjsMv zdE8A+OvrmJY`Q+Zf$@H;3P|Lx(|tkUSlth z(=K%jfd&mh^~YgPE1eVaw3Ne{O~+kC>?f)PQ^}unr*!&ppL|6cu{FCgJRK*o>Y+GD zDP1q(Ht@!S%wtGXI*2P%7&LVWj&N%mS;4IPfKZFc&bgO{nXN3UiRP@k32^T3s;n)p z+iDzZiH1eTA94F!yuMf@D@D(RInij5J_ zF0&3Pe{W}YeqL-*ajN6)nyB%-M$_!Q!&$2zAIy`YXmmNJ=4ByaZE;3L+|}5xwy*2k zI-6p2<4cCU5qmD8YC2_t?@rp^^&CstCDa0udSuO8etv+K*V8&Fa>KIQK?zoHaqaR^ zny(zOitzta%kojxrAIsAvb2(%(-0pm<3E)?Zk7#FDlWbeldvYH$uU5Q!%Y{%I`iQaQ zwiWulR^28VO^LQkwF}k12;dEHJ$xw^`lp13lG3gpFld`=4GId4PJPow{y06#)l3Tp z6HnayEw>8)!fOTHJ4B^B{Ef5P;Q%9FL+zNY6YKWljfl&9itF|^d&39veXzj}^@@dO zg3|_y?|O-#CI^X;$MMPr8C^RRuX5Pw!t~$|f!(<=YMfpp+v*cfv(TMShF}#$B5pH& zX(dK(tR6I-3_iQ~+k04E@2lRsiM{pJ$(Uc*Zwo!7%*^A92~{_|r?sc+9OIuq{o)2r zu3(zTnV_^b)62^IOjH)NGUB%_LG+J zUZ0mpxJ#p#P4V;XfY%jCXiq+&`o?}UX)Y7pz9cxkVj;MvPFXhV)Q(kw*WIXa~&1g=L>HX&d$3ASGLyT`Bx#F=f7e5UM%5m1uA zjjCZ|Y4}h+JFY6H!oy_=Y|6P3{HX@c%+xlUlgkVZsjt}{N5$hLRMV{Gsr4hh*WAU) z#pJ;^l;iVO%CHXce9qx!VI`coQ`7rX@B8vS9J;ado20J?QfN;BFeFWHZbz`0xu-P@ z>6G^66e>R?k;paQ!syWQ{zn8mvKmojs{+$OnMPxM!4d2>gP9^`Mw1>D(ZNPuE|puh zv<>n(L&mdS^%K<<%oyWtZQ*b0f9az|Y=+|1_TaC@&fyudUSJTL*Qyf2qg z$Ew6|EDXiDl+DVFr|Gs~>x0`47Lhyp8Bg`v3d{vwI_>(pPK+3zAI2QbXNNFC}<_2ghxcI;17@CFs+g;9JuZb0Art*lC z__v>{z*1K)H+Hn#!?|Gtw?MaJ=X-6_w}+4eel~C9{Ke%TI6tMBAWwC6k1nMXE<2a_ zQzKWm^~vEKAD%g$L0FU}NTU~?wm4|m=}vmYnsrx~rsq_ePXEfKg+ogO@I^hh%gK}G ze1n~#--IyFC$V4>ZX6~5h{7Pp#wL2`Vg)6at^jB+fa}3=FG$mj2GpCZf}=s=ihw*& zwpi?D@GR!yKV=*HUNT7I^@glLSfLyUHf$`-Oj24ibg3}O+4L^+FP*B@Q>=CsEbvMf zms6mZ11_JiBLs*~+x!d2(Ih_^+?}(b6Mhmmo%r)Brnfr!zO)Kc$p`pr?t z9}LE>=Fj+-6btf$IWkP*d%t=0zHqJCt)^EpdJC8V;8N%PyLLwTO&R9NS~JSJR#V%tz};}Z zwNr?eKXL}xEonButV+1+^nJjavT-o%tHhqkYUkel$r-U3ko<#{qyM{d)=dXGOd2W_ zlQiYJw7^LbC+$n6)3~$1j>z+q1X|M6KwSxyphYpF3{=e;GdrwD z3uS$b+-S}AUd+fUFUn{;^VE89IZb_GViJEXTI(MjvmQNiK!0#jl&ocAIN!Y}FoTLO z@M_R&pmt}{Gd!k5O8r%SJu8SO@s!KZb@O+*W(y%sL1^aY0y#k_*jk)tVmgZxlt#A# zo2;Rwi?$HF?b!j}wCx~ct_NoJTdv8%5y+zcw@y$r0)RHyV8e8vp8jI+{+GT6CEH8> zet(tJZ12;dJ*9SaPp3I;8&>qWSBYlg$1qzTQ)^w~z3$}L&{k9(7hQ>eg*VrvrDLRF zAoq_DgQJbtoJ~5&S_@K6`MgDVso(ik*?Va7Qt5A51NFmGnXWwFDr?olQWnB(|y@%kHlgAFStQ`p@8ik)1^9MJvywhdss z+_=}E1WZ#Sv*^2fx7N^Rvy{qAk0!U=-e%Rwzqx1YPh-7me8DhAu zRH3DyLGKt~q|aJX6%+M4n*LE+pWAr^(w%!I3Bh9PX`MWMkm1bS4p&QYXs+JECP(C- zZi3>7mQZ24VWmVOR$X?AacW_5 zC6^+WO;Z3<#YZeziZjqXex}Gjr#Ge$W72phHO{kjyg4XWe$U|v-ca0oe6YZt^fElN69-;{Ec$eMCi*_x{-!35!;%#f(g!uY9}}tohqpl{_wHEwpJP$4XQFHZD7sP%~8F-CfW3SimrbUNY6`U^L zRj}3hm>8F?(c3tu9nsaJ_cF#kmt$m{t3cmm*IG^(qU~L@A|-}COZnDnFQk2jrxpv9 zP_>q>o%G3G0dk|cNVej=RKKf8z=g7&+V0ge9WF)Gecg2HZtmj6m)H9~%_bA9{e*~} zdYK*t3h--LlRj4v#GZEFiUK7lm8q-&jEws*)8S*tDKoWLvO(?zk}4hE^q8{;QYj+) z$(Ww`Gv8A%Hd@yAZPgEUpcEc2+e<8tTY`?1dWR1FCrT{6L9aw zUA>E5i)Qpd4}YHGB?mdMdLkhXSiD#LPBMC(0|GOXzq{9Ef?)Mt;H|z$8eZ%TKtBNv zCTNq3;FkVFeFV6>&qFzmV2AtsY;cr!YiE3ntWNW;c+P!kRo@F=r>eY>%K!)E%jw$K zPIGjdIxUqYU{Q=Lf2}Is>y%Ihmyg|;3a<00-U=-9=za0g0*pl~U3dB9uR1u=-Vgk; z{)oJW(n>c~lfAs%B_@;CeagpCnN7)#C8r}TAu`MrcBGlPRTMjyP;s|V zdt@V55jpQ^t2V}6v1X-{Vpo7{(oAw+jSOQ=dQJc@CfUT1ykUZD)!20RMafx2T|R-8te$v#yi-Hyv5|2ZQQ7Tzd^gwg_jYjug?)i0 z`>5XWU}-N?GD4#>L#KY^)FxOALJZ0J&xYhPH7-*Cm5&)O{NQCIQ!Turqm8VStwEd3 z;oc&u0!lys3Gy1fD+J&Ak^Y-GQ=?X1K?BEFA;bUpXJiu_64{rM{-_*;@JqOb^3&n!)}{K1GsOKZasF1 zPz0wb{TFeZo^Tilp43w7FR1>tk$Tyywr?bc5z5Ic6Ka+d4pjM(mXLb$EfT`kTY|k#PZa>)=G%h2=c)&u%gHGlyj0~bA@pZKydG?%g zyGAj!`#raOi{PByzYwJSH{ot71GrHViTRoc@?mG!Hv{27d{w&JR6Yp9-WMr2prHMq zfl_sdHg|2dbRuZffe`nYJj71XE_4<(;?u#a%X7T|O8JC!T6b`p;xcW3JQ~4vyYFwIz6!fx+w>{CH&)}Y7!;Oc;H?t-e2wqngTBVv>>0k z(s*xW#)?N$xD8(EgWvhc(zvac^^$lgG))wjzoqcCbLwWF_i)kokNjG;yIYI*h#3Dk z?^0{Czu>>p3@f`?E{O(X`282dqZ{tiPnj#tvJ-pE<2?~JJypKhO$+zOip+22Bava3 zASN6))9-)K<{!E{@+5NZv*RN^kTacOHr^{y8n4mCXnO)lJOHJhhD~kG7u5>U`3*6~ z8zb*1_Zp__(N$ZGH%$2U81Jjb02^121M77illC-{66T;YeA*`$gDpC2Y2|n}D~I^>u_Ist3 zrDp-LmCi6;Ug6T~4S@L+u*d9hfi#on?5*#14XE!PNMYBvQiUa?t8rHB4Rj4mqU#<( z!+fxj{ZA9)mvgK5F#FNu6KPJ43OGyl>Uf8d34k1hchlxEHKfr@6d+o>_wl;*Ir!$u zv!@{__(O@`<&8-7A|jEP`jg97ds>Sp_B4eW5C>n#$0c(;baHN#9~yvVfx<~25BzNc z1IQZ53-}hf{C{y?u@bYc%j#a^4h-Xz-peoj{Q8hx{>e+iHdci?we_!6pPahWnBE&y zvCV3CuVnc1NqajjsO)z_Q3Xuw9IXj5Q9TqaMiz^cmlPo(;e#YN2`#?~7h^B@-uMWD zdsd8qlKpx*OqSixTQT`!tI;muXEs=@$H%>0jzoHcW-ZX?@7mdRek%5Osr`Vl7@o82 zsX<(dKP`*|9E^4xZe?z0+Ocj?e7*vd-8QOo9VLQ~jWAZ!gQ{JhC%qrdPj^;Ovr!Y; zRrQ^@V_4;yp<>5_yG!H{>iK_lXa0@EQEyzm0{75m1k$}4{q^=K)YY0c?Y+ohS8V($ zDah^RlR(;gdM*XjA$?`9bKv2sLAX1F99qDjR5(g-7gLA%bJv)B?mvx|mU6MP=CJNp zg4z1-VtPDGs~g><{JEG1DBKb9uURs-MCUhmCn*UFcF(9LNIxv0%*yDCTddad4qGGD zo026`&@PVAB3|A<_1) zLo|eor`tb!T3=rkSn_Vb8Zp9bOuw;nIBqK<60n{7uXP25_QzaQ=az}@$?(POfG&Ku%OX91lNcQqxNLM#P^(ZQP%~MA*(A*>A8{E&nAPSN^mPU7J+>FcP5CZ;Du_B5BN_cs^T}LGNuOHU zA{u->O=Ip~p$RT*u)Z)Ya`V08c(1X8>Ox=DB^RvN@(dE-9d%SeqBq4B`xjxq2#+eX z==%QIiSY3j2O(5~D@F10?oIP-qB2cBhYH7$XW+fWh^K?kYE7%-afR19?irQIS$po7J*OP=@9JXK^JP}j^sWhWW{=H-^>Z8=w0bvVETR-tWe5x zy&(|1wa*TX7JW(H1OVte#= zX#y!GbWaqW@YS@GrA%BPHp}mud!V);wwS!tJQM!bqI<)L#>lXO8f) zp%xY&-LUEYOTVhuPV-uDp#N=HWS%Tb6WXP7{n_er#IHk#Y`W5 zaQQr(=imrUc}?<;Y?RJpA^k498gZTz7?{8SOYZ`5Tg@aGuXG0mK>^3kRXx`ju?!C6 zGW3|_A7>KFW9)^GTpn~;M6BD8#}PUk^{zi|$P4AvosaZ#T4?@R*jO>^J+D1o??2+K zurPp(o!_}RXcI$|$F$jzv2|m9bB8(rco9k^$r^JKn1^D-G|t#eiePV(^WFBp7OsJ< zudtDA(g^Ts?a|Khmzt%@PeJ9ROnJDnK7yn59=KX@-sbSo`tTsZ!D~?N&m(eR7M)GW?Vv5{V8q^r zDZd`S@``(%CB(fu1+B6Nez z^TD(&<$^!#Ad|PD0kga(VqWv(Emk6xs#3*O6ZmNRzz1;XfxiIl68=R!us1h4l(RAvbo@ux2) zHPr!teU`D$MrGgDqp}h#jj!Bl#Cf{a5i`A^>v=4Ah*OSl1x}#nCFN+RD$=vOZ{FCyO*&Oxx0bE zo|2eVNsH+ywp$;&bTYN%VWO~urC2J?ss@%;7yT7ev}DyMu$xtGFe2VVqjKJ{^mqBD z0b0b}a!Z)`>#*X;XXynqEr8p+GLnU$maHzptUc_Um}orjdkJ=+Qr+|24jl`ZszJ#- z(U07iZSY(Kbi)8U$%#nUPNn#)%K#zr^HXmGsSm`LxHRl_1+(`(^J8wsQv7f}a2u;m z*y{D3vWi=wS5ajd7)AX2h=(ep_(TkczNk>Xv=p@0XtVTAw`!u}x5L?zfT|T%wIFsz z$GfW=1on`NiP!$=3E|Q&nS&uJgz?4Sj;DI61?6&}iDXpB0FDFIY|vLeK~7dztzeqr z{)B>UtE(3qwf-DXBA`DSPv^AaB>oup0-lZA>(d^zsepKf4fm1*WFb=GZR!_R(J$MNeU~vL_ zito`8^~%TE6QI|{BWuCZj+z8ESU!kJi#U>=psv8hRK_Z)!$c6qgXGL9x6$>S*slr> zy3q@-3svhoHw_=Y2q-I74&y0KlWJuzo(V$It0_i6&t0eMgeR+AXhte=dhATpu$`#s zI&o(o34sZ6UoGrZ2C78rVZ%0KFa*SQS}HGn@|fyCL+%(@KR z^6oxh-y6*t(ugg(*7&!9vngg;9xQE`PFGJh?CpZJdLZ1(2p`S z!G?h*Jk7e<+vU9w4H3jAxhe=1MwbvGOr&Vl`?FAXQv}@WVTUGw7+?NLf6Tj*PM}D= zHa6o{Dqt1xua1zprnEdUUvQWOl}E0$A18c7ZwsT1pcggP&yE2dz}bNZCqcIHvoOha zQcoiHMx4%0567SExzpJay=g?sCV2|{X0i3!FckD#gfI%if`vdz z9sMJ*V-Ca#RZb1}Gqyvj6ZHeXO|zKNHAL&83nev)3X1l!Pr4J2(0mb0fe{hTEMZ4fnUb=>`}C z)2C-re)8}ADk*yZth|{*^fNK!)BiCQ5+SElny`#mK0~nBEj7eiw`+ri9mgX%ki?u% zr$7vumF^Y}^t(Drohq+IsuZ;Cd^R^9^q_1xi zp!)}d1jPj2D=p=u4{WGHfG{|=;;7s zcu6teL!Rm@{>9O&0C=?)cv3;z`BZH3KH`RupY~lxHrphR`^pKo+;{ zx$ajlHIL?%b#qd!p_6C(%WAcxzXMvvpWsWAgUCVhmKw43HpThJh*pr{wFADcD*v~_ z5Q2c?w`VQ|Wnzb@T_nm5ZX7t*-Vv{!OiCR8+F4S|8DAo3wGW(r@L^4YIx~kOZND6D z9_{lMjPc_Jm9Tlyg0-}Ae8|&MVL#&GBF!n}z&+3AhP`va8wCm-o zOC)p3*S?ei&Q9=l>Bick$b4-ep!pe$YtudrRP~rdsw9zYCx`%8~KRxztB3y)L~kD7Bwpe69gjoU;xNp;A9YEFd4cqCQ*IGD|+cGV@&- zU~(#<@u&H&YT$~etzN}B5m-O?+gxDdL~hJ2V*B{2Z5d(|wRW15M@Bzr-i+i4E?P@) z1g3^gK*`+;gc`&rpUY{NfD~P_J7@{aul#}SMY`{{xsF7@gQX9KxK}DhT#RE&ZP$Kc zRVbiT#^+wY?`*FGcqvgzOM6b0dxZW#l1i4@iDK4Wbn8v_`}mvV=^;ok?O?`>U~3$u zU7sO9NOw7CpB_g`yEG@I61DhsJxn>VS~F>tH@8XJNUE&-l}JR*zdx@^O1tj)f4V5i z5y*}vQp^-BdjSLRS3lNsVPMNw4U_kH3#Zs1a04&b4ww{K3j+jU-pTSO2c3XW| zZnfoL#t7~k!%{PUvY+2pGNmCMA!`wFmf1#Zodmg(*CM?SWkl+C4ijQ~@og#D$?eKr zK^+LUGkd@QSn-*Sg`OK(0`VLtQ0Z?ufk)F{M;-_wCKh$!gLJ~!J}L{w(y=_me2NfM z+JImy8|~u$U^a_r)^FWKddiR8$f>Y!Ap`W>&+rXc6`?iUJz zdo$cgxBi)}vfbGClRo?()rtCQM=Iv`a{0+d?|nKAmH^62XkTMdxaq0! zONLHwVZ?}t10ufFA z6{U+7O6pTTc-PV923nxE6u%z5nDrL@oL@OV#HHY0(lh&VRz64I4D|M~z0sQo9T>rc zhD5&?A-4o*bbme!%lNGY3GLHjt@DG2E7n|Y>g$0~K{GV`+a|jfAHqG2cZG$lQ^9S^ z^uY-DVT(P;h{g7uRr6w}^O5xGpR#9VJZ4kSf!#CJ3E4bkP+rP6$*&nxA<0rD-9_G0 z9xv?gl9zPR&oy8Loj2F#dDVI%V1`L~?>shDt;rpjKrs^XK8*lufGgxpfR5#-au~$Z zR!9S3j9__POi%#NQ(-EwEz6UHHtViwx&~37Ym6(cl?g$Ep?lOSFV5okUKhU^bjawE zl%w5sktgJ~WjaPS_YSbRO6wETJ(jaUZ+L2uAGO*qc2x>e@9bemI3>sj?a`yad@>nlHH^2E=2mH+6};oothrOky-mCyA3>%P6C z7cH7mdUg7u`N^~S>4bp~wI(ba;yDn6@*Ycbr1oL8no5%z(CIXHJ)>ZK=6R$wDHIn# z;-l9E6y*Celk-&6K85_AZzgWugWZ_nX?25&_1JinWMxL6)tC2yX$hBj*t(%VD8M1!OvdME@sf4yX~k27q@4dzVMWGYkuneG+ylBjtbpDV0Ne1Dgm zs;l%$^QJc?`#EQ{Bf!Ocme$xkfCnI4d_3oZENz@J#m@e7-c5pu0vnh5HTH}o^6QX& zf*c3r5-n5|v9#B85kE7MNm0DJFD=!9k5KN+!??X^I0+?wR|el{eaE4b5FYjc?B7$^ zS@rc_Z=xs^s8pM_2n7!JAd90{*y3!&+g?`iIIgs(B}{yCaS>KE${h(*)2g}InH_c} zn9nh7jG3{@35$4QD1dw*PgF+RQQg0^XD%w(*~ZAN(7Bs*)8tXpvb#XJT{YWTjt=TV zIqSQyrCL9i^DC}~ zxmnp=UUu-F@Hw49PAbsVSJFuEobZ>`U9{@Z!&Rrk;v7F!JFfntIdNj<+hdXuh$_TU zMd95)au&N($dF;1n~p=6^WBsQM#-s2#Mi{JnaK)zr%CCES)55s%EB3%9q>q0Y>Kmg zH-c4#$?yqbvLoQAlkQ#a^`OHm&Hac`J*A&*JGpgQw@gj7LNbHeLl zEaqp1q{0-?3Al4$x$TugTr%ALpJG&drqKCcPBIL zZkMPOD%h#Q&lP1#eV#uk?$911fo9SNY}242qp^F+;71B*&m!?hVC)$VN~cEKz19RB zwO|c9X!Pp5#kA_LtQ&2C?bk2(J1zknE#&199U4mV*&V@T==O*)d=fMuDiaZ|=_r%l z!C4FH85W)XZ1GN$sE?-lq!!esD0k|iKeBgDGVmh{=^FB55|Vo$2P_366T$b+HYuKZ zm@8k7e|cS~jjc+Q4hm1&pl)@4@+d0N6oP`dB2kcis!3&;⪼s8H^UvxP6Tb+ng}9 z=KdTlE6*ujv+Z%Y#(i2$>J7`OV?EkE;sZeT-?F>2cWMR=7-0=hp|WcYV55C{l?*nb zTYrxD7W#3~&CKpwmgTE#SLotmqP8IW@J4i@Dg&oJizt{=r#M4q9E^atST#N+jB;m1 zRNksS&sYe3%}cLpv->g@p5fpL_G^u?UWFJJ{ARN$wEv8;fD@wRZtRvuI##Bf;ZgnR zTBEpn;bt3kFd}K7NBvGcFl-;mV^Nk3{oodSFUojl)lD)bGpaBDpJyv2V$ELAjOb&M z(5T;tiYc{QkZT8uxuIdJ=ysiG6M8iU4tu|3pmouuk|b|^Y}37=0Sxn&`%O(E*KyPx zNtbSAuY<1pXIrj$sn9L#xwU2t2hRDi36Fx8G#TYx6~)%92^ZexfS$8P5senIt#@V$ zw{^TrbZ39sGUj!G3NkKFylsKuH{o;Vx1^`ma~Md|tk1GN zo+``DUHF81j6Zw$KxnS)JZsZ3>y)>S>1UbV1Dn_SGO@mdC%mj> ziu&V1QF(JGU-<^nt6Qeyi@sC|ARGf{Hv?bfC9i-%Ye6M%N5)>W^d?B@$FoRo>$Wl_ zuG+0;XR7SoE!UM*^SOD#${sTZYol?j!eyn z+y*adx{`iJ!5x-kMPX&*d_E#J;^AfqFs>r=4`6s;w#m>!wGp>%l#_ByvS3Tx6~{IBBQd- zWekey5xH)bY2cAmZ$x_zKE&QE(TZS_)>7l?H!HKXKuMf;@)@k*S|%i7xUlY`IZ|}i z&EgNr_f=Df`R7F8J42Va2laB3#pxLt2!~Fx=oScB+njkm)8c^<|BaUU5UH~W?*jVf z?%dBb>^gPH$Z76cj@yZQ9$#2UeAYgm0~Vf;Aa1Nw+MCIGJIsw1o_)w~3OVuD9t;io z`WZY$>79_9pS z>p@BJ2`xsZVzFAELLaR?br0u4svVS%pTyg?I}fkbo684Hib_L1zZGBO#_U;A#7%~i zq_*|SXCnV?j6VyBaD1x8P42b)zRM*SJ~h9ulsdb^uFJx5veH~F^yTIIW)@qFFaX5- z@8Su)wOhh346V?&v!gX&+j`!T_KnYt)|YpKmOjFO6LHCfclFHa412Y=2L%GGO8;d& zhBhwic}!F6X{f@i)D?-&%rp<~sKMIqDw}QBysN)(f7d0!ULfV30Go7-K6u*bKhXo? z>tjLgos0gCWRSrm&TXSgQ*L%Os;2l`fi?q2G-dhOsg--dJOf_}281;6Z<)0q5}zlE z$%+d|SBGr#ptT7P-bs&#`b)>;V>N=iGs5u@6kZmMKEi?xq8sFvr=>YLvZ zfrgUHS<^E2zbQM}K9X7VJ8*8DzQrfjjIAC#dzAwI?7Y8=4&?k;C}Hw5Iv6r<};ME!dL+K|9Gm=n@QWMM`*Q`1#nPO!e318)IYQ4COCP|}YaVI08Gz2q)#j6VUCOOI%Dj|-tuk1u+8vNciglEP2I2>Jd1b0CEH7r$Oa zjyYqxUhLGrtI?kO^+PSVAyL8iJ>%@|t$EI9?Oyt4o{Ufnyp3F z`^H#>T2Bstm=vyN;r#UYJ3n+!IKAY2P0miq6M&;LnoVsHVo&qL)HfC=HX#lmNPYwa z(P!}6#6JN3BwR+;j-zh|BT^{}ssK3J)@tv0MnPW}lciZ7&h~^0YFzt&M12KRlu_69 zLrRFCC?ctXpn!yQBO#!4cS^T(qbLXns7QDB(A^*)-8nSU-7qll-|_w4_n);`ESEYn z&y92T*?XUR_pe^<6yV3$?zPI~G4d!DPHeT7S1jT+A9%OSR|knUo1!-}x^S=Wa&uYi z%+c8t*^GR|`YK3eA-*RdOQDjnmmnaj9C)8R8D)1K{uG(_*+1BkBadUCV`@RFlwHR9 z&S(p^2=ra1#oiLjZwuaQ6NLlirtnUtPE4pjvSfEx_@P(5N-J2JB2(2=I&?e#ol|1PgX0tHp z(VOLtEg}~o`(7`IhkoSTCYn4+%l%Js`?8XzO?9=OBm!Ziup$V9_>^y0|x+)#6^3jAy86CyPMs`;Bo^LImEoE~7k3>WC;Pz(i? z*#f{Gh^`sV0JzCT0{{|n?CyS_+Se#&Yi39kw1-X{5HTLTSX5WS^Bu^^b zxp?k@@*2q8BBkYl=^lvm*{-C3Cqo)K_@Io)C3FR4M1;#I)*Zw}bDFg*sYXr_weUA% zaA3AEm~GvY-ygovba0#eLAVho`Fxq`KK7J7c_Jb>}}A)SumwBRls;t!ZbC)xrB;^YT5JfB`w(oC#)?%<&La1>7{ARm(J~(}!*rx^j)hY_5I2yUP>! zRt3x8-xKcs50Pb7s#L6Rg)_0u?0&J58y|g8!SXa#+3e+Kod=Zlyc( zWXtT(!U2yBv5tW&}OkI!(gkBPqMmDQRiTmTFcjxf1B#o z++3Osr%hMV8&QD@rz+Hzv~r@B{@F=G@SLR{Rb$jQRy9jjN zy5WDkIsLYwCbe6E`o?jN_Jpywl7q1BuNi=$V(I(t+12no(|D)96)b}r5Su0U;DGy!h8t}B^2PHji* zU`05q+_cj6;z6fVdR8`K0T_E&fI&cEi`rd%#$!G1PwlZn07p4~V~!E}Gfc6qqV+xU zy8|F|#O8V3KLZH=AN)_cCU__YJ|4WjOR*H?D#U&vPq4*>^nI4>Lz(*CZBlTlRp!+4 z#*FfUa}teSK?xg2n`Vw3Ti*_l)=7#8R;@=>+TOLrN?(UIpC$kG4Q)F8Kztvvr6&dN z2yS`h|7LSPdc{myq4W`fA^E>Yvbf`7uB`g5GTS#&8ppqOzyt z@M?*ddU}8CsIbK{MsbHV)p6c+Ec@r(hY zU{#PnQMVgU?z6evj*-Ax$Y3Xf?vxA>LbNK*j()!JtbPQiAxjbC`3G4!C&_IBR2t5bYGRBdMv&9)u(hL zY+~7AB`YftR9dE?8|e?#qxgl?0M~Anqyt-n#pTLyMF50j|6e~b#9ZbfAF)xX=~Hwi zbT;!Vo~KyKZq_T$*3+Wl+D`St@Zm@TYpHnX$2&F!<*uE`S}vUmY%MXvQU{90JTnra%Ut1 zcZ4=Dmq8oP-xu>)bA?n!Ff+DI&ObJ1{YwDWi@C${m%StbQ83Tu7qAW*q0=;D?5)`F zQw=hfyG9Nh)AZ_ItCs*Ods}RZAkVkcRer_)_#BHSMPIjtQF|i1g(~Ry(oS{WHQ6H! zLU-eRe|MTxuM2s&UODxhU=A80n&eLv)sX(@*gViD8|D?O+M6YvI%d^ zf`>5)9)|XbZ$%_$&imTL*)|!Ja;cP?t9!#=zg_^apA23kg2XFx>dYs%A%wU!+=S3* z^?(0fBFs~C3MV$yE$Z|hXc$;XFrxOAiq&-admvTwNT}lTQ#vj3BLpH({<_3={^m9y z1}GoOjQ0+CQ&0nm3<@&gpm>Y5@VDob{F1!BK1(S+Uu$v@54uNtpRKZ{<6}M5Mk#UN zR<>gYie(#D=dkd!5jnuH^?85MKsM2&pp5;{LP{DIwQD|jI?ctOm1JL-`ZY0`NUpnmAf2uV*s!4J&sW-11hLcT zc15(wpzg|zKS5A2IU_`#sBCtkN6aGV{#Vh()Cj#=9Mg{1F z+YC^4lC?jI{{|a6JHsd542!4e-tHYHJeBhdL!n!_Vy@)C}j1(G~3Sk5Jg6ZQYYlW z^|XqrxYS-uw%4R~(u8iQrzH13Dyr!@TmKTdlGUMAR@JrX1fawM)ZYw#ftOB3ZbO^O zg4A@?@>O(J*6C97wS;EnnKYKc;|k{hworRxoUu@kx6q`y#JW5KMDDxeE}#^K&rpb* zm>Ki1S%0yaXm_)Q!j3=N%&``%A5ui0I%#49QbS3S1C}gM^+uAAdHnlNom-|@(E5A8 zO^<9lWY&TTHURE@u#V>8bZ|%6xV9^-*6;dwS8evgsbW_Wp5OhWcz1H^S%IUdvd)dT zk#9}Z*=g4jQy%+UBOtP1$}hHltE@kmypNNxlETW7{_=VSR)F zggOZ(RcNk?h<*ypfQRMA?t6I*@RnS7WCcGX|3y1xG>xBHqIXecH`f3*v~QuSsvz*w zE|EjW_hz-Ed;gJdcrsgo_(Ybp!p^KLCn$OR?h^-fl-pYs7J5^0r~MwkR{A)wH3akz zK6ja9q&|DV$ux=}C4Ljtz<7 z>x05QFz%A&diZUo{vkyqzV+VOx4N~hNX`e9XZX$Tio`Eu(mxI)<@u%}#|&pl8@c%C z*;9{@0>dS3vn7u@4-*Nxl0>`lKhs#^Ic?trYr5OqnjTvRGRgnl5ddl24<^Nbp@_zF zQE){d^gLgArWYm-`Ps79)&$UcFMl>X)Tlmn8(HhvvVou>XvdKiPigL0c9I)vAfF2;o!mSqi+5X{%0Zj%>q&Zxwup4 zv5lm(#MP>sa)-MUpM(+z!e6m)S1-4|Ky)XQ>=iYe2Syo)a|<;n(Y!qZlP?NKU@Zu+ z8_L+_6{WoUo*sA~K9^12Ht{C^o@;+;vNf2&hrx9fr3=-9;RZspWwS#fwIWN%}oQMZXfHV&U@ z^@f^%#O6ZQ&i({IZMnH_#Y_~o`JSXv`VMdp6=g8l#Ap$uUih2HRjbx!Q54d$VJWQQ zNQ$u3`oz%PB?Wp2Grod#SBNx0G;FHJ*jOcRJnh*V*=ypGeRyT@gDyIBhDAU6*p^Dvy^*KvB3=$s#|@qOX%}KYEUyAO_?Z z#9~?g@vw7Q?G?a86EK7yz%Udls+}|z8hbjSJL)1Q6pwLxG5wIA4{J@p_XHqMN!9UB zrI2pSP2_;VuA%Rk1@Ty=z@a$^g@|$Kwv#gn{@Ybm%8#w>IKLz z=E*bRCoi`)^H0*N)%I<;B0Vwr0ZMCo4e-e~g$&#jO5KN!1T<6FB-;FH1$OwTE{|KW zx%TE0f}cP^?{tY3L3kMh%7gh{Z5Hygw-u`16NJNrf~dAi!TV<-a{k-#Q4 zv3Z|knl>9NZP9;}gU)|%BM?DvH*%Q0>Schp0>w8W-a=d7)}hNm%z5VPJtQLYM60wx z?_=@77am>Bx++aTxRbdx%l2q6!Lo&?3+wdY8HmdLCvZeP6#!S?efZ40w1n3Dv_Zh< z)$~dBab3LceYE$^W@{w$fnsPQl@awCLvKOh_HB`y^MrJjA=1(OEe6?Rqi_uFGW!q% zNflrHaxvm}3fS9*;4yC`VwEZ2V>O{;8yU)*k8UJYf}Ii#+G_jCVRA?m7AU zfd2W2yt5z(&EF0?T>go`#hK&w+6)l=JX_maS{wG+IoOsVxZVnj1~3IdmtH6Cf&ld? z+2ni2pH1a9_9Y&nFUW=NoMQVmv6}c5A~VxR!Z)-3joD4-E3utTH(x+}{(q>1dz?JB zqE$V1p4Qj)qQ9%SLb!@lHLj@1cZ)~D*kPx@N_nJ{JAm5PHycG|J2j!|*fiq+sh>dB zX}mm_^l(+~y9)>ZRPbns3h+=`^1e5ip}X1!9(SNx7SlAm{DDvtb6v~R>PEy6@3PZc z{w$#oRTw!&^BaA_#0P$|^~a;UN-hENgx{Q(%SpH~P&*}PZ5mg}&b%L#z8FC25esO`FVrGdqd6wkR|N9!z{jH_)B)b32aTohcR%PTFaDYQq|93Vs z^j*Xh+`A$N3UVKP4|S&lcR?~ugfx^>&u0Dts;^4*zPa&T*eRUFyP?W~y)3Xw)=7N` z;|*#r7eNrjsIc^IHDyS+J;&Y9+#1oJSeS!t|i#*L@?WB$CRY}08*9Q}O65I!JJ zm4fIh~_Rn`~ zl^4preC@ax>~6&XK#xdph`6yOj+au<^N}@GMOzQs@-L$w=HsnRm8g+6vv^E^Qg_^1q<4QA4D6j`@nA?c2eKf$2r)FtI?@$&OJ5&Ze3vR zV1S~ki$AfOf?uFm!9!UMI6YEygIV!e3R#nAp8XKF0prS3R zhRdvhcuI4Eh)mNSE@k?^5DT{1=!^s_tM>%}YuD<@D$sSgWA^Pq|2!*ic@3^_^Vgn6Y>G@9TCHkl~xoTBdFO>Lvj5^(h`vqSj>Qx%1iS6s($} z0qRVCy(#l*8|@gpW@sVfdkbE(=A)n+>qO2h6`%skoLA2}13v|)l?=7u`N;-DuaFyY zA}WA*ndM(|_{Q^v6?YjowKB~jGK2U$mloT8LrThzDcDZ*qAm{TCjC8E%&+`Jby>Z? z_mj>K>~3UM=+(p?deG8T30zm2*Kw(FZTa@cXMkN2K7$(Gu>WfT1#6b`3?7jr{>)=~=wah^U-bs5LH z^GIP2X3YTAbwp-|4SzFiI35d};~r%uLYbdlly(RQD?zlEy1sMjlF+!@wob$uM=fJMkJ|O=dNp4(bhkf`^3*FnUaE?UmJsc-% zloaw2N!6<{j1nu`)@+mZQB6#wPJslSQup6lf>w%& zL_NMQghP&M77m8BeV~a|FB-Wc7W@1*gLD)yBb7TzHY^?RgfycC-i73D*P%DxS>upp zQ@+bb77~y6#yca~3cL+KGVH3|8k3EyGb%dhm&K9zrdsOInkN{V1;=hxw8^s^`u$OY ztAD+0`XyB|3d#tUIaT>MUek6mD*QHb5UlbFU$uh`A%a&2FuOh1Oe}{}o+iG^QdyHH z7ng8?1m}9J7@T$@dI(f&c@>zLksGr%WW$W=Kr0)a>p}}GDa^Y3cp}y{@D$pnlO*KQ zlTARaUZ!-kg>70Of~v<9&L;>wEEq_%zp^Ml6jOL%CcSE;2vehl;PRcm`3wToM zbgJ)zR0Up-1+i{3)A9afYEn0oUAMDJ&NUj3QJS^yh{@=GLKK!ayV~@^Zy-2U$}leX ze0t=f;dF-C-uQgFH^GPwFn>nCwPZQAXU=9_3@^8>y zYx$q5?VPtiq&Ig<7SO(wdB&Z@s|HGpVeV^$;qa=$Jc*huUGyYGFOjAK$zdiBB(3#s zweDBMikvs%HJiSLT=xvU@k__59&0OYT<^^y5p+ITdnWW!GMRS)2;c^{|TYsc9xY3+>LP}ebdj$F1u!*}{S zl!}Sqrryh&oih)PEd7skgbbsuW}%~#K3J9CFq~dFGkN%>KC7XowriFBQ09eqtJc>G zPV%2^PU_%`wIHXS@Jh){e!HlN={YJm+vHlRN*+fH+y{UhW%4i-Nu?uT0E0NP+D-C> z(5?4~@sy9R^NY6CeNcmWnWbm;jSEexWdl*MsU?&hs_tp9vsD~z?RW#mb%bAdMCr1M zTWxEcrG3R=5eawufTrfXuXxna^754IOBh07QF4tTN-4{)boI7LTCH(m(HpU*oGL8cBi& zY6**>N@|jI^;t28BYtJT_2>&WO0?s7JiaL~*PiboUdfwD4W*Q}0}`JT?~ z>56m~{ATq^n(wBieOhJAXt_Y>?)KN*+GiQ6o&}VFRiB?u>%p_wtV=O63Zyu)O!zln zo+$n@epwzYf85Wm531i&j`I9c-W)UuUamgiL51FwNRa#+A(2lp1kjq=Gi}-UX(m0#O!Q)J?2}TenL=~CY1Fwy;Amhh zgMUxzhsjoEzSqSVHqoo-O%WrDSWir@r%c(=_=CQ%|CH`+N$tM}e2H*ecC=e{4e40Q z%7bZM>;#_lkA(3VV-g|@i87AY-z@nm};b2_?l)Fxh9o;W!Em3w1#ck%& zSYDNJ@zb1a?feD96EP4zfpWS5ZjMX6^7;9J^N-rfVw4?H=>~}Di3DZuk5nIzao#En zJP$luotb8)53g(-H&E9V8R2CCsZomTf3@rIJq{|UpSzm1nEtIP)&dX6mATDL>nUoZa$e(ag#SyfHFmpgLYmH4d+LdhG6msYzt45q} zv{DPlUP|gL2$aevU9Z(k^SR$9AB3cANQ8Z4a6hMe7<)%HIuC#SO&C^gyvo^2_hC2M z4CocKy8GGfi1FULwJX~W-E2ct(0)+fYKpCoX=Ltx5v@t48`c8GN!P$IFakJlP7eDw zCNCbXv*1_KTc{w2%T8`Bif z>P6Jaj=wJM)DmqL3kzH#YTqXMoYkSoNt=T0+B9oNVDInQJPvs{v5|TKX9_iQB|05R z$hl^GM93^$^FDfYrbz*q?s>2Isim2ibKC31#N&eJ4vcvS{jM2^!${Em+c>}JiL%sZHwHvY( z*95Dj>}+$mX1IjoA$wOHkE_9qF#UOwaj`uud>*uQvIl;|ondQzAVp1q?C!=i21PY; zI#$DkjlaD#wC=jztN|uqC!{jtXiT$2j9j20oDvTr$0aEOAqtomxi(tnF*q^#j)xh5 z=SWHYCmzITw7T$M{Zs7iy34TN2NtFb5cPWUJC|v2IQhCeaPO37){ZGr3#Nj71t>67 z?$SaWu}5$P2CmvEJF}BVpye_Ug~eEM1F!A1$3@Ae_II13Z;z$*1x>%s)nBOSvf6y# z5L$B3oI6IvjB;JvdBH4bo70~t@Hp2orm2Q5cNt@Y z!P01@jy!)b3%zLo@e+eu=*(2KYshUzWxbW5Xd<23%eDXoTYwR&C61?90cc4ZBKFUX z?5a;z&D0szMN}8ta3vFQ*In=e5-+^J37p+h`;6I+w>@b)$-&4w}xK?Mion_J$T zii_Q9U3rjKhOD@ywiwFP3U=X!e<`1Lb%S0-VJc?do!sBOR+FKfOFSBSSruDe`7YeC za|Jk%M{Pi5@rn?TDJNMYMioJ~!GQc`a{0kPwP)kp)O#;uU8rk<nL>`ClLs3D8y?y9wU@>d7e@rC%dE53F3+r?b|>976!xvIDfH!qHPKdOAiZS2zOok z^1(W+NN&h4%^GD7duIIdFJR;?wL}?S{&{<~AVL-rmy>3yelnWWfm$pN{2J(1?}xNM z;8x@xgoW=M0QPiEJxpjF)%Zc|a}by6vt0ny*9oOmc!t`U8>w!pLA!JHR@!3H?s|2` zViG|6gfb%k6}qnRdfM8#g`9=D*wv`-4lIu-zKA0w$LtIKc2vfdUG&<`4|ADtrWsfh z%QP%+71q{>lBzCx7i*2irA#J^U*Ibx=i)W*^55^w{%fYKoi#=loCDCw>vpda8^_!2g*vSa>aa&0IS5|OPk>N7IM?AavU5~6S=aYj@+b zosHTCVW zwOx047T8Suf@W5<+fSiCG|AKTS*b4zjsRN^g;Nao?2TRHb!7uj$YUM9z%+J9h#>b#G>m+g7V`})|$=bjls zm%w^ciwH7d$hX*Xi62)G2dskDR?n>F6M+ZSsp$5Akq%GNE_BAe4g(&t6a9fgIW50O zyLZ_S$m|zWd4yJC44*~a$R*F2gCrxUhTbexBzdMMpz6c^Fji^i91V-l#jPl#->@Z0 zOS{Mc%|2-euem06hFHE_x#O3X<<02uEMlhN=wv*AA>I@d3`yJKSCq>PwPLJ#;+ZN2 zXdvr&z&?KdraZB_OGNlR_$i&JnTty4PSC6R@rP`+2f5tDZ^L4Bl=qy*DnQwL7vtlY zaATe9L;}}zlyNW+4pxMES+y6pkv7h?XQ6#S(#!2(XnG_R4lK4RaI#9ic4p@)#A}AX zmcEyVZ=A)KQ2`c6YTtkEdRmoLKEk3o z^1Qgovbn%+cekhJBcZmC?Ecy_LBZ3VWhP4X-^&hw?P_)MWEA}oQ#nz&QPR#|4w{gF z$Z|RVu>L<#n?fVwT^MAhC@bFXn~%M1MTM1-m6-hHC8ZLDE&lnRZa?oIUmw1r($vM>=#+tuMZ#V0 z-aGQhK$)li(~CmV8(4@Nm8|Hj7^c)ES&;5uT!?h_L4_P~+q7n#p1v-&xf{E^i> zz-tqFC8I%3$sm5|$Gj2|7IyuFcxb}Unm#&I#Hu}@=bq+su%rdZxcFbZDjd(ujQOBd zOi>lcg&*X*Tg)z9r)-{1N;sogx(_Su(KeWkj2z1T1GzxPNX1}x z4DMKZ6>;N?m>4)DCluSYv7R81FC08lPtK4b-pP;iM@$`AJ=m6#%Phgtwsb!A-lHtN zhmzjjxpJ%rJ>z#C+a6-*J*8&5ipQDtZk!?I5Kh3zFSP?sNnj4>)7DLOq$eD-8%Qol zo7ttjWO|W5Qh1|T1bQw4y=1cH^ULT@Cs-O;pBTp1KrZRE){ zo5y>MW^o?A@~&O^;LwxHn?U%M?Ag)cogEc~=M+(%=ym=}yfQBHc=>Y0o;HB5`k6VGxHtk5!0 z@sGzlEX8aNCuf*mpk#kkPm_GIzOjYz5lA_bB)`BEJmTs{xf*XR$vyrz1%4R4+jPDu zfH>nbuCIA(dCmmrj)*sB(vxn$JZ#xrq&ESp_0tmjfz;0>IYgUzY?+5%j6uAC)~nKu zI1Ymx3Z(`2SgP&F|evTuk-(aIZcw5902L8z^w$&J8A)m_mnFvr8c73fv z0Kp@MZtCX7XrQWA6m>4UX!4cCM+;2qA2sC&qYiCl2EDAcC~0@) zAw8+BRR!Ne==eVHOrqE~cr^DqJ|PpwOd}7y|NdUKn*dcJdu|i6u!BZxC(MeIS_b1g zPk2+4nAz-Q(xOX^<|zBSC`Y=J32kAXu@AzaPJBK&)L^v)29Gt2#uTz(ypLybwAwda zW)`lcrF9<%^H+R){-;mq1XKbV%N?Q0rlzK)*&A;oBO|Bl-OI?x$VP{U(*UdA+A4ao zIrh%DGfeg78W|xd0p79sq(CjMVT(~RpElf)gdf!mfRey=aO*GJx^?#`j`v!vn>q-e zk7AA7+Q?@Q__NiTLb1Tb=D*03Jkho!5OJlq5%w&Uj&HdNcn&2WBA`_Llpbyk(mrRvdW4`Kp1wy4Hh}ROIo@!L-Iy+B5hTG1n^jR=(5DMtWr8>qv#> zLOosWR8TeatDuBU^`d$iT~~y8+k_3_eH_V(idxkO>_@_#DAD_e!^1}+S{DocgvYJ; zEbEc#dPB9&TlYh$5UbS#Ya_pdz`^bP6p5~L?tF`%iSO|!yINRVk2($rW=HG$XztY? zg@FmYb9w&r=e@opLG869PZ)Fc0{Vl8fE3LF6DYE2eme#pT2ITO+=LhwPjpeyk2m`~ zCn%ef8wz`%WPp_BbykYMI+cBJ(ds$O|!T+ajR8N*cO}@ zkL*m#zGyJnGB_;)D&Y3flbscQa)6J)p&GwH?L6ijnboe=o4Uy7cNh z+5*s@Q5_n2^FWQ*_3b~+*8h)M_|8{lFiZ+MgiixF;kykpn?=n z#>q-w?fJl7{xfqVPyO>~P>R35@b>t7XzX;Ot$jSXlsF5MOO9A%Z+N|xl}D23aOQ

1JlkiDm#sGZ5s7$1eqt$0M~z{rnYP z7l*c0L2uHv8ayi0iu4NkcdNzNO?wAlR?Vb^uryA##MbsC33@tR?o@4+bW$m6Yin1* z$0jDM!2M@&{H`!q)3t}L&&3L&OWr4~#h*|YC9^>5(x7+*YWb|N@CJvcPVR1vIYXo` zrBlms3z=qIQF6a-Ix5zCZwJwM<^$im^Gcv^f+osf2~2kDU3*k4P2m!=&8egWoi!!s zHhIO%HIB>h*w}eS%U8cPoUUu^UPo@T7iRP zA}PR6ZP#`b5p0SjdYKdgN`pKbPJKlLHTCu=7%@(+fcv56D!(30q|{f_od#Qpz)ot^ zt1v6<-vJ*?WzMQ{WKjrcgaZ6@7`bBFA~s1Ikl9DveKj(oY*o-^0jS>-y8f|?=)UiL z67wWrjnMV2IF^C5Rzr3Ww4Y5|h;DDKf8G){DE*j1F)MisLoh1H7?Tip0rdAQVdkMa zR-AHcd2{Tpkz(3mZM2~9mVWIL;N!B3>3#Y4u2y52BJke{m7ys)*k)mqm~H)H%RKaK z=pH!j0nXCJC@o}D6EmB@DyVC`_o#c0mmR}~Rm&u&PV%AR7SOq2X}QNbE5s6l*WASg znz;n1l(W+=X94@bS>d{V%PjQSC^*Z(fISQbWt4}Kb8mJt7L8tA9KAfNu%3G5y(e@3<&rAM>Qr3p)b_B zT9hH5euv^rW`&4$eW1y%fu^L#Ae9)rDMh!Gv%r0WVndD(% z!}YTci9(NIMc=r&4QR8<46QO+!aR&B7F2Iu;+&1<SV`DL$+r@Z;Dp0bMtZk+!6c-WFO;&FKU znW_Ldr=LQ#gn*plF=wnhmLtP2k5|Z!8*|Db4t_sOh~yC@O#ajy`O= zupM52d`YcYtqZq;AOBhDw5J4oOY<8FHVi3E$F=@3z$@GGHX|(d8ZTjCysM;w*XPT8 zH&;hCJ8*)yxHzY-XVIv@T~aYWKCU+Fb=2npHvGwNV)>k$oIm5&XwXLf%lkv1pWFs! z$(tjpgc6~t6>o4fP9>;9Mc#Vsx7>1`b)Mj@^mMhd%4e?M7ey`- z`VNk%>+k#_?NU%yPM<0>vqBXlU&b72vy{>vhsXv&q@RnWir_k>3~(QYFQ8|A_3 z9+-2@g#kY<-Rz{vowS4k&@L2IO~r zoS)IkYd>e(%Y4J-w*KNLxKA>7DhgtacQ}5Z#g$&-O=7PV5VR#^XIC%|Bt=Ug!U2Qm zEhH0tTQ(q0Pz|o2J?QP!BcZx1JP1Y%D#ei+D-OW(N+RfWHVfu1#<_m$DybELo(XqN zrjOV&&6}n_m2W+Sa}aB=ffhX9>kc;5gG|FGZF7q{=l)$!VnE;TgO-udN#)r)v~LGs zFwCl`LG9w=qISEqhk}yvE^4ctPMPtOUGJ3J&hjNXk866YCA#Kd-iFqdfPH0x`a%Sh zP!tCxR%cvWSHjHWs18QZsrI&c8)~ixvZ!oT-@qZG|6ttK{Wa4~U_?3zbgks$lT&{U z`{8|fEW9Q=++{qegDa>#y1@CEMYTw#jHZ68BhQ#F*zyG#yB->kViSUJfGQhMGajAd z)y1%D^Fv#<*E12+w|+SFV^QFEsL{mi}Bp$Em-+N#cWE z$+JFJs<6vOE>&e5Wk^a{{^jhB#yL2&qG&lFnrE2%bR*HO z5wO*ucdD?+e7xi;5mGlNh-+g0v3R6F)GUEY=G?yac~qJTS#|T1*0ssNDzpP)uvE|i z0V{wm`II*M5uP<=4*T+NEGd4xcMGO3&>Q7bKbVL7$zEGNW1n&(d;mNQg6tvF7~=ym5Ta zd5GhUbg(+6r?m=oYLq~wGomann3)1kRu7(IIQ7N2{ zgLl6_Wk~xw4;vw6Y!8z%9O=k~W-iCWmK1`=nvdG@`Ha0(lo5vr-nG zI4iI>5i;@4)phlUJ&3JF=x^1x#Dlr}`o)A0C4>z3KKCB9Y>3s5#C8@h4B)GRc zk`6ShFQ>MPV-)QvDy)NfE0k_)jF(|fB6g*ZXZ)cJQ!$oG^#kfA*HaAzjUq{((q-D1 zKI{p!1<`d`wff4^`vdx~v`V?Y@_bfnK2WK`ktWxOYA5uxJQyt%t?H~hjv=}-Yk4k1 zNjLvqLWl|aHY9(=-0h)vy-ajx)TQ>yM->k{T2`jLslPAtFA-XRI#JzKz|wDm7ZER1 z%1IqYviT3-v+P8#&nR)9psgRhydvhSIob<(qiCWTlo>=sBLmjtNHQ5b?2-Zfn;&OJ?$>(;x|G3{k;Km?^`^#vw7c6 zo2uD>!^02RTkP?D)mMi-C1wLup93$=nuoTEn!ugd=PfH{qya6uuCre{seLJa{Kz&% zlarN|u(V`Y9Y_wpxmpu;1E}o)Ahv3qHSmt%+;eUit}_mSDc9gz9l-jj@S}EfT0Tz8 z{o*D!tT>b9FoH7P+@j%TqllK1dj0l(Q+&BBHnGr@SIp4|x)4gc8_lqZBGR6GT~VAL zaZ{FodLk~%Pwu{cdK&OmI#Xp~nVfDZqEFTB;_M!2gU(%0t=@Sm%$vYa`Tcc>6_x>8 z-sBxMBWr$M5{$pZzj~dUj<^C0?Z^Id^rJP;>M%f#=hlyVzT&nF$7e6phF2PT=ekCG z^qvfBtpLBX-59G_6Do5zinxW#%(y{b`5~h$~661OA zq%0U(CwHXi$3wI=5#qWxAGx zf^@z$>)2Hs4W3<=xM_zVD%^jx38LiNY zc3BOt5eupCA@@`>aoGEqkihEHC^wmj6z;{`l`n1^rRdV|C!dMzHn&R_0%t3DG_oIh z&)&wkLVh!>PI)YS>>Tk?j+~4j@)IxD!;eKv*li^@b1HMe;apT53H6u)z6a*w8yuo_ z(l`g-f0#l0<%Vq4CZ9)}dr4MlW+V}zmKPBoMEChT6eOhEk&&=6X;i{F zUyZjTy1VGs+Sdg_n?EJL%R*WRb88%@Re}$!wDg|5zyYS7&xMJcca%Q}Py)w;V$8zn zL+1Mcd>FQT!lEi<2WzsZ>6*{9H|8T_QT?!q!YQa0K7(?RR9f1}F##;-mP2o6x20^+ zawp!T3@weKPP<#=2dBv^=a-M#_Rpr;n(Y%*%d=u`FyUkEvaFicoux~Rr1rMSM4}l+ ztho6&+|S-MMn*{K6Ybw5CI#iwWv6De_<2Tczm^CYVzi03aj7qZp@+aI)*?@FevtEb zN*mw>2QABf+w8)76gKcc;F`HE5v!-fC8erJ_S4u5^+61eDwG8oK!4uh1&X$a z5PU7-U2`lMb}R_%Tv3as+=CT0<1@acwd$F)iWIPrQMKaMs`I!@oac;)tqr3RxI+3A zys&VoYsAO#fK_e`tP+8 z+Ie<^Gu5q|r1cv85H?~tjoPv$jQG@_dxY29pGc6}ZEP$dUzfnLAY9x^y@=p+_` zrE_Dx-`#=B-IF`tZu>wHLOk)i8r#vV{i8>{eV6&$C<&YcPo|zF@Wx=2{mu7CP6axC z2GoOk-lA4c@&>WP8hK08!i!i#0l1o=pO?KwC2x5O$r(sUnN3FYOZ>Jy-?m?4i|n( z`&l~*@#l{elXm6pGP8k>N*j2B&u%F9T=V?(Dfc&0wofAn@15(*y}+S$FD1Sb4yK-ra-8ZMn1r1$PJnR1)tr;dDPoQE$Ry#KxD zI*|tcG;qT=m42lAPMziY`F%5e$L!AD8;@TmngV6@-zQ4d_(Rsz?k|QkC3Vz!=N9|F zL_dFC)^{ht9*@PAHKn@6&(4*yMKxk%fBnMUNqAI#KiBAG(+?g8$--YgGG-ibh3WSq zwno)|ZSIPG{iTOM5?xni$sC{PaXrBr(B+6zN9TRoTZaF}P`=Nj+$l)^$p>u{@;M#t zfVu%PW<)LS6O03CAD5%vRJk>>yBA*x#+G_#FbkNLTz&Hs8U8QD1)%%kKJi)XqEG%j zwt4mDwUZM^6q9Bv?|D_STz1=pzHca-aYssedfTE|ff{3y$L0$rz4{n+@uZcf0)gG)8h?PO=Is*+%G_?il5BTh`k- zhdmJKy+@xx{;Ib8z~?~=)7xa>ko12gT5;%>G48vQ7bz`LN>TBs@7zO@pi-rL$)M0j z`%nP1*>O^OZG2o1VUd| zGnhQf^yyRam#8J!d4LPag{*Q9M7z!7M}O4HYH$=dckx29_ z{(}b(&QIZXx<0G1W=XFtE%Q=bhDSyY{zk|z!RmHDAYuXRUz##YmM}HVN~x@0X@98i z6uT%OC`c(Uj4WSpxkm2!F2~z7w)~)xq-Y!{WzzFHkO1ia)+hMW&qPmqgE0u)ET>+N zItOzvI=95fi)%*{JqyL|MeJ$G^^Ce4FRTu@EPbrut+pXCdHC!z&a(Ak6TjKovxOE% zNAX>P1MC1pR!27q(>vk*T}EQE+T0$6F6*)+Iu~7nx%+z+T2wZ2Vij0ekeQATl;d=cItH1ClQgDNM^tGPQFwa(P(=(0alC5K4Q zFS~t8uR`|=m7~+RF3-LLa-QDS3|Jw~nSDGo&GaqQ7JDrnrD}RTJ{5)2CXl^YHm)o4 z9D#q3uc{s_?sfyuO(+3#lWPDPEdJ-m%hlVG8iNP8`<|8*^c^R^x{M?p{HfBF|3)f& zl|LD6Sx65JbQu4NDML=O1=b7q`F1NR|DCDm;Xsws>oHO|2X-tsimh8S>tE&4e`on7 zNxx2g#m4m#k8wBYBO#Z{Qv3W{aedzw<)-D5qa*viUrsrZhi|pSrBc?H9B#yzyGVjO zhxiDDE}Nv!*IX}43QI#rO5eGRE~Fm48RU&d;U;lRCy94BKN>*dYcX}yvw6zTPtHB- z6!F|<)&*`u%IB0ba%RItKIe5Lt2q5r%gTze@#^qhbh7(qZZ^?R0&pF3v&EN9^dJ6N8rhIs5ES?PI7L;{C!h zEEM!*=f&j~$>8h@a$rc^i&aB#&xNZ4-=R>pu87Z535?0RmykSL_X60HezYq zcoT9xHGQ=z8^g;&+uz4S|24R6C}azAVIC7infm1e6LiYKAbm%#K6!_Sp$PknBV%p` z40)T--wLaNKRAqd*z`Z&h&6R$pa-<%K6Z&pM#&1ck7uQS2bsNc@vz}2It#`x)Hl3z zz~?%ZZD$?-_YZ`iN>kfOMpZ63@&aecB5;7T?U6C0Z7Y4zEz@c}s_rn-fqJskE<&pjy1Hcj&wGDjri~?~`?{cOrAY~4fB)>Q z1pT6C@LBtAQz=AqMk7H~1dSXK>RB{z3IzsBGVI2ah34MPJvIW9EbD41d|Yc`rc{ziMDk&tc2#ni~P*&NYG}t0u>JJC*|TKWT>(3-FEm^ z-MdQBdg(M3l$sGL}!S z7}|gDbTW|7JRD+9;2~5-Gag>I;6r8Fee8utcXV-6o`$S~+i?%8%G9M6u8GE*h7g$a zYDPQoo&O@(pa_(;=Z77>r0`byU$y6d!=-$xHl&`q`>oDYJmxbzmi8Lq3O2&?SPjcqhQgH=XMZknsmE$CkV2Px0Xqc94%nagkX0SMNu5Ck%DmztdtM^8^ry$&x{ zo5>tj`wol8?O1lB?x5$J1*s}L_JSgrfe)Xwj0X$}r;~7u$)ZOv0?v0xA@vRl-&|MrI;Jc!#V}@8gv)lz`Sj0!l1H8&>@uZ8 zr8Ionx%d_SPcBCIz21ECP0={`JTrhT$ad%*JPseh`C7Gs5f3k+>Wei^KmU3IrtdKi zf7OfQd90sn&#_BypP!ha`&9yAN(w>zurPMOe?E^4??}xhR)$-!5i3?`e;fa z4J%Z!?6xG7>BCB_F#7IULn|ucuHL1Zb$CA&@z*#xl||wkSeArGCz8OHv~pUiw`SYO z<#QqH@9&p(;-;d41~inRM6s9sdQ*2akh7E1(C&D(OErs8tJ<{}KAX`#7YGapWp)k@ zQXU?S`%VCh;+9~o|D?XSf8=~0{@j#Z(%B3)ys3LtNkIMa2H0Ix(6IW~l)0>?OV2*2 zcae=74`atd>{3VM5v6P@(U_Q2WurEZI9J}f9zD0(kcG?CHGWs+pK&taBxK)|MhX2R zMMKw9ha(?lXYb;ovADIllZ+&{r{$Y?+`Iqt0*qVLZJmgXU0ikhrt*0URPquMmk<5< zJ`Fz4GAhp(mmX^JC01VFR*j3^b6}Op46!drBk&aXKes;{O91ZRXtPj%!op^URm^U?m zowf)#NYDo1Lv}m@5_kR*`)5!DSG==k9Z^jXZ$X^%i?`W2VsM_?nHcJDE3F&bdISJa zzOP8k;m!R=RnnI(Gn`#~8UbVSTnCy6bBv-{v*lVnpp`%YjYLhu8G(RN`^GlRv_h!@ zqUry*NMf+jUCW#&(&yM-|KLC{w&SJ_d+ce$7Vr|j`$YtrDd<%Gamu3=Re`bDP{rSm~{p0aZtM8u1$jl>@VGwa34g zPM<59kKXH@K5Q_-ulGCX^2@km<=Pd!?HNl+U%o^{0eo@PIxny;_W;;fda{4v$pCzuqP?e*OQ7!;R!rm8ltG7dJqbpe4_bsOK1zUO` zSA9)<=Lbgwrf>0V=^qachbA8n>*{MURZTMz$LI=UHaGzYoGmVy^6y@g@dG00%hoOa z_u4vH0&<8Etb-j3Wz!3C?{mH%ohLd*`wzJu^*hMVUZJKLn4Z|G0mqH zs)_@HadrSYivA1_<69K~6|jQd5<4$LVNhQH542zR?Zo-zACLMv7ZwUu$L}XKjk|PK zyR6UyyBs2Bk#f9*VmrE*2P%9|RsD`!bxfeyTrp7(OI0QLD?q=zw=39>%MTx&V%62F zR>C}MSz3Os_kM-sXgwt1WH+dnxAAcLR2mTq07R9X;-}KG{}ELIme} z>8}G6cx*V(80iLu*LIK!nTtZ-F~Zyd66N667YEI5o4p?>XnIuZ$+#uJ?o60%f+GJr zF7wvN3G?&ew@m!}+{h{kJr@IW6S_;O4yp}`LB{kVH+QfmCVL4KBNGurm#{B-g!`|^ zjBxUV(m_Ua0s=&0Vq%N}cPkqvJ{O)eOp31jeMCSfla`W#!NUIg70Gq3T$^np-M-_d z<}pQ8)a~KrXBso(+u74uxt_?Bc#l%B6k#a35k4CsL(NEazj#DxKzqAzSl3cKa3Z)I zX9F-(ft9Que*g#cD3@AjtO>A@l#TcIMMa@>O0>;^7DAH8<3JvIHev?PzpZKc86g`u zuQp`zgj{}Ota{(NcGh1e4aBs$-=5zgZ~(*=&=$0w#AZ8(1*!gaXxjOHc57)@=`4kVNWH$EXZvN}bD-T_4VZV0 zJR`T~+BD0~xqAp&G(O@2En3yRLwu;hYE?bTh6Sw@jZ9D{^IDpMs;60mL5s$4n-3FY z!q;nom6&y(tLG-RPitwygAGj-TnP|`hW?v8x$X*JX& zaWs6Zi7vKeRMxpX)^8U%X^fn1wI^sKX(H5t%_X=3*SSZ-PIq!(jQ$Y+%zAv#uThEA zgwR2xEek3AioCy42Lf%TF*sX#|Ayx69T^<@D$*1C78@BbeLuXd0WSWjxB6hX((Lr< zUm!rsYiJgg(WNFQhfqpIxeuigQ3w8#{Rd-*fS z6iJ)OLC)xap);OuJoKX0{I)9=<^af2gZg5m6O$lUMZ%1x_Q_9iHNkZf&t0fh6YZe~!J=K#>{>92# z_GJjuzvLFh8Fuf_rNRBD*)(!D|zt*=0m9m}6g%_fn)&audjmp{_xw)=WbUlC+KXxzeVnmanpusU9cZ`NA3h5O$k>a z`U*SFe1IA2EIij-xAgJfN~kv0QgCDX)a~&R>X;?=v1f_?=L2Ns4t%!y;eP8A|Mw%8 z*FwAl{+*ccH%{w`U<0{#09*26xxX$79R;gRR$4)`-r{`mpAUF`Ei?QrkO#EV8>+Jsy zkC22n!mPf@VSz3EERmQ`W#*P%DI?f=?2AA^(B0`;Jt~MdbDST1o;Nlr*LFgul(BjF z41<8yYf&d&RcwX;C^%oR!(^g`Sq%&$UNdui6pB`>aI3)A!!Y~+u=CJ|gE4w9KzcV$ zm@tBIW<&Slyny*eV(U3hkayR!)ONJP;P*5UqW>E2b83k2sf&cjIaKu0fVL!f=*U=r z#_oLSRXJj9BEPu+VNEtHxJ9RVyN=x0wCCUFxrs~UmlNG-3u)j~0pP3jF)pFwE$Klo zzz3;}sll1O43-Mh4xiNMFeTyQ$JEp9?bvhPZ?mJ%!>&u0=?l2EI@|wXtckqeck#pp zWf4{kAS@^kt|@vI6pssywy0FsSE+Hdy1NtU;J&xec1y|gbVyBT;RM9Ay5s88;I#?C z%6Wrns>#!Nzof+2(iY1ovnj#l(9d*0XU8T)WvT@q(Q+&->@Gk2t} z=R!~$fLFyRjWdk`FkGQKQ^ty*FyKVjJwJ&ixY2s9y)H3Q5NbM{F&) zWo!{V;v7@;xNL1F@ZC2gv>JVYLiI$HV|t&JL;O&MM5sPhio+4>YUIp&y**8iwt3?4 zBX)}W4ag+*0%!+P@ApMj== z0S9^UB!T^M+=d$&1w~y=jY6Lsco|e_+~B{HR&|!jZrlKZbU$t)_gdIKrL7*865p`; zG1;tTZmEwFc>l;V4TGGCN{2IlpuX-1Ie}dHsdqtboK^pAtj5<#HM6Tk`*aoA`pQ8W zD83I_V<3eCq4Ofch5g=7vV6_OEg2XKBDu7m6L&E*U6uqscndDVq1zFDHTIwY)$o5> z@!_cZ+6#b5W)MJ+6o*t8%pf5Ysyl5^?T>M*t&0P7J)bir|GFX~LnZ^a(rM7nw0Mh6 z*gbA+_K7Wh0_VL(1xbw%#vS)IahHw|K$Jy}qWDT9VgvwNu+V?Eo6CP!+}nlr z4#(&Y(8(6f<>1pz=JjRJ%yKqVu@nF2Vv z_0xs(bd4Awx@^VIS+^clI;t-y%H`Fq=zDlvsZt0FaLWv?W4It|FuMU~Vc@DJP-t}0 zdA<)jqKrtF{I~o6x0oDB1wBUoJ}xcItUHeV{OSHL@Z-m_!jr4N&K*T1B~k^+)q;64 z1ptM~R9;@56{XE4LvyK0J6@ntl41AJ?jS!;{;^`TLKDhnaIvUSD1os9n+T)Ba3X zC>#5mc)LbR0gmizdSnpG8bHp;6&H7{EErP+mIH0PU(fnjg+Z>K_A)#*XLGjEp3aMt z3|-)|Axf-rd-RzWlpe_hbZ~%YRi1XoMp+XRt+TKQHh|~_Hg6bT^=Tj8xAn_==SxC1 zt~~LMN&fWlQVeQ};0>od6jov|hieZhmwr4FrM+LzWdg;Hri$COR0kM67`30n+Ej*Ezrs@#cV#*1dA#{!g&d##|N zz4#ERGBXYq(d*O&vCcp$=SPe5{X1jPMYRw^TWg7ed_PJE|EzWMrHXx#4p%GKzrK}} z%H-xZ+`mP)R%6$C4-kjp$zovZJAliN{=Ypc^WPqI#}!8g4Me<4X$MGX7Ii{}aA1*s8%q|2JetCTvq7_FXpJuh$KD z`EqTjUUZfE5VZK&t+!rfS?%Y&!k?Nk7M6Q_P%&CTKsG2nPW4UR_wPKYt?8hOev_7| zuP$jS5bZhi)wEoCxA3SP=}|d;E5JnzMOyr?Q$+bq-qq9n*_$G%VN+t;1YCQ5c#TO_ zDTUk?z16yRyahJ@5bY6vZ?-TNH|Nu%9xWhbO%s9O(?Tu#G4+Z5odazKOSy-8TxsZo4Nl0eo4LWNuq8vzbJ572Hb=C#XJ%E@d^S<-#GYtWP4@H8T<~fBbgS#}MRY}@ zm|t$gA0vOPQ8@!BJr!uF>4P#c5{>Va4T1fJM*RwF zc9)wHmMo76co@Kj(osa@YaEz&0bTfy4nlA>HSO`A<^MBqfJ1G1FeRCg@86Jnu+Q4LkpF${*j>@ObMT|ne`TC1{#o5U3E>8sUD zl&FkR?#SueL=F%y$=Mh&%yh++1ASK4WDW2BqCp#J7Dy&xRC^kfZC-lwS~^%~(gb{o zC5wH>{_G|-_T5SWjSoQT(Yw-}*ov*Qif|==xwmx5s5~$*8L@N<0 z^+N}|Qq6 zao1>+De7hAZg4&NRT*6QnXt5yS13?uvDeS140-|~EHqV4Vl2{Ldn8Vzi7L`)RgfE{ zPLMU{rA_U;Z57k>*auk4P*HrN>S$ST7pfys{m4+m@ZG{?pkojHwEI0W+ZB2Z2oS9( zpM;Y?_g)ocMp;lDgQ!&W1B4m-!$Y+H*DTnF+k1UDvpjZ;tq_+xN_tLI>Ieu7=vbI4 z_|?amE#~M3Fj2@Bynw01x?uOp#s9E?7AL5o7pF0GXlE8L|JWZ=65+n^ip<)+nL>as z=Kib*uGPvvX7WKiYsZ)0+@Fhx)?x}=0L@`tN&&gAGhuFVfGY|O`H3>Dv+V~wnJgnC+U9CaK{fX*-)jjOpoAJl0ta`#tyA_+3j!t12L3Q3#SC_s6Waho1a(J>UPn_f5 z13XxGxSnO*&@?3dm4A>KhD&!ZUNA7rwwHoZ7_mU3-_7|21Ga2U6&Y=wAvyP#2xxyP zR%WaJ)d|u!S|~cRmzEaEK}n4aNS;~nnjM#W-)$U)j)8IfLo4NgkL5jpcP{?GQF97Y zq5_~!O-&pG1j0r}{rb$6gj z@AhssnTV7M93Z>g;kK2pYr}%=GfqP*{K85A2eHluvyYMQO{ESXeTsJYLB-% zDQ<&P2VGm>_t8Ro*CQ2&ibd{ehgtWHSpjTnNe2|k)EBIHS=7PNx$a*eAC&Nz-^9iH z8k2oc_U5oF^NC5;+M<J@%s z|6lA`ntjX*+%%04X8Mw?dL+h-%T@dJ;Z2=_yIAc1oICf_?JE+9$wh!2JN+y&GE%By zPGLE6bJGkG(O#{$U7g##S*^N`sOPm1LDE7@3At~0Q(S-}U6JT%jHCB`Nm0Sm($)E{ z_D|Q=NPk#B^@Gz&ZHZ_~K(TxCW zm+{*3uJxcHJ9IvUO)~GF*$@Y6&WoaGjdc^#Tc<(qo>-WSK?YG5{*2W&Ko6Cu2JFSR zUd@Wcd;Dv|2|uuaTXH#njddMV&`qZE;0BZSstAv-XcizqZeX8o5zHM3;VML!pdLmNk z5j5i)#bkSYwqKzpFs9U(T=1B()z{s_H|5l9KK+f$)H{s7-whwF@M6=9S|=Y$w^9o# z1CW7~@SJgjo3O+h=q^)82;qD08Bx{wm$DVw#bHk>h`c9L`poJ^+2n7-k-of7;sWr|0(RHx@d5 zI6!e<^m=JsL!=xuP2(XrKW6{%xiZr{_xbC`31ODq|;=_UWav z{e-?%U~gkM8POMF;MgS|yPdy4>!*=s5S<$l>vF?774U1N38A1lr}+TC6Qr9U^*3lj zN?ZQszs}mp^bZvUZt9%#dq6GAl z!5d9(e%1ml4zT}=9BQn0wvwt!VQce+#1ngPH&ZX5m1gaykhC#iaEfakSV*n=07S*O zDoz!vDxy3?QCdE9ZORFD)vQ@zFvaEw#`_4tvKM|vZiDORj-U=M)G%E(;xG(ClZHtG zvb`fV*uwX;<5|q$e_>T=0h1!f!qAmj&(%;A3MGB7)g+M}lRtOYTEzEwKpDgBBmwvq z@q{F_s;N>yQftvbKHBeZl!GKxgaYW1H6EV{l<5@WeM$>KB{Qlahc~pao3YhWfSq68 z;7g>Smg$5|1{w&?hv<#E_EyZyF~f_*B0r#l#%Emgf3tku?YyLa+ccu9YNG;X*%(0= zOJA5+3^dV*CkMHbDYfKLE*jp&vD=Hb5vR74#0~*Kx zSqjWQFL@uogFgTL(cWJd9;az(+D6bb^TS6%oIyqoL7nJ@yNs@LUAY?djaY|uqp%>A z8Q;!d$zRBj{AhA=Z|AoF7aQUN2>+d?rEmQVJ?_F2T(-+#OH+;?$klqph_fstfx{97_GYs{5;ZZtbV*{9InkJ`NwHdUR?3 zNxl<0yhJB1iMTd(bNgN+Ka7gZr;g8gHRFhIlEZfA`pJaZ&dAOs5Uy79Lip$(T$NvD zKZFq*!#k%9ikLU)`SUg-12+ar!@ZR1nESxpxy4|p8^8yV+DJOY;Hf&|bsJ}XBQka# zR!j+2DuN$l0$6&BEjtwq7z$BHp8z3KWqEUcbL{I^m*Hksev)4E@?Pq!Oj1`k_|#AsrTo>q{VK@a-eT# zLV!Q?if%k5BL^0;NTbM*L8du|nreEEd8eR8kl zTV`Ppnfk(}Z=5pX1*vJS%aepBYs*gI+Kl3gGe%}199=vDQJjHrqk88f7hhoKz~9G6 zqK!i)4Ma`f+u|S36u9s48r{BH_u%p20|9;FklBnCBp$JAtuwNjCvNeCt+N0-L&P;3RHuq zCXK}cB+ynSHku7TeFB(`06xw|=avDpJSHtGie>hwlH2!;P|4hn2utne$5@_e^?A^) z`hvk8c`L}*SsditdT8$F(ne}uF9%zOrxS=*oExX9 z2K_w+Y$R>aG8OztSZw2sA@4o=C~6GR0~v(~z!of1j?nh)1Rl9KlQ`d@G^F&UKY}9a zde0(oye@{jSjHaw9X-9E^XjzP$`ERETp9B~804sSX&|#cBArF=wG}5wi0vw~r7p=yGT4YzQ#JxRWd~<*`B&9= z7NQW{hnvJ zmdW@-+bJ4n#~X3uG2Nm5+w>QNWahF(IU(Ui5+CyHjt;~7rozau?;M7lE%7&<$yiY! z6=_olBhO5nH+rPGK^+}!LHNZv&IBrgXADEn8y5Y=oCi>4XB=kNnQD^93&qRKDH%R*Hv*^kGs@%?s5g zQ_v<=S|(%uq{>MUg7ANsbV)cm`0JIW72He;OQ}l%lujcGaIZplpSi(su zODCzNseqg;^k%;v`Mh*2=vScdH+vwx!)x_s7XMG}$&*_LV7TnDPtDVFDBK&ec-9#~ zg6g5y-a8oh#xmwoT0 zwyXr(B;I)|;GvoaBa8EzmycIk0nqfKX^!a8v{-+EA7{I7EZ^?nQ9T}MRX>j$rClON*xi+ zNSj$jq}ndE_m~Fn)ZRSM;HS&$u0j=v2Ww~>cn+0KDQVFBT|6I=uWRMECK6~UB<~*u z(a?HiB}%H@ZV^zI1^SNmh0i-yykA1*0uL{~O?q!d5$y57SI*K%_bK!acInma`+h|G ze(bsyd9c6P(@MjLys4i#KJaNZwZF9F8KKw68amLiKk~GqQkS;(9~z7+lYPZ zj0AL=23L}j(t|>|1O-HRG9t?X1X^SqPq|FT9qBGFcye-$?OZrs-#~F_$*(4h2_*UX zgY9ARMoEv8t(PC#u;c}qHC9*e=-&=_LPxtpMoQ@~e=r6Q<%Qf)tcr^@#b=c>H`ongI=drUka_|MLPA_xd1T9Fx(is9M!g3|tJJnh@7E&iJ8= z4*dx2`ym5Y-~X|hDtSJ^20l0KLP%{!nwLte6~5KcZo_TD5#|>?$t6!rcOIeY5d00? z_4`}!tC8-;_+}Lq?J2=WDMt*mCKz74eGV93Ztl%9=m(}3+KAfP#UXjE>8XLu@q!cE z92|(FZHNmK?&9M9Qcq#Dl#pM%Zl9Nh)y$-zwb7_Z3~S3owPy|it#&3eZO8ybUu7#=7HhewKVbR z2Hmk}Ly}X06}(Qs7vzNtTzur~_+hpQ;Txjn1^CWR(`b0|xLL%YXQ*B;vd7{QsAA2X zlf{|AUX`>0)r)Iq+Ujw#41$D7^Zw~CxI0h98vMD(B<1kS*5`{#Xc8k<6xEL$q=Zkp zj!7<9Y)#i(dRnD}t2jav%D8)g!Px+QtXzaxyw2?07ADLcCd}{BDHQ7rpa?V5cJ6g! z9Ne~hej{(jun3W@9ITNRe2?tIv^15}k$lRYVp{%=Q^rvWDGN8<=xkLDXT0$GrP?4> zg7;nXzm^axIARWhp!5u>RxRY9iTBN>NQawh4Xa7Mx22ovoAJEp$#SVRx}?e zanDmRd%|?Ux5#{~X67c~>eQTFpMGUkFHmhWKGdm&{6f1LtzG2>A|yrFrD?Exzf{+> z)L?1gj}c28L7wYTWA+e=-3Ch?)ucT1;>^{rckKMP#nG35xl~L8mJ__3&A`gRm@rhx ze^C?9qd>vepRld+5|o$Zv{MB#OM{+bD*9MjgWP6mKLp_ALMU<9oRp!lY&L1RjcWG8Q*{jYB0ii-K&aJzG$wO*D?>9k!Sk!(K z=Vr@Xl+k@4JC(mRu{>8UZqJat5%qdhhioWH9hWc`CSNKC)sdNrQ+j6OIxMGv zC;g@$L(8T70Rld-pL8YW?Qy}neNv~(>J@*}O%#B}i2Oe~pnwet?cl&;=Q(2#W3vyM z_~o;+lnnuj6G()``Ph8Q_1ZLm4;ygoJfk%-pW7s3c{}NtE0cz~2bfyROAgi+o49#M zvUvCLh-HpU0d@6j*!}8;wRLUF$-PT^HSvAgu=Jd96*9>&V%Dd!mgqW!-4E~9pEJ(s zKUkm%kRlPlx4LJLwj|V2Qm2Ohl&>{6!ifE(=?JdPt6}QEun=*@@)O#XsZ~1{UjBom z#PWw}GnQRGbirp+L*U*@A>u=$&dB9c`d`Va{R(InIPVS1B;-~ryA79&`$#U4Fz*-~ zyIu9RuVZJvzErWy^^Q|zc27GaXHCe*VuC;Ra6!kL9cmmPYS-U~_W9*TpBHatwq(5Y zn4pC13iltdF7Ia+aQhKNdgd9-cJzw^JxQtgYatj|t*!7N%_I!BKaJosF%A>sl3wP= zG=>Ggu8)$^)>z;!ej~Gd!fn%S>CR?>)gd#V_t}d;qlzI3Du3%#8RLI={*!Ql0~xYZ zD>Anqm9X3K5T!rg{%F2xIl;rnkL>Ie9$jH%XP0$xIb*B=Cfq>6!{ygSlj#el_iNo- zB)JfY>%id?l>@@`~>f?P$A#)^PVOd|al!*@^ z(;Jya*A94emqZL3i>Tn_4LmALQ-zKc_vmlZS9NO;YeKb}=bDES?GOwztr7d57KD0bNL zaCirdVslVy_r|!xnjmR^|Ej79kgu#PKO6d<&?lgC#TQQcL`M@58SXAPpGAtMByU+) zG8#b?M#@TeyI547#OaiG->wloI}?iW+Y+Jogum$1<%$-QFDz}wY4FG4Y?ux@987~iOVcmb z>P~-xSbIYyQdnXCsfXQ>i4u1D2XrTQOqk$#uB|4p_fc)=QiPbRFvJe5;W;{;JMU%= z7^9kqmG=LW(r&dQ!2LzhP5sAz*5PPt?Q{wees;!FZIrfxGTA66A-sAKwm`0Bi0?h4 z>(B_sa^y%}iJBURFaU(Su3;lFs1#3`2EUCz(c!uMbqT2q7H-b&acWs{=^<^|2<-TC z5=SC{6&@a5(pf!wz~Oi6IJ!cA+30&?Pk}ro<`0@R?DKnk()mc;jWcX8tBB*<6HoN>KJzxPhEgj&k z#GDNOr2o{}LsnD8^5Ns`rjTqjCQV&aU&L`7KVXWEdr-kvAVRe}5Da`Kt<-swo9L{h z&Gq~@RYrC{b(ftTL(Nz1&gB3qgb<%nU&e1ald+V(la2^uam}vMqu=&TVZM%YPR-B` zf!Linzf*C3xxQI{_CCBW5}V$mye{;-eT0kLDLp zar)ijs4t8TYsJ3HB{hiGp}u<@Uzj8cS<>VJw^Th`*{+YdC#R>x1Exn&##QQvcGXNC z%zvYpWC30yh$3u04%l%vOp}DA6M~<3Ypm$-`N36y9NJ)FGTgxq*iRFmy&X&80f~%% z)qZgKv(5U^HE$Oo0ha}|W3)(bPIlIpY@X>07tIDQxJu~2uw-+=UpXSP2f!s4er^|r znLs#ZyyM+>4Xz0D+qmzd4yFnI0b))~fnsW!Cl`B7MB{m6u@4evtjoAQ zLywQtoPJhRHP)H$y7r$ei}G&M+`eW6{NRu{q8KFq_ux-$TMa@{Wh;Cm<^r$)FLq{mTKa_JHvC8&q}|c%TxO$uzRz*-t>V@55v5KdqLF{@!h)*va*r0cU^V=2Z-)B4!Pb$$^D~vM4g?giXWQi?C1(`VGb&a z!vLopX03mnqlG42rG;9$?LOU#BYaoUirxEHt`C%$og3*>kdn~#gG1aS3LY5_=8Lr( zkWvD?xAzO)k6kk*vVr`;Z^_?WG9cU_XLfLi`z7DYj%6*5{t{rFC&;rQJ_QkG6U;~O z))=(}q8l3VlP#@*8RHziv^yH-n{91Cyv?`F_VNc`nKEF)oirBy78-=)lFDl0FUj;* zp)LozEET!4-IZlGUZtP7LQ&nwC3wlp9y%&61H*`)m#}4=2tHl`%zINfV%B%W{}pE? zGLfPQtA>>%)BkbXEiTZZSxc8S+-?U#nQF5?da!<(4RdVbJ{>6mBNGOl9qLXS)kGQTGKg}u~8HCCO~_b@fpf)I2*t$vHEKqR&AcOp^u ztv?E*zzme4Ts;&>DUmXk(}!Hg)d&36zlg{RB?H}ICrFZmjkQnieR^7v;ss%0$?l?( zN()z%hAAaS+}?ztJ6%7sO->m%zFVp=T_6NMyq7rGAN}!7AToK_Nzz>jI$f{;xJ)D_ z+LMC8Adj#2@zZQ1DG=F-$pTyRu-^lF@x5PSbO0^$gTASH7jQG%+j+~iuMXk>Ku~@` zfpPa4(9e0Fv;wECw5;sTNHVp`#vO3t{tpvviaXJp7}LH;m0rovZckrbaX^L(`MEF# zI1n{D(DJ+84Cr+5-aYN zqUlPsi*t4iaOY1>(^V7*ZLYj_m%IT(3R^Y`q!50OeFFb@u0cD)o8~T*lbs&iaD`>o zysSQFPlBNasBEF<6iuZk^2z>DikqdsRVEXLV$*RpM|079c^Ds$J7J&p^3~N4Q46o; zh4rfxLNKa$qGwv+u_t~;4=)G(>d${~y{I-Hb6Lz5DRI1xSE)m_I39qp{cW-5BVe;z z#yV*int88VB< zdKL7BJr(ieS0L_C19BS`*&otJL+QWB2gTbIg3Ok-0?TM}Iia`MMOhG4UueleW=%`x zB3r!`+KdTnvuu^0vXe5=V}tA9avdI1ZVddznkgY8!$6n@SidOOr0hs;w1B`X5N+OS zt%K+M;z+N9&*xLL_NCf{WkWX+Wth&dNJMh5mtOyOmo55mwyllg6!A8@hXL+-j~Ddm zvoHJYZ+>>0KV>pq@(>fuH|x|r-#2p^KupUZSV-A1)^5esw6!f6yIcDo7qi+#`Twq$ zmauo7%!M}{mbVDn@x%U@p9|cj66QoyWW(M>R=PS>8%`Ga8f$i9Z>S~}`aRsEnS>RRfFI`eDCSC6Q zJkIR42DN|`3uJ8b2{LIuY$M2N^&2Hi;?qc9%{h_V^uHtD&^mJ}5oP77006h7pKM@Pop?EhOxW&w<^2-)Hr z%D0cZe_CHDl8ux~@qnP(yRo~uw=N5a(7;<&YBA%=Audo|L&TRcny}iW`Z+{JkoW$g z_f;Qy89hwc)Cfm;>?Q+M>k~Mu^axdhJogXykx)P5@z58@l144VgN`fhhttlS`T&Es z`NW9y^nxmMVv+(s5ZoqmGsh{Fc?ts}^mAjwn;U@D3pfH=_P)N&2=MA-U|Bbb2SRJ- zD)caeZ=)LiJYhzm@0fgLNjfJS8!3CBy)ackqWgt@Yn)=9VJQ(M32Siv69^n^hVt>o z;7x5-ZR)aZ4}`v@%1s<54Ob|HL{TM3LT_6)u|fX%-NAX9kGDT?E$hr2v4BW*Sbw|9 zZ%?$!gk-`BDH9F;>a5g=iuDbqQgmeaDF$4gHWLaY1B}SA{2eOi*2~rN18k!MycP+Mr44gCWG#9p`4`v1q&+B*ZMdFFW8j z0EamX_@N|*X@K8b5rLUC8;U6B3kP5Cz4kCWTe>wac{dCU6I$lKP*WPks*hp<;~C-| zN(wc_Ig)8bp?bd?ET_wp7lroq%YW44XMFeO8_0F8-tMYyFx8K&07U+fwzjEhQGlw0 zBuPZchyxvwf}-N5$FDzr$jHM46BDoL3SAcFuJ2Z><~$iowmDFXh!|grVo1tS0I3MP zM*lb!Y7NyW0w8Su6iV}pU2ePS2@+@bWT}E?@>C`LC&y>^XsGm8;9LTz= zD#JhXWpMcRr)NBcCB6U=+bGH{;I9qmcHi#fKqcd+$2TZ~cB!cd))ybj=o_4XPI>7< z_RdXG^LWa$1R_svLKB*qXnYNhXo<%!MXyo8D9MKp~zmG#ZaL?|GX}sK@8@z z*y<0{8c9Hh8vp@Cb2+X$CET6%!`wn(!zXMGAwDP&U>YDrq0r<&<&mZDUpZmHQQ81Q zYRsCjPzNZarJ#Bx<=WUwQ<2|VEBpjyJnMj+nfx~?8>mwOp|_+iQ<;^WSmXSUygv#* zSUAwW9u5Oe4lsL#7Ds4Mjm5!!^XBZhHqeYvi?#+r1559|T@fn&ubyVw_v!t-{Ld8B zF-frK7BoyJP0NrPfFHmhx~97$cMr*l#uf#JNnD(F3LEjghtcio!PTzn-?ahf0|KW^ z0QQ^vvmie0&0>_1!|HtLBnbiXY>LggpG??zq9n0L%HHN~0O=PXZaL}TlbJn4pIM={ zHXnaioxRB+K=sBc$Waui^8&R;Qc4OF8#@drI3>Ad<>itp2_D+073D^@nK6lpkt)Mt zmMvObTwF%oXQyXaVI90&+}yNhFq9BjA^@cOwbYIl@4zbYP+xig$znU8J8dqM%1wjq7W7ul;xP&ms53J$XQX$(0ZI)yDZ*T%kYa z!O2~HzwD<2_R+~=b50gvyeT?QRC^#}d6H1RwgB3MHUj~WK$xC(+Uh#pEC}h*a+4wm z652Huq{Ibq8Q6VE!m-K`n|4zX89pW4HlJ{KV;C^EUTj4un569kNu^&TWIzz}ty|Zp zHL#z`bRACbsC$~2EmQakX@w7%#V~iBmeYXJlLOTv;s#rLWKl!zzf8q!TF&l&<=!&p`)W4eJJ4$^Ch^WrW3@PYJ9H%fB+dX+aID6RlkEPp z{B{`j7=`Htbgc=0l={y%`lqsBh2_3)#v{6-3G2*~06r*_6Q|;p6FV^{cQ1{XJU2J; z%sF#+4pdme{_E~%*u>f#Y3pf$lgYbcx|e~)u`cKjI$2Lx@R(FhaeAcPJx=A5%jk3E zYDwEY+NG#n^H8tf-gUjrv02bbvzU){sB6!7ltyVQK<*vXEi45o4I)*d{jQRof&S1%Y;_9^BtE|ee2So!V?CwTE_;Png`jj+qifv3ff5yNd+Ky; zDvunR&M9!;LQ%|T*_1xvmO-e8_aXUko$ez8=(471>fh~OK(c<$B(0quN3DaOZ~lsi4g*1aQ< ze42R*>C%#Pd?3vLR|?JH#s>VgZ^Lu?u7XVTeGuO}&FI?yr^qB@6Ila(K8HUe$%}QC z0F+f!04{)ieO>A}J7*|=ez$q%IO@#Xh5tE8TuxFFk>+|m76%s!Q=%`zV!-z%2Kv^I z^@(LQ7L1D{f!V2tDXmsEX zX>d-kBw^ztvXonM3BA1)#DiNfRVOxz^~F}`ZX|+Ro|)0V#ryjE>JoQ$IEsntr-UiI zOV?ljY8Y&j^2N+f2Q|WqS3L3u>clMV5HcP5qr0c&r5dXR%(O5aXeH6K(J(hV6GFu* z2(lFVF|eYT=`bdh8 zDeS#>SJK`1^l&SOG|bG$*OBiI45cBbLsuARK=DSb@GAclDwWjJ(td=SD^?!Z9J8>i zAEwhzA8Ee3$jh&(7a>BAqONt@;~-LCBI#a8ZV|>31pjG+=u60O&uWB5#nXrHhf=XI z*SFi2TohO3hxX4iRCVC=#h4`poG;o;26n~OmdDS=#0B|3BZ8jY^GxoF{gvT``SKVa z3P1cL8=i~vDkoxFh&dJ(o?DnMa5d!}S&8(C+0;iRBEe7966jGneKAP6RB#Ghz)C(+ z|0E2)+4WezqWrD|FG2lt>X3-ZJ-;m(tql%}oWP^rTKW)$UYDn+LC|?E z$b(v!=PAjdLG>JdC##h*hj4lR@4+&rrDf0J@{cc#e1BDyMcs*Bce$6~>lJ?7(J~_X zon5~Vp|rI0A58EMDQOjEZf@*c|4aEQv5k7`*y3lG_0G15+!n{OZi6tq?VTM=5|X&9 zy~%}#Z>)yRdA5@|->!qY?pSGPVC(AYzFjLz|Ed02sSS4CQW;v2eaO7HJ;!6ySBLy* ztNXyS>mnTC8R;N~u6B4sd4PuWYJ#`vG84u(>nQRq@pv{oqu~_sGNuv9n|0BH z1cjGWb~4qq)6Y=x{yZdPm{|)0v>Pauqwtxg(_K?g=9gaVHuAreCYuDOcvms(T_^sC zvzAT*f!LkCHn0de8g0;F$qYM!TI)A|Jew$94wY6J_o9Ny<-^t@9fKicM{ z)T5n4UEMKNNhk)cdgJ?NP~IQxuqF-r9_)l3^|J%`PC>0&l;!#!AVIo_d=~@h_#R8y z#%QS&MAN5}3Q~U8VmZ%^2{kDG_dm&nKB1(#kOzF+b{kt1_i)CFNqfAKey6PYAU3nG z6=(x_{95z)@N%GTH%|d#FE91i#P@zw=;2_%bwJM^7}DUx-jed~oT^qwL>^YfjZ8dBp+Rw;Nv|;_J6mcKgxKTnHu8^9++zNVj(5HI;d-XMm zrq|-P>1+6(X{sk>$>o2WEmDhKEaVMm&K0BYu`n?)lexE22&mi*zJC4c`Qm>xUsYOO z9%{n=5+Px2P222L(czoZ03RHpXldB&s1K~S#*ZmBP@BLc&$)k}Yy&r<{vVpY0xIh7 zd3))WZUI?JKw3arI;5q$y9Md)mJ*}|q#Nn(P6_E2q!B5p_wM)ie>rCl=ZK5$eD0l@ z=b2|_A~L6kqrZ`GY`Z__)6BEF!>uqqmwzHa)M-PEkI76>sp^$B)!FV);x!rX{t&d3 zd?t}&7Gs6aP#{!KhUk?qn#+s)0zLjxvFA$=XUv@)e#3M1Mt&>%&&NW+cOuInPb-TD zQRvD$+N_^-INVng4m;1-fGLH|pz)wRJplXEDpY#UzJIajkC#1Ht|!47W%l{r`BgtT z!r4~rxU#mouVg@%)l~Nre_42A9QFW%>GH;{u>buuRRun!>&M1ZSJzzLM@I<^!9TY|1fS;|saYKJDJR!H1vQ{iYu@_; z7moW#FOwLeNqn3@2Gr*Uza*+1HxO0r&A8g8yF&aM4eQ z39*$pF_FDo^dI)MQXyT@`6d{^TnNvO&?Vs-nYi6uUQ;p6!lxHJjWhRZXb^*KJvojs zID^`L#w1z0{z<68?v(VquN!F#UATVD&rd20)WWkUEZad-P@d`mdyLWYH-29U=KM2F z4`|V9x`{N#3&`w;R5~`=s!{_nNM_vV!tT&*53j}d&f}@BO}4t!jO}6Pj*rHm9XH{J z&0Hzrm<89!$cW9or-}+LkNr{zc%hzpgNes48B2t$%y}{rQc~#J3|08u4%93mH(-od z{|_aR3fc8eFp4Kjdv*#76LqW!=`<>HXdE6CY`kV0hJV0N?fZ{#qf+ z|L&uIA!-r&qr33#w*~Mq;Mv-rCDLw+IU~gxzHHCai4Y|QjRRIBTiX%- za_u2^8RzRL{JBp8%r)0)U+I0zS8~GRs@MjPT9@;zlRN2sKVAHD9+Yi6J7!&+D}1== z%0#8W6F*;mzshc_@NAxfKOO=20I;kF>QvB4ssQ!jDAn)PnbgJfq7d`htwLO-<{*e> zaP3aiFRH$ifP1z_nExmKdkN9p@{#pPOa9Hn245QwErmUKsGdIpL!ntB`(E59)O0n7 z#lDzK@pM+_wpWLUSj12_DPczfa{DuCVS_hCocjlew}yZ1$l`t)IX)LKWb$4{4qPLd z5>#iGRImWb{QKcsr1osMzBap5?I)ngEW9&2& z8b0)>xC5rOyJ~+zzE&K1c#U~3DprjBY%j8To!9+AMR1ydbj?6-HYXw?Vujc;A1~nt zXU6zG$lBKg+=|1D)5wQLupbS1$H#)hwzsc0VhK;0e$HNG0fuCf8gNqRlp#X!Au9Wq=TWt_;t>3yEapRwK;7aK-~Tab*Vjs;WAgKFy+3QBDpew4 z8@C_=+}Z&1qcBq!`BQTpVFTsp;6sjm&+i}?$?cH{tTy_4jJH1}%(zc|b0zO-HQd3v z8SSP{($g3#w2bkvZDKj+hW(KT>YrPoO-Aq9<8S>e?(|Fr4hO$VPAMgCxp=}+l!}ms zTR>7z5)${Opt+_Ms(wilG7v3`jrfQa&CoIQE_#HV#RSvUX<^FfkC{F5rXzbFBWhjz zDW%44D7Xe21~Ar-dJ1WX4}2aHKG3DzTq=&OyFUMLYCXD_fe3k7qU>idUuyiRE8&v> zc{*V*@8=`@84X!U!e5U3VFF8o7}oLNsSlCzohCt{P(6`X|JI)#HIw{^Uuh}tP2Pdg z%(9(%-)$G3`T62tx9|%F7l-MbEL&#QdeF<=%?{eUi)ExOSV#s$`h%zn4!B15|anf$qbbvzJYQBq)$V%kB zRvg@EWsAejbyWk!=pab?RgQZm$z);JXO)K>(QCUh4y|@D5$|`nH$QLbxn&;wCmZ3r7g*qz{pi>j^Eq~nJuasT zPwn=^ek_NSQ#7Z_O|(2E@{ol^bUxXu(~gUl=S%V4PA$1()8f=9OzJf_UKV;U9Bgn|oL=utfIw8ZnjIN9o*z>G z#kU2O=Be)4`&0{z|2-*fCmts7qy}Qi^YvRl-hffAw!Y)ur|scjoV1}<4%jo{0D|z( z8X7#j9VNY*|D+0FT5RRzo}uq0p)PenMyk{G#`&adn z-fAoaFP8qaTUPs=k_s*|pkX&FyP47@g=E!pk~b6K!gZ9@aF(S7WDEEY-abZ9Zynky zbBOBo?d`uJ3}Cz9+-C>rB{FKJ)AcoZ`qs}|y!-EWuI&a?_&c%J(hVVtS{L=n5fGu= zllFzJ7DGisJ*8ic4U^xIErkZi)WdXst*=w!cl?Z6@j1U9(t^_xs0B^%zaQT%SyAFc zvJfNmGGJMu{W_lGI~v(`wbRp*3w{|I&q8+iDe(MvT9_hJhu znoP9hi!J$DF8aNW{UhFKv3271Up7Vtvca9dCoPAS{0LoKmJ@woX;XOd%S&S0!FZ~{ zq8vY+J==j8()<=G@BO(lVo)e?2G^9#-=SUyHeB2Y3@j1*cef|<6ge`oMD=H|zyGWE z^@-R&DD)3v_(hbu{d%QJL~a63b0w-jSBHNSzQMf%?_(>SW}V;19RrE7RQ~}srH?

=p{ParUliH3-M;4mxkT@oM$Ork%Lx)%G65Q1 z@)I@oAbQsl&Ur`6hmVqMFPcZ3;&UO@QNHT-I7$qj1AD~_vNuMqL>=pXc<=ou2ENvD zuOFgcUiK)kkZqg`%T{~L`BBi>Y$9_HmXwEyiVd7;mP7PJ;E3|||2fYqqra!DCuYSt!Gt+*c&MsGt!10v9~7d8OAYg{lUs1AaQwuu9J8Cv zmj<0>fLWIS8(w zypr&aEiorW;fnsR*B$SDZPl+WmK_6-0XBHlyu^&e zHR3Rt|H&g0O@zOs@4lb;=_5#xA~FLH^%d|Eq|@1r;kUN74t&PJUcJc6!v$uWC)jET zu=7EE&ldcol3d~=Pe(^b8mGBjR@GvYGtEF8Mf8EqE%pyEF~kWhoiQ2x%;MH@@-5XM zsH&>!=qfToP*&2MoASYg`A^hr#m!QwF;3x18oia8#7V#1>~^n!?&ej4b9y+sMdgI( z{HRF&ZnVf|bEp7FAmo2M%9L-RyCrG9&%d9B@+ePPMGR5wyWthCEx|XM4gB;~ZKxj! z1GL6q`CNF-o>`!;Kov?xB6?Tmq9VMN3S63ZVR1lNK;Roj4H+WwKH)ric^fr8hyv3m zZ%Df$o(tu-tB2Ecf-q?>9u<*KBGmz^4?^<-vKM!J6J9Y`7hIbufQE5&_g;SEs(^lX z@$@jZ#muR%57$&%O7>x%qPsW8Q8b>{UvmE4yQ-TXr%xIi!?(-T9(%Hq3-H+?r_bi3 zN1I;U-&k3~c)DZq(Bjf7eeG{PRrr^_7Lc?E$n79J3lSgnjF^QU4w29dsjn){b0LC7 zmx&akqcJQGw`s~u)|cDOZRGFqAXnfWh*4M#8_VJRo7swJrOWB}s}7QPum2;~RQ>i+ zBZlH$5n-%(9kO7O^OVmo5D*dNDdh;?9Mw&-J8g7%H9mkrvm0>&CvR0$RI;kP!7i@N z<755Pk6HZ)*n$DrBKJ7UjgD29u0d>*+xeE{3fL0@n{s{Vqc0_e z3=%X3+c61=Y^%pY)1L|6D(d8Ht7%~g_T(*Y^|a7>Ky$abeBeJhUO_Db(E>b9?&DLj zNJ3z={vMX*H0}nhCE9BKM&_3)=Qu-lvzx2SIz2<$D-y1RNuu$RiTx?57e%Mj~WD>4);P4P9QA;Pw5`#}kb{qz?njgsV>O zg#k6@n%IJFJwc{e$ADY3gxvn;T4lTe!rW16JSAIQipl_I!qg=K9?KW!KoYJG!3PaD zS(Tk*O)mh3M|;w1Q>qiry!`ZSYSLFYLBR*+z%Ln3@UxsRDBtMzbuQW0htd= zFD*@NzH?v6{qa>yvMFd$rE6m!y^9HdNUuqOFIW-9Hl^hQt;*n&!|>+W`HbQF2Q^lA zkzbKK9lB7wULWW6BZc(ur$;%16&2f4bc~oel|n&T&BO`5EoYO;ZHO;e`+_W{;hIX! zU)Pcuw4!Da5e9Vrbi%A!%Z%%(m5cdjMFAw6{w61r-iiPtp^uR-WDgFI4ONu>+G%B5 zj06cQfavKMS*{!@Xt}+ZOz163tr+}sKDEN4d9QzX^8%2NxVw&0Hs3`YWa3TO zfA%N8^x)YYpGT?^avgrGX0q8V2LK#ZRfJ;o!Z-w|{nD zzI<7%*$K8uQiAFGlK1%F$*&F2?5W#R{XV@pLr!2uzveZa5VAkNN!6{P-V6HmuzIz5 zDieJ*_~Su!ikngX;!);H;-T71$?!M}`36u_R*besfq{;UuXAi6v_^dlBm}H$rB{-p(r&&|({!&cyBC**jG9A4u2pzI* zXUsS8sIqB07bxh{^oLz%5M}dHH$C5(gjk>U4*_84lTa==NY94#?LnYo^r_`Rxl<(E zGAS9sFcxU}=XtknXpo-6S8M+~vB%fhG#VN8&$&zARB^T(^Nt8ZqX!2>ehK{RxbHq@ z_e4h56APEd_xzC)yxP_9d2+H8r2z>$v=+v741K%#_s?WFk#2vbnJbP`$ZK`Maj_N& zly;g=4sGy3>k8ew&)^hXQqivh0QlzP5ee9P(0|y$BO*ct(!;)1HKeRj8D?4CqdKgNLxn z(8_v!O+!`!RF2+heUUnQ(-4YB4@#y~46ah^CCpB$yW+=7pi&F<+%gedszWXZ$_CmGd%mu+@Eyw^;gwi^ zp8OOYdF{UX%`@BaF*#P+i+*cuBGw~*R5s*-|{KK%Rv+sFep zE?ccl0^iJTJwrQwM-6o$-c6aS)+ot%KHV%^oI8!lw9dr{r4yTc?Uc&VHSGo}8jEr_Ekd~Fq$N0w1}Mj0 zCIlbu1ii0zxdRd*?yEv=CTgT4uGdaFz7eSMrDzT#SU>b);f!`e5FL;@o}}RHn{TO= zxS+u+purt~3SZ3kxljlh#R#)T``bc+#8#QFfGjEqS-DVDCk)^=P`l7`M#@g_)SnhY zgt`drru^x#1T666r@KU2G>d%7HG|a0v{)}pTf*p)MvE7-3ztm4iBdGT<|Ms2&JVMS z=e^V&5-UoV!VIsoQraniBmJDtjoS5xq4j?m*ukAYGrOBLPt?fnBnmaKuFGrK$)^Jo zm`uQ&w*BSCD*EH=!v*Zag{lQXvm?~^h4S5CaP#XDo1??SXfTP@^v}+4&oVvK#nQ&{ zmDg{#{d59)tJf0Q3ROvGS7(@lGc?nz*rhPTDdZT&v|8GCJ^lzyzm~pyugB_dZW$STm0pofRfj}j|1FPkYkuB@E>7Kq?j;C~di~>pq#F!XZ!s7QvASFUiLs=OI ztWJyp1Og%en6JS~#Qc`=voohQz!^1d#|a?DOnHJ$i_gIb#4Z?*05<)gS$_a&P8z=( zlZlB*$aiUp9a;3zS)>34Y(?>iDp?rXC|=k+7ane^6BnF+E*KuKK`{VscKW5Jwta6c zp!e)fzg;YLlTHJQHAYu=(1z!0%E16Spts~ft;)kv;$0g%JK>!o@z$5Bk5)XJmnTX* z@L^X+?Zl^)x2?8Y;J#*D^(0i+Wr)`ChGo9 z4##gvPYrszQvKWZ>E1C(G<^QN+rwCyDG_>qurgtgkmVLWnQt8NL4%6{%E9w1Q~K*z ze;p}=UTN2q(?}wtiTSazWhv}Ek~ysAs_u_ANA?$QOWeolNDOVw&=1miB!D1LzV58A z8~4j}blOL--AI7)XpN*|D|oubxj65FMAZS%WGjD8xvMpX*BQs8C|uh}s0C!Bp9Rp0 zUY;My8}psyw4-5A9R>8AwN$zNheMI75+jCoS3UQ#-nj1L6e?tdffthv4L3L8k3xms z&ED`;;d^gwd3j8tS6Tr;8DI=3fwQZt&#PgLjl5Fvl(8^+|MC77^9c`^QLTU-tbOkC z)hF9*;He1$2?_*f%NEAB_&gX%-+!?B&`LOc^KltX{@#lLxuX?bAkOf+Qju$DBKj?1 zKszu7G&b}med??8OAWzQiX@b8JxaYJ+ZQ~P;;`^hsC;MBB}a5+c@+zo`hY>B!d&z& z2VrCRp#!1u?hqx@mtSWUTcwO7olN+H+Mv^gCXYyB%Oaphjq z7X|8hy;Gg9B$N$7*7Xpt$Ux0MMQ)E5G~MAml;aN~KMe>50Mhsf7IHu9whH30awiGwX0p(I zB$yu+f)!>$zR-T1MJ9nc(y?QW3%+73$`j|S&!Oi4VUNJxk<%qm14>7El#L2*wm<7)I64DA)#Nx^f4-qz|5jGf zncY*N70%9aax_VEbZk-Crw@v^Ce>?#$VpkNtBi2u@p?Ej^Plr?hlZJ@e2U{gUBRy3 z_dWZ9iJBo>)`S-IRY|fR{$IW;3c5Y`1i%R@MoIXu5Y7%zQvLfm#DV} zvL&i`Yb;xJZUg=AC;%D!{I+iS*opv|Dziq+{+$!k=Oohl_b?Ks0Xr-LQ@vj(&3`0f z6JpTDOIStHX**l`^y`d^oWr!ATH)V~+q!l+|EKT?g`U^eRG$pz(2a%?`*27h`A@hB z98T9ZX*SnFVbX!9(f=q|MEeU^>$}A%{gd%kF4cG3Wh78jlG0LeRj^vUeY7Nd}i=6p;PM{YB|J*r8!WJQgPoV555bcY>$v_P)z~UU#i=_ z%HAyg272A5NC^V}tmcgSHw__rxhXQCplH^E^;_k}W6t>Aa?V&9dk~LQzMVR!6!nJex2`1j`h>z?}uu z4KANnLJ*`n=S$Hai8zzlL$LOm3@8w{E50oP@zgr&!(-dt>v_tt-o5L3@e2}GNNy+~ zFIClKe+>4Sa^mt$)IGdc);8}Q;|?bbwXU*!*t}Rm4j`1rze+Yjwtg4gMd+@e0jb2U zzoU!~e4Ckr7;Gl~O<~a+_uw!z?S*6iLm3w3A1<|tMF3pTXg~NX_vNZ187b(vDZ&xa zP#)@E1dRalWBDZMNgM7)2NaULXDQ_`satgZ1#(Fajk8J0f7(sYQMYv#&qJo$Er-bO z#Qj(B^iE0$q=0hgA+&Qi8!=@cq{g7^*$qs3PrUJxS-5dnM)PSrMufZo8a1yXDI>iF zDRxp4VRh!B05~HTp~yXnl*D&F9vym&r11WMdqrG}h9)pNAOaQZUo*B_q zG4v`q!iex1#r!oGei)C?^)2$raBY3f0b>mg6twU`!C5eKYVJEKB!{v5*5LcNBHG3b zdYE^_io(@z=$w68tX@Hi3;|p4Gr$U&j&liB|NBCj_CZN^?D-F}hYU%6FDq^@(_vvu zKYwmjL#>$e4?LSUNNyPD9(i~vhh^UtQHi*4ph!Ir+>4 z>i@IX?a?(2OaQXD{M!w$?e;~|(C@#tM3Hp(Ek*~Ei#Nu1vg3DU#iawFx^-i{!06-Y z@7;%}{rdEWzPkEyHT7QG*0HBNJ=79*pKaxBW75tAuCiFwRt>(WFGt?UQRZ`{i9(C9 zjORn{3Uh7J96DSpmab(6U9lluCXj(|YQ__ALN4zPuCvX!F?)1-In|V&@fKtLU_UF# zj4*ASLhphXE527`&X+943Mf6;I2kaT+6HN=R_)>UPlr*5j0-m{y@ZQq1}x4TWFQMf z9+b0HA75AZR!Cq2Eb`DXK}t#0Q5F%!3nN;IznXyGfYl9g_5rU7O4yJlEgQ*`P*osH z*owX!bh;NqLmy?Txibr-36HiRueKUwe6{3^4q-187i^&q|LX11BtE!%R6ZAwUY{29 zO6so-8MVV(3G|gkVajy}p};7eO7)$ezO|56MS@&yglt`KZxb$@FRTe*hg4$1+VVtF z{_$gKp1rREvZ54?i)!R%M;Z?&el+E8yGCIpy;tHz{`Wz40`dc{nwIFJ%Ecy$kyK^1 z_z6j9f6jY&vEBOm;1tvw)ip|vcXa5Otv{FuMCL9OyW|$(@0z*zUQk@4}f-KHx*GODarsn`R6v_1%kY$s-uuR%}s zbT2-Qt%~9%C z4BN}O2%KFPxy-L}FstrB4DH?kjiNa(rmuovEQ8C(lIcf4yK|pBxYCrXUwOWn zvOGX{wR#?8`L8I~Q$AP!pDS_y?g9N57dKC+ixfyquU#ENU?Fdv$ZoJLc95X{y~P|q zf>)9x}z0&{EjRG|$cLZ7#^p(yvQC!og`k zG!$i0oCDXX^CQr^z`4z9z;jo)(Vl%ZyD-Z7Pz`@pzk|%wtc<6x5N-3j9{hC|dp0;> zgFo5sHSp{ScZ{l}M^x(-9IkBxP#1I}HUz20_`$RJnkN4%`up0`^8D}+s)n3C>}4e= zUk|o5*1fZM-AkZGJh{Tanb$1odC%-$2gimf2P6myCMXgGQ`H(ZfDhg5KXu=BGN>tS z`2R)iQ-pMrw_XJC#4rQCexn`*^9n-~c0A-nr-DFarIAkSg0-613kw?4yevHq>Si!h z*nL_xa5s9LpEiecP@%TlR|5oFK~iE81+hS9Vyf2qMsoSHwIHtHaQd6fpNh~lEU)ue z7ih#Mr|ecuX?60)oj!{}u2M{AE|`y;DjGt15%S8b>p>J3ck{69JgN9gdnsQH%t!`I z&9{sMj2o6b=#KBrkc?y#jW~u|S(!^VgdCyn@3ji=y;pgtN!;CSU`m(&g%oM?&0%3M z06Vdn1%^XAGd?&^7Lg~M9YM!*d;tnz%d7p|uOJ8@PgjY`*yJ$+aJ#`S~%fu5v*;%3FSyH7yM)I^~H zp?9H(-1GyI2Ige#GN&^;Tp+eF20^Um_Yji8o$vn%B~TO6u z8esf!(vRP?Z9eb$!^{SZhC1hmmNX90yX5H6xEREth*~ib=E=|Oy{i%EOi`nMM-trNXV`bs5S z>;EFd^(>d;0F6x0J$e_&zL}WHHqDLNF`(|S0zNIAyPJF$zHeev7hXaVC;6pEu{3_n zaasUq3~}1GT>@a=hn_`^Fmw1# zSdE4T%0zbk4&p3d$_Z!q<@n?K`YHnk`^R6%khjT_ z@h=_8$?le?SXYoI68=$rBMf+uN0x7|5B0U0DE*Zc;`0uc4kZ!TcYhqlTi*2)0Jr~q{Rjy!b4`+m=dCe~y zBq`ce_&qNQ&Irm2oMTG+_?C3*3%iPjd|NfJf`QxqErWUOb~f}~T^UY(o%u;`Y<;=7+bW{3rCmSs6NDYo)@(-Q z;7E>AH~oPKEehz-w*+8V`rzsP3yI)J}Y}-NHkp!x+|DnC4X4YPmTZF1>n>$}~L*<~z!nfCl zlpZ;BzM}zAM7=b=NgWCe{g-|QlZ&0%@&aw|Kpf=+cWJ4;mivvMSNj7wy>A^p9eOr( zYtVLom#uC}C@G*fG})^?U!T~mE6eD9n`Z(CiJ^c6mH~0!gnWS=K^fEk0M5ruf*FmF zPPEm;9vBS}SM)>H zP9;HUDiNZ*`jA#c7>q3H75UC{_Fy_&0T3|}g}%vk@MqjR2F&ODkv21cfi~su!?2yy zQNM^Q*_fdOhbvyz?`&tly6pV&vmTNVUIG`>t0dye3+`dVHvtiu@wBoYrH-5yF%x2S z$d7T9im}4l-iRe^ue#5E+txgIbmWKA#MG0ewHwAKGMO)6KUz?R4|5BOuoK2#%Hhq- zxAdBnqQQ_`Nw+kpfWr=wF73;EP#K=xWWh1oj7pa{DRlE;@9?Xp$=+xA1t;N~tR@RI z0HLe@K3LFkYNnwis~5chX|)^^B-L6gwoFGB$p~veH2bh-O%~SSMQtyOsgH_Q+kAId zd?jQ8)*8pyl)bs&Qj?eH*AMOj6rfl!<`EI#SECarl$8~i56FEXyd(jxnktd@tC9{a zP|9)fh^&(v3QbW0NdN72OWdUb=w--@Dh3#AT>t?pEeAggbCDuYpT-H6on}lVmfptU8WL6QHdSQWTb%lvVm_qnmECnw28E`B#S)H zKxg1wBb||8rJ_Xj#43W8R7#*IB?5)gv0vpvt_#?ctYWVBKPq6|+FT-}yXw~ohH|kv z&%wDzj+s1FN{Q^9Il%r{&7N{6J!<5#iB6!zrS%|>4Li&*tBJ4TpDVlHetnE8)uC@^ zZf;nRJv&$Ri@%IyYy4V0R_fsmbtwmRTn<3X)iz$3@5(|O368cy%fq_&6Yv6?uN!(# zi0`(_Q21Za(05IXBRKtD@fmS%trqKAp^{!U%)RgFp0o>@San=WT$YVG6CZtZIqCne zy$=5HSq&aLI9Ghna@hZ42CQFp_C@t@-lou1HT*rV1PVGv;B0or0CJ7yE!<3MT|!0s zIy>k+ik-W#+-W>`9{ut6Bxy?WXpWf;55SlbmBV(){_nI#hi`a*&*JM0d5wd=Q_+HT zlJPboewcB|$-)bm@5B;}QVuDFd39=&1UOuE?5E6p)6&4B^?&!CNJBF=TxzuRD+E_*SS4>Qv*-S5cTg3MW9hD^F zK2#PzclWP_yPG5!UYm~xK0n^*obyGQF;0hPF}|N)8wTJz_}bt->alJHx7wdk1fxo$ zrx^0ycwdmnS6UlgSk2kP)Rr}MJVukl@Nh8r4^51ZC-~n9GpSo-e`pLYUH&5Yk`Qi9 z3ifl&7qWOQ^r4%FC;}$yqYqB+EMk87Qcf@r6D%XMzS6Q0Tq_PJj~1YkzLY$R|06iN zIg2dg$?_EdvihOZPZ2f~D^$t2HEepZIT8<6=W7UEfN!jx*U+97AJ%^rdB@JUNp~Tj zzkK~&XSiNyRvm&IfF%vPeUg*@b@)XXBZT&cdmE4!xQm9MMHTcf1|KK=+h{Cm0lld6 zR(L0epK6ZyRRRz!(J5vcQF+Lf%T37Mx(0Z!H_~0Z0fEwM+l{K0tVAIDe_EthV{C@N ztfU$VtPT6Z%4B95ERLVw3?>X$tEZ8D`}FsvXg)BMDd+zAuj*e-owlZ}e;dsftXJ-S zOS$@PYmO~Dsi~+-Y0~nZ*{Sex#6}Dyj7ibK8DTL)Mk{TR_R}ErSXL^sQ~2Ddf2DjP z{)_}rkcYSUUh>avs_^>z>jf^ARtc`XWPr9Y=h>W^OTleVUkFr03{9SMhSeNOmx0jy z*YA!OH1d^e-&IPT*z-{;%Ahr`|6YRc8mT;n^G}IhrxYGFMNTMVEGh1rSuG-TJRJq4 z70P!-NmJ~7D62`mHQ-j3Z6_{+!dHsnU{Yh0D@ z2B<-YfSCxuG+a`RV&a68tgHeqm57JWa`4%iVCL}z4+8cbuN>6+q&t6t>eB4`8Tm9n z5$>Y}9L!F1vUq^Z41&cqOSvZfe}cMNah<;P2v0=H{VR)vshV4N#|-B7rsrFT_)r&p zi~M`t9v#5LsiST6eVhppl}HP{qX!rFu<^C#U!hAba&~8<_vgVboHpXNV?}(~OK0R| zZu@9+9~)kcm;P!D#3+zfjY#V8!W0do3)x;t4KAc^1FaU2IM_5krqq_caZ9Al)%=0#986tX z2Q=TWzDyy3B7(;1{1EoS<{?XSak+UQEzEK(P6JFZFpyxB^WcYA_H3ubfq{z^Ckdqp zjRY6BIT)r;wUW10(_B8=Z>xauf8%%edt1I%AeCj6HBP_YMeRHi3XU{9l~4hK75s!f zWeqs3R+OJ|QR4v5TZ{G~a-4ig{ccMTRP>L2dz|j>fC91F<2N|Gm=Z`HwgPV$a(UkL zo91qpV4VRzQ&D0=!^}ga@AR2Qmbz4Q=&thQRy10~1Ff_@L40XA9$6>juGN$cL(DiLQxltt^@X#E23a|3+ z+i{JY<4jZ4Z~tL=PDH(^C1d75Aa7DE@)Qdaz?fR4M*U}2Ki-s+5QO`iF6i7+Y z$*6&0RgOU!6&6xus;SI065G-ji+l0gli07HlO~V(H|PeXn1%=Sq(J)3j`Zv6 z9QAPS(_Y+;6(>wnOMB(-WLz-e{Rq&4vR2IkSA9>)0Pv`evhFngM#rt@b}OApHv+{} zx#(&jMX;jSLIFGMd4u-iEbWm&q^j^5DmVq-f~n%lF)M zaQ_Px`NdS;l)XGu4N2EV4{EU6j@S&E zbDc|bG3(}ca@U_KBnF~Iz8;r}Y;R6B78@XnvV5~`e>NV~4YHC53d{rqZp@mOUIt$E zFu*oAcu4WM3cKi&UBHpRzTgQ{G);a?W0WraJkw*l`I2RdqzrXY1dW;lL|E)^XvjPz z35WPJW10`+Og2C3ZTeOW2}c7T40wKqHhXD4*9O$24p{#c6~1E;PQsyTZP%D(Csp@G zjFk*o0dz;v2IWmn)^}qZRk*afUxwxbNSk-z0{OXPQL7B-l_f2>q()M51vz;mJC(1P zl=V}#tx}egykdK2S^AO*HiZ{7t_nZa`r9OTPW4}bj943@MVgQ7m`SwPaw5~mm-HMU zR)d?5#GK^Fo-60?Pg3yQja9`Qkc@0u2m?~|mJJPl(lhp8Ph!jW_f@%%IONBGc#xW3 z2(<()zKjXkZo+RRMnXZ)DJa4~0urO-j>cHJyhpE1cOL~?<9A&}`Cx$S-N&q+6`k)B>xN$a0FE3? zFxc3nRKPi~6q75U>Uof7y@PD$tB0$rho4D&1+ff8VD&Ya-bOWmAkN|{C4bpN=^j~=sPvfr6qZ({M<3zHIe@*cD z3vg#Dj7ix^cl@zI<=NP75b^8wG=`R-*d!zvs&l_KfBwAA0Q1?BB`+o4sdI|(?%IcK zN_jbt;rlF`ic%Ix`QuW@`y^#d>&3SkgaZVCW!&(a+z?Hk*}&fi>! z<*)xPe30D`U;LegquQL*>8uQ_yF+PSfEylQNZX}B(2NR`F~FK$Q|jgKU8KzCnV!FS zUr>tW$Obqq=)$)G_%m}rtcGy|^+{Y9VZgBGP=${={;#lNVbIvNMwU(O?GIWaIXs=x zd4i#fQjN9|ik!^#T5W$lOtn5B3#-dvUibf<)<(VHn)A+xi=_5AZIItQZ3lFK*W(}M zzLzh2e7XGyF7p>;pLtf5tMeQQYa2bqQOKO=$O56C+)yRt)tRu9!kt|}|I0EgC0&w$ zA&QqJko%r4HE;`(qT%rpoPb)m<}!5cW2a^k=uBc6{Byj-0MRPjeG(W)7A9u6z64_t z1eZl5WprWPZZPKZd(gs5V4ec3|ATF6Od#a~?XZ17JfdE~vj!|Ai`xM&EhUkCbQ@UW zk*jO!VXa4flS597dHP3ycgIe^^Wcxgx;Br)8Sq;si?48}{xUjP^RzG{I% z@@DJ8d-*G16u>@7%>OdK8rG)95AZqzNIiPu-08}O_y9y~<}|(@v;=p{Ea2ueUi2+$ zN)h)+HGK89Od_q>CIKBQf##b6L+P4fJ=VwtSs)Wb?;@;Ej>T7jBZ0J;v+4{$*b@$$ zwV1Hk z-?xp1dFQkiCpsd^sT1nnyUyob)#X}!p<1sG#X)EDWm3-)Eg}X98g9aN8WukRvtFRr z#WaT4pvn8!vReB%5fHu7ky4^-g+xF#hwZ14MET!05tGMfN*heqe=P(Z`C#fuSkWCl z&D7RzfQqUOT&`beKjY5Iut?b!T91xfddNFjbmp@?nLjMRlQxjp@m`Ut?;`H%T4#)D` zVh~@n>pBSbjKGM*Uu&?EG(QNM8YjES2NM>6v=Nt2s=A6eYBH5+>B?2~%T&$F4B9c! z%0(G0u>%mdaGEeb22i4cQk2R~>W4XHL$)wKeTo0|yt(~l7fd%`5Ur|v3Q@!D6d-|U zNJ(7omRU~~EOU~%2J|3>&NlJypPrbZ1bAjipbue9XexqY-Bi-tV8;mBBYkz?W59D{qbAJXQ4PF7Y3 z?vjJ=vH;f$o1dVqd zX~18R!MBk<(n0NiyLA=Q&!tV3W!r-Y7ioR_`G-DQSor+QfXx)&Uk4!R<0*SGI!*6?j`O|HhSnsB8oeF>eGX) z)VQRxco)5)9r>U-$$ai4Cg%YHMviR@n^AC(E$q0AQYn3zd&I!QN#F$DH+fh-=k|h> zA9ryWq*SlG3b??;oi_zfU|dTKPt{|Ld+PDR5!j2-O-BgCnME?u&$@QHt$UWdLDMNf zvBbcglTQ$R#;{EVA6$^w^80_90Y<<|RqukKM?5p+h^S;(xGE2{H*na68Z`6LM+L)m zl9lIEV%Cs1!hJzX0}Z0v?1tTdRH*HYV=5)kDeGf}e%)!r4dyIB!WD)7Kd#;atctCD zAD#^;(nmo+$^r=~r5i;+y1PX>mF{f-5(1JUEhV)zhj) zn7wE9Q}=VP8Fjt;_qLhudAn>@O8^G2(CfVXMw;u*SGqR zDZhp-+0Z6m8w0(K`M~66q8fF4OVrIsZ4*1<7C^iiQUZ^dnjh^Y6nJn@|Mp~L27WwI z7>!BUdE3LBt^FSB;B#}mj|;k%j9HNNiz|lPcTz{Ve&+CG-d9wlTeqa#oNJnaA7@mq zsCzd}4#>r}t{~v{fkXLQLACN8lh@Sw1K8q)XR4$P`uq8s{Cc=Dtn&RWwAoVnN>eZe zZ$5AyB2xTPr zY&M=1Y#POeF)Bik%>tX{*pD;BUjT*AyD9DCd7>yOTf>FfVO(r5>m$~ArFy%;c500Y z7b?PFcl-RwW@d9GVhk{xNQ`XOMO5DFWaPh*YyBk!8+e~dVsW_3_k43P)JLsph#5eN z``NaM@9=M4(b1o10H+c2P^Bn7fexo=0=~$y0_rUZP{TS69RHA6f2zq_%+~pujdeZC zw3&B>YHV6UYX2ZzwW7vy#CK8CPIcgk?Eo`c#acs>vBc(^kyFCkR_g+ z2Wq8uqiEK1JYU10_DlQiw6S1O{+!pJf@1i;?j15nsM=f(fpBQVGC)? z7k$PfUO%Jy{e`3ZE^OUp=jF@j2{{3E8UH$OCLA3syaudZo*5)zPW**{{_v^$QU{SVwuV zar=&nmi3Z$;(T<|gKT}&^+;FLAxQMqOgk0maKWsjWUWky#qZ6)4>ElavSPbHAyn5T z+_vJ|&{pS9-y6_+;kP1YS%@4xsY*e(+;kwzNf9AmSF!n%g(4ycy@Sj;UqQT+8tCady|0V>P~4dZ-%a0-_P@^; zj_4Kg22`x}pFiHvWT8I)T(ZP|FxIS|lgehR4L!QHF4Z^8;#lG z$e;Ie`M1c?_U81IhEA})0V!e2#`N14Pzw)t(7~9l{fnKIH}Krck?}*&I8Tl~UffD> za|gLvmO`R%{kyoMh{9!OTU#*1M*F>iQ3rqwO6TX~%Hd ziJ`0PEkjO_bN)`Wj^0}+b951EPr-p28NqyJ6w$AE6|KNuE%}fKm z-nHYF(6gA+gBJtyUfvDD1M?UV^zL?!CcF$~&PWlHQum99oiU+Irmy2;k2On*RBoR% zwjG~k%6Cem_b-I%hL}Kta*pQw0)mdv4|YEn@DkB{xE!Ciq+byN;9Wp3EMAe^R$NJB05jSyLkk*rI{{O*MKRFvBPKB4r&F%$WYp+=Ppvy-Uxe_fmOpp*9sk}+-D_JY zD}Ow(E?<=-2SJMQnvJ+%05k*X+sUYW^#j5me6rYy1{!qw$86 zP?2+f|HhKCj>2i!MwH|`OA39|Of!L+nuRHsaB*>CWoIFKnLLDVYZTOY!c94a|1*#E z2~y>*2sIJ`F}%F)f1szwdy|2JJMJ1a^QQVX8~J9=#3YT!*A{*#vqJqTY49!W>@S7j zjqE3R3m@o|=ilrhLNs_P+gXPGNJHc;#5HI0V-JY9ja8#$q9D+Lj7LMJ4rUW@`0>QFe&ejXgZIRq5aO0C%;+K^RwkECxq(XpY;e9 z2%`t?KdF0)Nb1`uE6bah$(><<4tBMyGrS5S9^gA<-GEy1l=|q7X9)0i(&CTdri zIS+sLkmijKW!dSE<}U3;NscC4Y#rBxjKgD4bp_LV%>9U2kFQS2MW{+CNPV?9F^3~s zk@=G)4*I`Q%GQ8$$WfdAuNcutDeH7;w^txmIl+)-Hjo?4Mq2_OIZA!QJT5*NQL(uDH z3x=qVrjKDqWV8RlGdot*u2XNtdrRX^&+oF=#5I=Ou=YBSXLPshps^X5u;LOXRk(FK z{~U2+#k)?S7w}KppJei9QcEJrGrQ`$jJ?!U$vSD~fISM+=~fiIa6ad3Mi@%D8%z4L z9&Qzdr?uW^a%}&6xAMFlCp(9UZ`LW_`nyPGI4lyaqu;r{2$V{k1w^t|o@v$8)-+fq zmL`@M{)RSHh!^f2UBM? zs7lOCNb6t|s0?gfG!OTR&_z=JIxp?K{-GmmWFQweU&!^}9^D zEV*#Hcsc#)c1 zlsG9rRJDYykP8Yt%1P9!Ita^mX&k4<<$g6Ln&A@ zs|j2?+xv|mZ=vLVa|+h%@mLAH#rPlv5fcV-RA*3kp|x7*Ols`(H?C0CdWYHElH>4} zTleTAPg2ZSa&?;S)Fka>;-u5fng&N_D@~MdK+mS19>a53KvJe@Px9JG zi4S@yCdHs=e|Pds=#|&%MNOJUSt<45mk2`iLPu_I+Vwfx$g7ZB+x+RDc|q4Zw$3;h z@dZnMXYy1@K#W6rC+1Emy5f61MtwHGj7>0KYVrF~!txSRiku|BGrPW|NjG@>`0lFA z*x*c%v(p3+P=Bne7&5U9Zh`e;h5IkY=h!leqTV*%cC z(@8XAtn|a^=Zs5}6xp;Szu!tV=;jiVk4pbQcukFF_0MeRS4+*<>Zcjh6^O6ZbaGc< z14BlPFa+I1hwDL~RqP?(`h^_}Z^U}RcyH35DNYKwWWpC>;o=m?F8o29=F5V*YXCJ+R zb0t{+woIC?h<=v^s@G2B)!Q$AF|l&YAT~JqS&X^)yRhKlff;lsNn8vuwv}QmH1ghE z!AzFTdNfntf8m({zg_lnwzO_GE(0OgoKdrb=Tyo~{*$`I9^!{C6^hp(h+GyoCyEGk zC`{7&EfE$HK@#4Z@n<^uQ4TiFWd?L8~**IE)*poQrR%lYV+hL(5u8h<-fE93V!{ z`iKakkCKjK5oz1C|A>Xj@ANv)duKX2c!7J37Z)v%ArjjC52Xbr15FCjV1SuC--UxsXl^d{GtQtZ zrS7EvEV$1=jeK+3ZAR|Rhy%>4=&Q=*_uo-nZq2=v!Of#?eY!vDkYWuF?^UpZ(ZyFz zgBKDc!(ERZhr9yKDmR2F!vQNw#Nn%ixR2oG zCfTz=t0pmb(0@Ms`ldbXzSgXP?-_yxLDk~eldJrh74o-5oT}GdEyX1A*>JAxCdims z?*8t{Js6Jef6sY)FCR+{LlZpAQjieqm* z)y_Y*Gx~sKtS5R!8K~VmVi551pn^YkSl+>?K4i`7by??1Qr3 z@_u{W7SV4jEnWILLgsPqZDN!dfoW?_uAJR$$1gr{-ph10- zvQssq#NYBe%YN+sjGU+m>k^aEaqM|-RJl8Nbzr`ou6KntfVJN~bjc6*(z_7rr_H@h z5Q~k}sj8WHegoaTw#>fbF1a8Dx$*#!t^#o#Yb&r)32lFb3 zc6Z0xOf9wb(!0waE`;{`hfvNasezm(aR&9niGZEZUDlp5^1&W!uiznDso{zv;$+X~ZSBu>su!F+NVw6$03oAO^z&u&d?j*gYU* zVh>#$zt!+~Po99gAM{0AnTk0zRpFeR340y%XfY9BJ57YMG$qhIev~`i^2P)rw|+|+ zv`)-=6ri%d>3Bme>*9e07<^%eecA->3hp*F3<&A+ zdKB?_r#%<1(zDKU}Hbc@0Qu26OO3%C5LA$J~&6OFfHS$3<`jEbNGCDAD zK)(~?hY^1pK?6h1rEO*_%f!vgt$iMj6W0?(fK8+#{MTEwSl}oVpnyd0GT>l4wlCi0 zH{Jb5V;fN*5?25|i3*mgBghvAlY#;6O zDO>zv3Ho5Dex)n^Ta*C*ZhoDYT7HS+Y$Y>5KOhk9!-C$9i54uzg34qmlv28qIK;z? zb5a#F&Q`_q#`~7cJAauga!_WEF%UtxeiIui=na*g4HK`|d&{DQQ)Ze57Izk8mGsnF-)z8&&%Pn7u)r_U*Fg`&mb`&sM$NxmfcG|n zL4$=H0gn~#(qbrAf2(uvNztaH&*Sv>^+H!#SBVEoF*iRIJ0DPZ1pWSx3$U^hiu!ZE z&1G?5fGV@_TH6A|M8CKdrEx=f@(AN-6j3OPIPE=`$??8QV??RCg}aT;%Tmzqz= zlLe6>1SPxvMwD;5b~_arhhZUYC?JPCtg>g!>!IgHM}(;Zaa8%~G=53|?aJ`+ICO&X ziLP->h6inBC2jU1NU>))5GESXXvL1V-Fg9fCUO?%ad$GDJ*i%l^*x4n!efha`B+ZD zfplP}1e>!#W&!9jL5qDX4iZBIA>>L&vbnPD_7NmZG8aFs$g4Y9w3wfYu#vmm3BC$+ zw1wu6XJ*VPaqB*6Rujv^wv`15;%lG`-gx`pLvHsnV}}+R&$jDtK-^;tQeXYKMvaLf zZjh79e_av zCuRU&OXPzz0`w9F=4mR{U+OtqHz?iql)t5wVxZ>`Ut4ak9i5GdJSA@5mf!-=#Q9!X z8(l1$wV9FtD1eZj%ASRm2;#;pR1 zr6n#8!Gzlkq#0eE6BgSoxG_u!WWC+=2VAc`uU@@4I}l)Bf}qf3tsx2zZX|AZxLjV7 zz*_(SBUdeQ8T(w=;?gh54gI*+*ZNVNwPLjfAhQIDQj_T5zXH}-WYEqZ6P=ObOb*lP z{|(ze)JVJ#GRo@&U!VeUY{RFk_A<1KUfA-zrcOJ}{pKU*q;`Ry0RB==`>A;7$F$td z?&Jr3H^A@^-{$uY?pZ2^GYw9=bW|NBhSTgZ*|0}Ec?CRR0L*U+jBW6Ul>czmWx%V- zz=R0ZZV;Mld!=V&Jq8Ovbo^JJ1eZ+NDv$o4Z4ccwa7*L;)y?>5U}^BaJb*ZUck}RK zpczk2NhUREBYi=zbaHgD*gCU&qEYs6s+*`e5%rmV2cz-9Ct0n~8lY;nJ?w3P%RVNO z$gYlO*1uA(QM%M;v*teAx7OsK>ou*}Vf}4C8RT9d$oB3V_(ZN*l%oPWpX$a9G>))k zh2nAN76qLoJ(86DRxq@%L9>tzS^2E59Q6gfHDiPN?hrpA;=bqZJSHqTm0E4|=@soy z!m?+D1+jTcQ~Ut$wB`2*=V>(GbR@!l&0>42C#g>{9q6;g*IbaIpyjV0Fotrr`HRo} z*g#?6+j4ktvwYsx3eY}V1%F$12Le7gL|(qvm2*>OkmU~UG2alY2=ZrgJx$A}cS`fKl5HGo+CvF~va8ED|I{J$+w0`hcm8>lTyQJ6VzMX_mj0 zAFgPK9_V}4Q~APEIZ22+ck#MDtak2*U^(c)qov58oK>tpIA|#(9OXQcsmf zqL9|}!ixp`HTrsL)tzNz*i;aOV#=Or9&lB>9zr{rY`pU+*W6-2g@>nTu zHZ>-N8$Too9v%!qEx$9o#w=F?bV3iZQ{fAf&lj8iaTx1W+ktfd~ zZX)8MIarf1&3^k^qu=**oJC`3Y#euasK){--P z?6L9Cw6Xdf5y&o(z5`fd7CaAC97r_$EuyZ8@L_L&Tmz?*xoAXok7f3$$04kNM5q2P zf|urX4gMF#e$f@+2GFiV;3&?{dd;*JZ~buYF9zn&@D4y)C+c38%Et)`rVeNTv>W(> zPQTLH^@&`r2rWaWrOg`a{k5pinHy6#gRY|0sny=R@!YD;qEK5KGc}S&t;zgA^tt{+ zVZA{I;qwBoa{pKt)CCU1f`3~99DIAu^Usg^Sb=W@a^DNVj3v0Uh9$1|q8{rH%3~XX zi&RoJ;;JHb?uoTNjn*|T$IpRc`_z?*>GSn&-Fz^rzYlmkNx*rJ>9A>cY88L@+1DzJ zjHlH7oJRjSc(0Uc8EtviV~QSy{4Y5G1s05*uxMTetEF7Ebt2)Q!3=kw1G9xJAZ=(P zUlEy}11bbZ?6vty_?)cBivta4h&!!*9(7cQorI8=ut(>n9RWj6T3!>bk8Oa?L&4^T zmjZZ{c&4E}SBfO(DoLoGSPY)bF@Xrn?VKjDp!K5C;7Z_V@v*efc2)$}l8ld|mu+VA zibqDs@2@un^s?p*Va z)BTY>}9#E;$4uOUrDiYLt%dojJt{iNfx+q zP}ucL3nA)Pc@oiNOjEa{D))`$AQ=SL5ZWtK0oAt@VHG8vUQ(2*5HLG|S?OKJS@@WL za=IEhbv*WriLT)^U$Ym6DDVjpbqYy*9^tjyEtH8hk{Sj^SC9sygV{Rg<}~L~z(;fW znu1($sQg}`VPm2iI_4T^>+?Ec-P<`L=gkFd4XcV2N^U9*%wq*U5wvhlWwUnY0GK8? zlAr&b*2jNL%3aYL5dbxHQ@tEW>bi-{Ld6uw-^SF>@qIH}m$HNx}`rw%rv-mS?X$9i-le%gaW* zF;G#H*V#bwz^nY&Q<$qiGW&bRE_xuNPi^@lHFdv3Y4KjA5{06wtN?^PW{wSyIam=` ze_iogkM)>UNv9ks!L`N)06i(BM?JQ-YrG0OKj_IDgvU-Z9uJlZD?Ylr?ReMp_n=A> z&oL+RnQ$xsGB+PW{ncvSO$vBorh+bJ22)tbn6hF%ims>|)i($#Z$q6D&CA4J{P=Mp zJG&K!?-a?rKO;;9&V1j2q&(aVs0AwkU`)^*u@M576V{;eItExhwP+w3xIDI=NoSnZ znB&7&@a16yF1zyCMx2_+q}79u-^hy*lOXPpoB@cxUN#o5D(9@XC>y1RM~&I?wX@aO zkNq=pNjMl`H~yoF?(KdNYBFxS9Pi{0Ab!{jk1!Q%sPAS>(KU- zdnWrM%p``X|LP9e0$n)2OpZ?M{4DHn@fi5O>NA%zi+pi|UAI0C=!CDAIsu8Vra9{1 zV{Q@DS-Hk|W_09C#PqAi9-VJz@R(!3#PFXWzflA2`8H(?UJBgBPNJ^9P!ap!zQf*& z9Vx&K$p?w7cQK&n!2N_r73ixUdLXKS451017a#YX_jE!5C5JWuB)h!&%&+?cAjKuO>a~S#{C+-34CO4j)Kad$KFwOpcy*I-&Z= zcK@;o_uwWZ%C&ja)X&^k+TYte-ap13zkSh~n)8cfCeD>?z159*9 zd0~D&>vx(H@C{VI?FqrVH!qCF!HyWu%X*;LzlN1c0sti3t831j*a$=L2?;R(P%`vT zEf?^rZOjo|UQIj!G52uqEr+Zxqm&%QoC9>p*Pe;3v$3=_&g<{>DXn}5VXZruhoC;_ zoyt9vLBwaU(GWgFCH@Mj|5TIwxI8H_e9gBBMjTlhPT4NU9eGcE3VvW9o89=vQ@VAI z8g7ijMvz?ND=&8GL1>2SkB=@Z)1fDCDtrcj-x5H-z#;meJP2+cm4plPlxxV*jHT{3 zSPB{NpETU8-cprj1VSK@4@)TfXMC0*-b70M+I|*oQozRUXg-T7ZyNM2DM~>fm zdq@0Tb1&as4wXH50wD$(=<*4$5BSK<99V25nDgiKpJW+rz<8=ygPN0FkIsY>208z9 zQ+aKj;&0v3r$A^C<5b*+_7}_@@(*OGjf6^h6hs7&o}c71qu586*q&edMWC?YzpIKD ze}oX-9cD05ZtoXDtupgk9F!~S%|QS)t60p4uXA2%wZM^uuGp{J&wsmn8VHIAKqIq0 z6~a%sRiCZ-j9;DZ>b5MwTln*ks@P*kGtt`_I=W{&c%~8lBZG(dZ>IuDE|=0IyEO)S zr-`sT$xcvBqy6^UlYeWo8UFMtK&@2K0t`(_MASx zHcly$D@(`fg6Qn~E|60C)S$|+vTyMGrL7N`Oe$+GU*LL|C=;$we80fA||-oxMIKUuh;<~ zrg)0U}?uzubq$lEw~y>Kq0=s{~oygn*_O~iiG z+-o@)r)kC=Ko^+6L-(ok0|75w1n^VVzrtt#ZWD5dl>mFzEanCHljKn^tnP=)+oF}o~qzI(XvErWU0 z73Eo8%5%0FmZo`6L_`GXY1oV4HUIy6FXKi)_|6yRY$S|-f&PJo+%m+u_JO{g6nkDQ z<__HUqXt39nnv-LhA=8LOdKQ(fR)Uz^WNudb~xIZoGihC4)%!>yNJ*>D+i9ZLUI1{ zc3ZCfU1@g|a!1pP>^z2Db+vwaroctAf5u|zU)`f85P%ly?-^aza-ZU{&VEl!CbeKM zDGSoety}VDV@5V@8eeKof?PPZKS~bbH30q44WtV{?gDP(auVAk8p^^UxqsmMq2z1b z8St#Qwsr0cdmY!BECxsx^C%{UT4Fky`K+D`N5vfiI5#HI%r;U>2 z{kQO!MrXFd%r{`A7A7KF<=QlTbZfH69BRKR)p9FtbG4p%pU5G>;=o>NxovVMwM-<- zKN@Vakck73zN*jkMjQZyd&-UGz9<=F!Ldh6_P19AqQVs`Lm&I645V;PW=!wFwSyTK zm4;XJ?>GSxks9aFy~AyW%zkiz!FEWqsJT!S{0dED}Elca(`A_OkQYBHPL?U`;wTR!bZ`-${k&R4ic3 zF=YPQ)&DJc9A(%8K&Amk*&mA`pjm!heuTUi^O4KrufW^00|oDe?KH#e_#QlDK3yJ6 z@{{?l-6FB@7h7*cMAWUV2Cz3gp9H9yzB&hH8X!PVTUE6IUes=6(3|w!Vr^YMZ?rpW z{9G)_h`T@1vgsQWNG`rSCxUc~odJi?c)zQk4kY&Au0k&ZBVkFnW1(PHm%3GQQ_v9L z4`8}YQ!&|BF2i>!S_)2lXu%5GFpd;08WQg z{HF-Qr=`rQ&bw~w%qY`=4@8ZAHGL7{*M(<{SCjLl^W7dY1*Qali;?1XtLf!y71Ny1 zYS+7W1M?FF=8c5ugv8rkrfd3nV`C<2l6Hbw7jAANZ|dm5Jj|}s9d9?}-{u0eMIW6i zjf>5i%o5i#{hR}A>%H=Vl&1H?+o^RhMh1?*Oav+Ev{g(r0OaO_X{G_E3N&X5=jGja zofq9HFh+x(G#PH>h>D(WJ;j4Y41H*4rL!8Wc075VQ=jb6IRNTF-;s#BM85TqPs>1z zjg5n9TU*?P@Pv;@g}g%EkTGX%rbt%Yx`*1D&=#hF46TZGU8YP|-h|6!7XX-+1L;T< zG6+vwn+dKfl27B9#aV^kR?k@ODfnxuf!A$YuX_on&b~W;e}=gZve(YlBYdD`ii;Rp znrMNV+MW|0c<2<_L3kn4v*3LKUTrmnul7ugM)jpXJ`HZb4k5Zi0m8=g2KmYv0)+m= zc#2Q;&Xu#}q|kxYCQGTFFM0_fmTn%Nz>zv%*(yRE0Qgdp2E`6yh4aLB(KC>Nih8MGczCf#GHJSBxU9I3XrLVjM zeoz6e_&Y>n1kTK>u`?;X!x^)^I3HnsV3U>Fjp+Z>x+;ek13G9pG zmVPA(=f@JLSq@FCd%UEKJx%d@3*9P?K6#bt3NL1#m65UK=M7~ zM1MFNPP`e^nfu8n=~|uDGRU4q*B{`S4XjLbC9#T(W&E9k$I-rtu-J*77Y(H!zRyUZ zQH50iNroS85{B@}`fbS`O_i@~2|OJU74RJ-sOK%-Lv2D`HtJv*1oiQT?ayoDZa$T2 z(W(omUV>I9cV=urg2F1Pq3e^Q_VG_PgML82-6*HYgclT>$fATy#X7(gvyq01Cs=>(gl7 z(^GqxuKCLer@v>3r|NDJU%L8SH&4vHtEa+%_dXB|2-{f}-`)zUP&>-<41{2v@tgG6 zhi3mBF!IsAi#GfQDR7nE2x_H(YN6SHpyu@5q&6?dq^fxb3Z)zK$XxKd<$+P1u(4`- zt<#n)*sc&Y7dT1R+fg#42}k}w)6gIc!AbP5eHc|VVAA7fO}`kL)c9p6b!-vgZ}nsI zbppRzxqKqKY^|pS_GQ$b&(#+#Krt~CW1n@ytY_XM5`&M!Ne^5y=+4d!fg<*(r= z5WfUT!br*hAs#@(00A45r~1^txSh7Hcl&q$`kSs;e~>Lt2Ntn@)g7Y_d;`i2&SnK! zKvjX^liVhk#%)@NxyXz}SL|*K0BhyVDYBb2XliFxKB+!?YiZjODqpa`Ij~emW012y z?uwFO#I53gG2HikAuJyl+_;M>d((vTvuca%yx{rd$Aizwg>{GuzjMPCK}aqPG<^DN zdCRj>WRF+d(<-NXYE`qA<1%Ot^|g4D8J(giR8*MilEhcwd*UmsZBxBBe`@D^A9Dja zuEr>m*K2JHa=i{K2e(`h=i5i{s&i9~ioG7C1RFEqqZN(UdeYq)Oyc_%@Q;-V6xBvR}@MkUQ z0Jlui=h85f&*GvPiK3@Q%I(w%CW;F40zmZKwE-i6)971Bar40El=R~zHHSUWjQP2u z5)hI9p5aNz?n)Gr;*e0AuZ;h?kABFqych(yTrcm~mRC4`xD;hjN&njl*2~JUf$#m! zn?@N{IPeihB%vzdwBWyBIoc5v+~fop8-tMwM`T~0y@Clkb(Qn3d;9byug(0OU49aJ z<}=^;U0f**k`S{6Kicv0KP*;qJXnT*`~f#N@1p9#0Nu^>mrQvJ0~@_Vy^`|)fEFKh zb+AdiB(Xry;Jr(aqs27l1?j-wCV)n;0ah5S<%w8qT3uypv5>tPEXX&4DmMrhKX;40 z*7JLa5-@%XQbRD@UBQ~pQ1dur8-{HiF`YibMDUqJXS8w~dc-@%rPk>Z~k`cWMC*XDd zT{$3U2+9&w7OWS8MeOnb<^Ht3CF|m&yyU1YY!E_RGVAlEnxm$cX@IW$1=u}BvU$R3 zw);=X>PBDLMKQQatz_lm0~dWms>ne1iAY_=-;%69X~VzJ(%}R65mPV?)*J9~Cn?gu z0|O1bO0QQ%1W$LKpmu(VK4Rb*RlIXMVMI{*&AYcT7q7J=XsY+0QS+eY!}1p*&V;a# zcu(q#uqW-qOtSx$Q;K^b5BqVG7&HEn|An)l_WPO*+8OJ8hEp+DgefPcs1} zLQ>D3s16irp=kLbvOuukZixRs=xgO${eK`Kh>wWvFBYgY1;T_7?eOCrpOpE|lL>=s8>BEDV^fUt) zo!O%B3KEuOy4yLQ?a-#1pK!xrKk31i^`*_@V1~#Tq$%l?52EG;DWZr&nMW1 z*v1LRM@4aw(p&YPyQcl(to$*pFJl7$YzF;-OS`k_Q$EP zkS6=VZ|O-yog?Siu~x3q>v=XH>fZ9X(;Nfpg5wZ%m&I8kD!y7Iq|?!1?QdQZ6#C!P z0$Kb&ip!<*3-^!iL$F0cCd%~#7JJxDHM$htn91iBgTm<5og=D`F3WQrCr*1^2C5!+ zJs*(W{Z9wIByv%Q`zsX?IkbLU59L_Ff5Ar!&p^VXdL=Tz$LCuFl==@CqS1gH+3AE6 z5-Gk4e0XIqrvRC#!J*;d9IcBjv$49DD{n-C1~%wO;*Eha*h(8>L;cg$|L>CIt7?PQ z2>uPg_R^n8x55H8Ma6G4$&6Fy(m5V8HCm zs}3aL05yF#p;;X!+pf3)zBhH>BOl$5>T9cxoc@%;2k31VueIIQhP}O@FI-H`cTI@b zYF>d><>-%B8?e~aNT>BIFE6Vw-3sfXC-|7wrx@KYb-$-@qUnc62BnqEf8uEW7b(2M z_~|hobh%0BayXEufF`9Is_#<>sIBj8PbRn|j7L0XejR+s>x!A!L%eI0l4~dif#sRa z+IVj52H0fxt&%g>yd~eKa)B;~4}g;vnr=UpsLkXkK^DGjsGCavXk}T5|D-h25!jq1 z;QNNm4}%1Apv{^#*yL7o7JzARTm5?XpGxVDZ~4knyoQ`+{0aRRwclkzYieb3T$~n5 zqC@UiA9r-^+KdU;3^NH;s(sOQJOj`v}(vrALqb|PRY|GIC-x)cZY?ewMJ&FP%oh~@tAiUkjljbRsIBRnr;Vf!gC z6mSCL+;Ij&E#`}l?LlM2@do|CN?nq+&-35=3BUsHZY(Ga@Nr0(k`#}Pb!Sqp>t!r( zuX3Q4Y^+9XI z|4+R8FJ0#3MIn%A0lU~fHvI#^=nj0`xlp_1_rrZgYDP{h;jtGF1%x@IqI0Xym?!b8 z9kX`UL~V7)&Vc}+-(8t-C)85A(ZfQz{685qe(B%dnwRYDuE2y`fKHKz5?pb84#4iqL$o%B73Wsy zlKgW7k>x8q1qS3Q2zvT`^tojKx(;W=5^D#*ND>{LRCG8UuMS1*)-(?=ed0fMM#wd^ zIi6sLDoG6{D17g+R}`tSM3LqVW>t~d{h=HYxQhQ}{@3*0e1db`S+m+LUmv1qX&JDY zO>p%9xGN=VE&3a-j#@bI$LjPXT2>5$F}#tcTIR z2@Y5}yt@>`{xfUVm&Q|6NjkH)@_gLH-MxbbfO`LdN5G^UWXp75qV>)!)Z7%?M0i~zA!+a6J`+RWywsCRlw05^do6QUC8ieM5+BJRdIypeC)zVeu^mit7F3}yu zNbj?0(iH$g!n+**ouse>0P2rz6=%2mYss`RBUX31G09teKltm(W(Mc}1_WOZwA_cx zezj$gaf^aCA!HpSvsQ!M6)1mi?CFCORSmUmRK5XVKWEC_LV-=-eJdjZ#kMXn;dbfo zy@azwVte}g^%X3oGt)sp(}b9$*Vs@JZ0*F$ux_XeC&AtJz`JY;n)EW@BS{BNNn`h6 zSdxF_zfFW@s{jPF^_k4&fs;`xb|XHz7?T~WrqK`O<5~wDs2?z~IyB)iKyyBT>DA3^ zU;*iOJ(s4Rh`PGhlK!^d_P${6lfzk!2O;jW+aJj`Lhlw4$ z&h8@(9y)V~6k2~>g}Q*>9v*+rp)6&Fsw*E++T~j^AMaR9AdkP0_t!~gWx{>` zZ3E{o6komWptgd}r|(ut*gVktU(s0xU0>dAoHYlcuB|v(k6|oQG-}??l^;P3FcP3Y z4t3O;?T_*phvHr6?wS=@G%HY%GSX|n%_3=sSp$l%3M+o_^i;cKo^LH-N|L_%>r0B7 zEo&IKLWgU9s*Z+QMnSX0A#4&?(v>vw5ar}o_nEvQSGnE{N+jEPZ_%sa3nA^@g+hze z(lu%W!IuNd3b5QJ>$F9>1K00&Utvebm9c}PcP;^4)YU=0m)ljLMTsVYkq77d%RO&5 zy0|6N1oTg}I0H#iI4yGo&dHuM@f-hnnf=wrORl;m`@6X@%GO#0Ivr`&{|J~9S>|0# zeq!Ssw8CD$KO9c8-4679$m50klW=7B!^QFD;-Hyko$ITuK=bzbnZ7cO=3#4AQWiZ* ztGL%nQPSc}d+Uhnp7q!0WlfXRwB7@vT*Hp9~(hVA2nvps6aZa``Xdpb8>QwCxj$_ z(v0i{V7gF}3t5ei&GUJ?UVQj4=rfCy6HdJw7c?PQdWYt$d1UL9^5JyFfQI9;nWfG0 zqRot0YT3usCfnPL^q20d<7FoNCVh-dZG>qiVlRRH61Rnti_S*Y-@Q29^xhiK7-w8O zw|4kMU;M_CR;TQ_ujtLlr+P{hNCBFAtk~GAkMAVvm*<+#lng+pGbj3i1JQXb!w&qG z_8Y_H%aL9$4n+nMbCk2ldqr*=ALn08ycw^tnx1^;^6-$aB-YW>v2JRs`^+!j!v?Ir z84sUCN*^B^w@fO*N1mcxhja7?AC1mDNPXASUml z-PrL#`CisQ;C}Gay>If(wqov$PpXJQ6mIk0TegxZGI7{me`gH;$QiTFv*_O<$dfNy z94O*e(L2QTAb!ho zp!C7)xU>#?m3^_Jy{q%!vw{jf5fk0fv2uZ}&^>xvT}fWtOG6XgWW% zzFK6$JYT;!IF^{0(CN8lH+?(M7rdF-^4bR{bGlbkd6QD9sYW$riRBZHsf&}h8Cr~z zTagt<$N)v??it8-U!~Wm8~p}rD59LwqG@xrz83D8e5~;6xhW@0ncL-I8$|{9?t{Lb_v&$t2EY3v$QQg#LnhvhEd-CIwqVV(^{-De{R)y2JHE(d8yXk=8~iwBNXW?FIs*Hm z@#PJ9zjv8E;mJmpj4xMq@rMcKkqGp?{;eCGYrO9fl|^l+-uhVLFD~OQQ7S4f%lIv> z@jQMxzK~DLy`nfSGwUzLcg3D}7vrQxP?^b{<1BWQho8S9{EF2;qcoF`VWh)3ZHK`i z`_;h^e2|*Q0`ou%rD^dA+5H@pc^tMvyn@K*ABzyqA zqWs&ZmoSs7kFn+Kdjdh0c?e4pr=+B`tQT1>joRKAwqN=E3SY?*<;`o-`eixNS@hod zxb$?cq1rGS&Z31TskWB~nHZ0-D0q_{6uuOv5JAf<<%WXerfixbN=0hN2&PnrR&P29t1c<2k%j+_`Gq4og?Hwg?$O`%#kqz3KPA zJzd$Hc4Kl|`xP}XRWPm1In$-x&aYD9pKj*U(sWMPWo-dGtwD&E?pX6@%k~Ga%1*ta zKdhqCxq!K+1l67e&$LthcQ;SX&UeQiv+S`BJdjFqT-Ff$sparji=)=ly+5)q%$ZiT z0TP*-GmKp5WhmHqj~+Yi3TcUfDcA`Y+$eV{f1L0TG<7|fVhTP-PY3gn z`2B)rpo~VxyPC6Dn4FUKC`**{lkg{17t-rR*G(J0Vwhke*w4*Qb0WVpGG%;uv~=0p zk?irc&uI@yVxNpeN(?j!Mf#PK9-tR}GGQBW>C@aoZ^XLY==_0hGeu|9?cZ8!1hmtB zI8m*-f!R;^aD1er@%|IsXB31cGvA3g*@7`ii$?i5i!yyyHZF?txNB$jBZ|GHcavSu zbfqTP!~(baP}8=TpaFmW%A-A8 z#EO)(RuroTy@qGu@3B@YoOYS^+Fb4vODW!3LkBMGLtpT+1?xz`gZp-JZk=IWairha zQ@3HW{jBP)u)I9LKx-J~Vq3T|R~@l5yc<)_HYH(sqITsb(~dcXl9Fo6*G3fFc*C>R zRkyT1+RItDsm^lfDsv8WD~uH7_@y#s84fEX)_@bR9HnrQPVKxIFFG9dYl-OPnpNz^ ztkA`x6(L8_)YH?`bX^_fdh+L|z}5;L|7{Ob_s0ecuiD)X{4En<`h`p7rY^UtvtYSO z!QPG)Oy!%<+jU#cmL9ofJr;EeQ*_9npmR_9HOXWP=m~zTnciEg=pT+;>u4UOEUE0Z zC?l0kN@S(p?rXknId8~Pc3UsUkLuYN|K6eLG}$O! zosW;tcx_U$YCmOaRv{l8Wb}^C3!j*Lyg2gDgZqlKH^(sc&?jj7E;bNySMj`rTII5; zm+WqC@%)(G)QmVyf`Z1aiHoqM^djc3jtiNFy@UAa#W&T6w>{r^7j1aMydWwcVz|nF3#Si#%B<9S6}~=|fh-k&Dg*VJVq}ox{#ci;Q|#K9s#A>4qVtFZ zllrnFM~D{+0}tyX8SMI8>^25D-CoDag`^bp_6|Q{*i|?9WOhDkTi87J_e+7{aH|0m zoptqvk;YF6^LsE>iIgiH3K76+HX4mU7bdD+BBYUb74Y$Z@;|Pn0q8yH8#w{uh_+MElABP4RL5K4+`K#a4~k zw&E>b+-j{wd3(BETdkc{6nj*?w1k9&rt@qWmvM6f+KUhuaxB`JhnJ=6M&Rd+AR>;e zk~FgsY+R4BPh!=+n@yceZ7QimG9nv7FUDs}*OVloN6+v2$a($8Cw|rr^s?^B{^b41 z-Gd=Ij5J!-w=ZgBn|^xPm;F71iVC*;^+C6lAC?p873CjZG1Bt#^2Wa3I0yLXIKR23 zHyuAmo!It<{b+2+KwOx)=jgBaicfx``BNfcYhO}vYsToDTmC%tsuY6q31(^Eiygxx zSbm5mhY{AEcLm)Y);fR>lfJGwyKEgET3`Mx;!>1;(lIP3$xh2=W9Zj!0lY{^4&$CVH=2MFvD5ZO~gjL5qL2JpS}O;UHN4gINsXW?pc9F~Rj{&VUgt`&_OQ zU{(4gb}o;jI@@g?PahX6jIz;2FP$$!(r^Cp>`doc+p4pu z1y^k!#%9IRll>!xB_DcJ+lEK*H` z$+7dwO#tKqKM=#5X)|>@Mo%@{UTr~Rd2YIj1->qeUJYY?iaq8Js2|oVn9TN?cH3T` ztzt_hdc;fj#XrZloE4q<_h2cyx}WIUBYLYEE~?q7s8>p6B<|P#JduH~%kb^ElJl7) z0;dPE3{3Q9Jzt)#J9m2Y%7`to_$Y4hMt_8SZq<2VvWuSsw=!TqTSkMI(^wzEiGYLO3iY5j)7ldU$n;D&Chj(PaN_e z%ZwoO6oNgMADnLcuuhkece?hER-GuZeA*dsVR2V`W}ek>xv$XF-7zE6tOFto4FU@d z5_;f&V`^?l@!oN`DaBNelSoWpUnA!Bn8z4uhmY_Jt z#3kQAXo?>A6B-Cj@{K#R1PWTw5{`;myo(vZD%_v&Wa{{pF7xPnbz$Mk ztb_do2_}}XD*!N$a=7VtERFm=;b!M=WxfBSVMyymkJTmZ*i`39V#YiaU{+JP!;*^M zOH5W^!NtR^=Pm}Ebx&3&KC1!oS^pg7!wj4Ln$i{47?Ru%rIaNXD2R7S_-E(FP5-;G z9Pf)=?qQyEm;wy8BV3I28PbhYvxLcIbD=yA{ZuIdFXuzic7l)P0SWw9_)$EC=*k2E zIaR)Mj&A4JcUE&S;hfeDvd1Y2RzHUWCEb-C^bpT0>(#jCBhiILD+6A$5ShyY&dPoK z@Bz}tNjk^@Jhbe3;OlmO>PY~I*AL^{{BWTw`dgWQmq+fiGOO`rmBu$cb6L;MOi%8= zu(L~wRJ+_SU(Yy$9z2i|U!@eFX+Q-tidS(RABfoLw7F1*~i_ zZ`hGxU^f*jW{@%IHTb>q8VxG|sRriEpJpJ>yThfS}0br!J4-*=^{ z5P?v_ep+|7(xzBBJwK5p4^zH^#;nlLQ2V(`7QOzGe|P(B13oPEmu5VXTC}A8XFHEO zNY>1;^7Ej}*N3&9v-pY%O8)LcO7RNp_6IO5Y_6v(l5M5ex>J>yC!ANydapk`%&%`1 z!4t@y`F@kQdEyR`rX4C?@0lI|FW)z^2nd5E(q8w~_hQJ~H0hmZzM;(4Mlbtkj@3;w z)*$s|93b)P5KccrAp9lIU-tVIllBbcTAg!siRJc2vx!fqQ&VKKXNd=WMASGbklg1d zSpbxm2wDJluWn4Uxe+Y{=KkbVrQ#{q`LMq0rNvKkk|pvHSpSCS$Fi`DrAfbf}=6^Q+eOJR?$6cJ{mCOi+w`l3*iTLOb|N5KK~@?m!C*| z6FgijPI; zikk%frI}L9d&1=~jj+y}8IzYyXoYNN&J%uB68sY=RcjnT!`vPdX$BkRZ+LB|$*gqi z(WV=*cj$I|G51m~s;a3~yuF~L3-FNZaev9(41M^ZM5>#Q*v9XJjqUC2Lq!l|>x8BY z1t8~Oj!>|z;=sf;fCeTjS@%1BNMe2Q{D3Lpe(uRKP1wvQ&f+6F@3(SRIv+S)?~80< zaCH^^&Ha+}KH=Xa?1#1O2Q;LjI@Z%+=7nff7QQ@hqHtm95dv<)zE=LxH@Z-e* zLG{|;Fpu;?f>8=g0R3{0U0=S_-0DXDEP9LF$?UEHh_syct^^njq;Xpk-;r&rZf!aj z07~emO1cSqe7)3yQRC3pVGiFYS5sZ@6P-Cn9=3>%6P>f-iGbAm4U@vl-B#o5TbaAe zSZ=;koOuU_>aOti#{77>*NWN-e~@e$AV%HRFZaw|!pTHwB05K#kO>s^TbLBDlyUBj zWWvNvI)?sGmWU+&nw`H@$p3O_yo2I0(Q9QN1D^BhGP`!;A)VaW*LQ!t8*iAO_jhI> zL<8)+8(J2?c}DY#zM0z!QKBw^ZGZvCMp}~E&h;s2X)*Bk+Uqs9v`Cf~D_nwOY^RREhd}mYVIc?cHcy z+^bGvnnS(zc%Qokwr1Bil0N5@!J4YfctqQd)<_j(_kiN~Jk zhC}sHeN$OLBpu@!8c!`|v>K{;?cpO)Mnz>9ZYlL~R&*)dFUv_DLdE%)K&K<(V(J8X zUWjzOqrPTQ4i6jW9@U)F@p|N+xpRh*K^d5@&J9j#k9Xx*T-ED!nl2jO#MvBqY-VP5 zGmMYD(SCj6>n+oq9$Pve>QfM1j!I`=S*?42Gbpu+aB)Qn^5xIt4Vyk4Lw8%=u&-aasxKwvfPu?XaYy#&SzzM>xQeq+eO*er0Z2=cbwbk zwyLM*k;dFxGxA7DOaA)r)80(IsXz312J_QM+6lc85VUuZ^mFHY#va2?@1>ppcMs#E z<<92MO8aQ7niFo*6$JwX9Bqo-?Xw4KP|tRk=YP*yU`Tk{=)>L&`SJ^?siO_Yk4m=Q%y+#vc8 zFWm%JPE;=Fvm;#FeXi-#IflN~nRf?#ZvT7`!+vz9rfNooaaf5sF2F-3sw5ruTkd~$ zFlFC?;rZ3Yr(7=UOFmqBdo>P?!zzWPa_Zm;qh~QpT`qt0Twu1%4zR6!C1pXUvr>|B zTc!W-RizX%$`T3-o0o)g7^X}PPv4ef(Px{=u9eR-YmX8Tsno1p{~i?RcQ3_fB_t=C z%`d|BX@t)KXA~1=o|xn;Peezu^RX8S%Dn4uvX1n|9pC{{xQPUDL4ZB3W_+kwgv6@H zWPYetPPliX<7-zDpV6HMUiYb}fNwOz^?o(1e_F8%d*pA{x`RASdx4pIT|ccAxPmj? zL+d^-!$yq6?gT4dTO4nj$^tBUj&?jbr`HoF3*6B&j*6CcNma4tm zj{<8r-4GWyb`Z3{pNv~sBtNDPh6!*(h-0DgF`|Q+gS|#S8 zzOV=|rGRkhpsQGJjRE(2lGZIomN;slT93H4fa$a}%m$8!c;M7#&eSkqn)?skY>2C2Xo+ zJWNvZ9(tAAuZ_mzIo(#P^JivW9uQsWKTtc1avCX0IPwI-HW!1>;KiWr3fl-4*hpfAuAHzvDKjLPp_Gyg6xM(TwW~2BO6&u+0w;*3;n}-7?RW z3bC!mp)4)ij@W)naEv?Y0G6$s??YC@&k{DC&)7#AM+6(z5-84hW*Rku;dyxY&^q@y zjwcIj%>2;nEp(Xdb(_i?E(hYOwIF9PwZfNyPOseig1zfO;Tdrr{$jeSjv3`H$W53uP{H(}vsQ{rTgzuE01nHQDDC>mBlLp8w6w0dLX4~y9AW--5iYlr8@T}2G* z!Vx174#>i?`L=W!1><^kl32FoPB^KRWpw}C4Ve2 zcPuf9FF$9{1zf(yep;UMh=H+wWPaJOPLuy3w9PJ#Axk1G{_>|WD zNQ$KO_3D z*81sR@we#h`~PL2WrEjG;((9*?WEtzDc6X%Q2+hcz;0r>q?5o<&bI6MmA#BF=IG9QsEhti_T~Bu96A&~7#kZ8jO%PW7OssY5lEm+qhGpRW;t3kOJ=L1Jq333 zPkx@V1WKWz&|!W62n=tW%ew8#Dk>}qL(Wbol6uy|xs*!UdIiEedq8CVe>pUD(i?-P zanE1*+g=}+AnG68=Yk;nKc5WEjHM_Ei;r@3yng+QRskQt{bLY`*OsT5fLn{0>xN_l z-pi<Fp+Q~j~yWH>H($dlbY-O`% z6?gMJO2O27x2y6ve-yktVET)D?AM>ylw}K>C4pbH8bWYBoVlfL<|9nC%9uH zvC6^u)w@NGHZ_1vAJ&DRfLwbCK>IsBGj)2K=G%yPy#qsF?kD-z4>O1GU|)7H9IHBT zV<>VH7bsIQ;{%;+>>YnXq(Y^op`juBkq@s1l5{qWCxC)XU!N+dKvX0+8=XJ%$KC;= z&9b)9b6(B4bryH)?(KY#76rRq3Bp>I}qH(44{X2U@EUEkaQ> zdx*SW`ECW_((bY+v2M!PEr+)za{W1jS=prDJXhqbb!iPGt3-C5o;~`ok%NshA!VfKR=&O zqL?aOo9ywpN%D^pleQEev|pA(?+wcvK1k>lZ!URFI}ZzSL0}1RIS0Ju%%nz?&sjFQ zeK?)}7U$-72449*I1ERI+?4+B>M&arZ`y8bEf@RUa-9q0vY+Xi?K)rBE`OvnQlRYjS`cVQ0d~4RvjZpnU zgsLv!lG#Q-SDv_AQH*SADZq;F#?F^kTO|9&CWQ&|NZABMTqf*?VrAl;O41^~4gBQY zo_Fjc_q1pjh+s7T2r$TSn#)|*CuwMOoGokKUuMy^|NUa6cNs^6Aj+r2L{`h=xi%+P zBJ6r!>uipxS$?NrDUH7Rj8O7zQBf;{LYCZ;0|}PhJYL;uYwx|a$Se7dnDIAg!PfbD ztTY^)@-aNdA?K`9E$Yi2w094IY{$gULbJdTVD!BKzX$=!h=fdxf51>|{T?E8A*Cqp zxHJ>j`7a$U?Eu6Dzj~J`t8~1tQ2BF;BLf8Z5?3EUvFlmLyL*Y|K{Rk*9|(7ES-9AXIkGFoGJTzM33rRet-iG==QEJc;FL zz8JOrQ(9_&WoA9Mk@{}>rF*g4`uyvu(UrzH!rjHM9ELmsd^MNNSaU8!54~?scN6IH zHr!GcLZ}7scayLF)zAqOb93F8c_rp8aZrSZ`~dxNRNCHHYb*90tPTko`az0aub_2L zx) z;iVi3W58)x@a->rVDfm}w%?#SxD0r|Lp{}@-3f`KBqON^@7B;0Bb4^(At-P3Dyv=&$Uh`wU%x{5FYa^aFwJj(+~QZh z)8G!F<%2@iW!KeeopNBrX^Nbd&2va{i(30z+W?;p0D$r2bpE|B9Zo_;t|flpqZfx~ z1(RFhTP7MT;m`{ntPRX>TGUG1d2Ewe@PQO@ZS8)s{Yqcg(aE;;>eFcdyW)9A&=<_J zJ06A!to{kam(y8zmwC}tAQC=mwZ>5Q6@%@g94HiIpFh8mQ@qK(HD0{Mb`BUAM9tJg zZZJD6wtWR2OLogV*>AUW2oHoZ zbJLjod_hFj=MH$X>27VT5-M{Xg)`sVAzkQ#L-I&$fA?A^oF)8NQmQYMS1+Q?hPQP_ zd?});nw;-q(G!0{!;bVpolb>#f>%PQistTVTckm-#J^IXkB+=IjW^duXa+JhLg`KEmIyETK}PyLOwNx9>I6U$ zpV4ZM3}xi~3A1b>Eg@W6oXy4L^Z};ejfTc!^1HtfgpnAQc@DdI`tNdCLfN=tpv(*Z zlFr;CP(knl5Yq*clqGc9CJrKDwdEqq-AAB;s(^4GDpv^r%Y)k}5 zyo`hJaJ>sov5o};dEM|l3I@4An(J+EF8e{rzC_$yY)~G1_YsD5SP zYvFpi94J#NvsbQNPA)%85Cy#fnVBzg_2m1HAF5zKQLMd_x*5|P zG$DrQv~*=w-QsVRWF_)>-$S3}JYU)IT`zBbW)XJ)(!WR-uIV{nFD7=3UHxcI_Y=A9 zC)Mm+PD>My9zF8#SbSDOmCo@`_mkwTV3Q=(WKV!NSIlv%L-4#%%yRenn-+S0eq-<) z%y#vU9MP1;cPrXR#dkqiK*@x+7(^cAAXmWM(#3~AkzE*Xv+$yI=PzuXgPJ*bU{Wkw zJ8$R@%a|c?*Z}5k8?*1O)D1`g1u)Zl|3iFQi8!37ugFq6LC;gm-{%cg)rt_@LhNxa z-O~K~(=R{tdHDPQJDdDlPdcgu${5p>d1Du)|HBzyc%PV3`HDUfZ2>{-`_JY2I&kmB07I|@zSwAeNa0hNhLl>zjFI4vYR>stdX%C97+(&ha z6c9V0&6!KAqLej2{w2NgfxE_-*8fIVd-?p>E(``>iYzEy*$x@psNldvQ1PyBO91aby<91jLuW6FK>4B<{wd9y$? zN?q^zw@>-CuMf2-Ikq?Uzq?w0pTGW<;=o1ue97-sJ9~s8eRFg3QKV7Ov@D~BOr!0E z89(*XWR4ETqR5U(MhBT_<*K)!|6Kfh5j(JYo*}9NE_)9tbxJch-t#> zhQHLL_5gYR5W5AYkT3M({S@H^kae(?LVbu%Y^~9+(`>V6W)b3bJA`;$R2&2{?5yMR z6ax?fo@;B4lO-sjt9%*i;c-(%g{78QygW|>wM&YF7v;aFK-LLAghI{0(|sIwm&dc! z5eWi?E`ha?Pk5*-djB{mCJbCofpetd#U!;=>!=NPmG-FXc z4ds|as1l_&Q2IJH^qln#NZ4SB%K)(B0jzoD3L5fio7YL7u4Q z3&EOsLoVlS?Lz`O0p_F(N@W9X+skhF)#0eV2~r~v@CncTWVURSq(Lqe+c+YVw}!;LYHS6VI=>24YZAX`y#oBWjnBZm9=S zC?SPaQv7a)r3Q(EWuU#qi*4b>2H?ii4R?XI_C4r2^NgS_g4D^AM*@>QWl8q9i2=M1 z{D_yyI7UAD2wbfd(WVI`*E=D*DMyGjciXm{It)T2p+@rhA^D2}L^Fcnd4skyF#%r( zEYuP(bh+DG>t2E!m==ozSz2l-;kqSpXTki^wEe+5d~=)M}}d9h06d!nrj!orRe{om6Vb7U&b zNH$m7|2pgcaZD)~#BufMW%kKprnQDwvOLV^yZMV(YgeWLsVlfCC@Cq?yKT%`f&$5Q z?JIUZMKj>YBJ=70yt$MiAI5TVXYpB|!$F0$l@3dt&itjIB}6q6jUWO?{>aB#94F+3 zNUnu~KmNU8Boe|&!SyfR%Q%DhyOk-sVmfe5!w)Nrz|n%q|Wey9G`o#^LNc%A*g#$s*>#Y{})w zxtktIsW?FZQN@i}pad@^*+YM55B+0t=Rr1|*L@p9{Fbfv49nn=JErWX3+ENWAAhH? z1Y9S5PD$I%;K1=qCvi}uw;j6-s@o6+2Bv8CyyyQzc0*?olFo#xt1;NmB@}Wl|pSX*}VUxIJL^cBS=B^VQ|57^N8w!GEHUJB^f*-GS^!MhbAXYnO4VqhJ>3kq1-Xp%?9J#) zIeo59h_2}S3IJf7VI}Avp1!yA??ZYIcjag)MD#SvI)I-*V9+ z$c*4E8=&1ESQq;Tzh9*r%i~(CWU4k&gNWhmCjbL)0U$ZlMS8V!4<{N`2AoCC;uypH z52mfO>Y*-3An=GJ_26llfZW+~Iz-N@eA(Y=J73FRG1ijI z=`MABKa;5N0ilUBj)-{(suvx%W-FNdps;8=8je}_`k6a%sPg3COkAC41q%$s2*)$6 zgRU{hiUb6U&Yh~oWA-WTTA{zRmO6pV4<7YIHh;|wwxZ-7zJvMN`*w&p^LkBYc0 zG)hZzv}NrJ1DyVv;>fw94D+Cr&5|456>SxqtbW9=C_nel`1rUmeBT-U9L+IPx~?ZN zJmt@MR9&o*H}5{-*Y__oW8tTen?l5x|3;s0hRL%)6p>K)RsC}JcJ17KGIn-$)W7gi z?||6GOh!#lugf%SbVkiSaifPtc|3w&AGrQ+=NN6Mbb9louRo`S#Hn%Gp^A&hJ^?0&}8~h z5F(F&T2t~%_b9jt(r*kQs+p!xVVH3ivdIe zB9W$wn;#n;6k1KIdH!3&_V!uA4NHbDhE$hv77K`SY*&>Aq}0=>PcMYUnCzfCeTYj^ z=&nc^CI!j>u$`ZSTX|xpR#sNw;L6g0=`VvFTg)8{*3bp+OeH1wB2*3IJtLz8(ld9r z_(Cr4jjEp`@1RVQZ#qx*rY_WZ^j4X(saJ3MkLWm#FT_=C4+qt~fb&K}?%Ilol1|q{ zOu&Znb3E}s8Y@aHxdG0A9v(#?eWu{l+ zPQrD+#681CTT2Hj)=4S(i4*e;A|gAZHq{ev!3vhDpH^=q^9Jc{55>1nE&$K&Qlz zr)mD|y3 z2xej}e~AeB+Y8~`b)$x*TnH}%DB@{yB2IL05R7M4ydZ8FI}z;GV(C== zFH>Ls{ubgY-BVP%hUGS>VgiFMPhk84`mOjmc%)`Tc_GGBc&3DmD%~j84j-klZ&yfQ znq_uv7=P->D)gDPJC4u2%zjBpr@G+m#M}B5*aLpl)1%ym=m11Z=K`)DK%i3>pr|D% z@5^&=i^<19iTs{*_xY6Mo;j}$yG-99!qbS4=4X&SR-Y>-{J%GpHZ2_PRRvJ}AY|ky z9SS((e@3R@cW)M+b@nORtdUg+o6=fZ4%_fF6{4yO8^Flvf@?NN{%{O&@>>vIMQowL zD!2dXK3$OHwQx}Uj1G2Qn?5Kq=0Zs{S6MaLJ^jvf_1Eo{iPiQ;K7S<2yRCo8qv*&X z3Y><`w?0jdHuD+V$z0jO`+x!@>kppbj+x-K*7sc+s{svZaH*f$2L7FZr7l#jzIF~` zCjvQ--qBI|e)$UFeX#MjO(X(3-{azv=S+7Kex(oj-b-OP@0LK5Lz$}YAg47CH+PYq>~El1NQ$2l-AdeoNE32H?C5FOK7IvBpU&=Uz;aLev6;SW*0#@-=Bu zi(XCD8!mnKzD9aQPS^GJx0lx&T9*PfcMS9q568x_5$%n2a(CGo2QtO3&NU}`_X&vm z9;o*PBH=IN6+65hp_$3D6nYkcnn$$JCn+D#m*j5B3E{dQx;#9f;;S6v8y6S%F)LHe z(2nm>Lo}ke^Z@>GnRn;51KX)r&7R}EwYe@`409krOzDZpZ4j+7)r)OA3&YN%>O#(m z`)0MMa z|6ZML?~8@729h)f|FIhPYab4wUV(z&eW;*gxwSf6!BH@ACrI!?GVJlkVK(X;78a39 zV-w~mbF2VwassrQ_7f0YZmYG~-Ze)r%bwHC4dpTFz;p7RDEByhn$h8pKPV7gsetd+ z5z0KW_&Gk376hw);6qZAddW-9HEreitZ6!o5iL36Q_Azjm(FVsi<2{&cP#BB7ES_7 zYlm1o|LVck-Akq}ad$#;*%c0(r`K^BZl^fs?JW%*aGn_rLA0kwJ7Z(?)KYuE6m|M;C|5{Z51%-iI zZfi;*&)wSikpTf6%81Cr0=+&cr>%_Ma_fwpC;P&g`j>Nfpw&W>`}XGJI(4G{NB`-8 zk`tEz3d#GPl{uWJ$$_-OAU7jRRHRM@+ED>jy;?Xv$)V`}In^k2-W*=(^I%LjML3E_+cd4@8`DEHpU8x}u8pR{VumC$o-DXC_@53fRu-Cm8_ehsCH3ydxcjeHf!>RGH{PZ=v6^{%Sl#stl0`oE=vWcjU2BTTP7y9++)?!}=DSdW)=i2e=~-FR#jnkDW?7ee_fe(^b8Sgnx8F=PK6ork)OC z{WeUA1@)tIF!FO){(;S5s-!zTIfnJUjj4Sv{l+qnHuc4W-VK_{miyBFulaX@@FY=- z6jM0|_QeGHaB{KK$*lrd&k6{1Ny^lj$whVfKwDCOhG}Ygv{3H^7QqL}DQV5M#-T_) zolVlOq;Tb|0zklw`mYd9%3&?|ukciP4u>=Az~l=C#=caG zDA>shgRFa^HRc@1cFr!ri!rPguHJXBDqUE=(__~RMOBh@^WtymL&4WdH|^pJ>Y>Ar zWY5IAFRBz6*Cr>EeyZNlAfne$G3W=%pvAAS$SatC@`%hT2L~zPaOw!z5ILb*pXGJw5M~wz}^Sg z=4{+y{7G~@cXck%`P!<$-0{$Z#7M|{0}~*#?XhW7^(%%FD0Ry7CGQiL&jp<6_@W)# zZeB3y8L0yuXDGzQIN2#XZEu6F^)U}0UvSn-bslg9ABTtQqjct?_PJ+&sie8%W09~- zy(6Fqzr#mA37PSY9k6ulhM0Z{&?^mNvp_4V*Qp&@8+;54B`RbNM_2IX*$ zZ)7DFZBGK0JHh0#aNEF>gqwNt2Y2km&x3@;NW%ehZWKbVuJJ3)jVQWlfYDO>1;9W* z-HH+&cZDWOfIq0CY8JYDmD9N&Y4zb;^gzxaSph94Y=C)+*7spKDQ??alfL)TbtQMR zl4R)1cVcNf<2S`=9wo@-3^g>tD3~S|cdI2q0uX_b?5;oEdyAYZP!;_KUnd_Q2s{Bd zs>UWp=Yr5PYh)D_G{4LjLtnFGeU6%rDsm`2sK4Q}_*wDbKl@%N<85}VCI4F0hQ-nR zgr3wOqMs(@&MV&zx*h@-JnpL9wR;6hD?ZSrpb9V11IjzENH>srRts)JAys8z1GUVz zu9~PwZ;2Y2ntnld$o!*Z3o~$tfGuBq>_AEK7bEN2=XPN9ehSR66c92}A+*Qrn|Zo> z-vEf&lJ2N9WG|7HfFPr%l6+{Q%Ec=VMB>j#%HJ<4C zF(q@sP|l-#S5#%U_zgc3?TY&XAaj~IhdnWHP7Z?RO zIBKVdR4e|XmDo!EGe})PwudlsaGpsIj7;#1WP+o!0M7JU3wF={)(I@-RvsNOITts% zv&X$4p~r&b4AI-4+!w>d9Rr>bQ4L6%)5f4dM=ClR6F88Vl#-}xllB3TNC~$;bqYtF zkwHZlgZBkR>x|$j4c^;Xq2Tm!7;=d9y(*;om7yDP1%oudm_Fd2E#ig*kI=kS zU|nbQE3OQJ9AxegKA|CLvgryx4fqm^LO?H)6*nV=^Uy*!1#n~CiqmX6^)3e^eg^r1 zojKV08Yo@mM)e1IUodwYLa#DvO351voukR~2S)Kzl&w~<2P(gI{&j_#@ z@xxBg?1hKTWEUI)k;C+YaM&l*>dFYkr;mEA=4W7(Qj^_(XHGB`_tWZlvJpE*e|DF< zm&i8J`8c)RWo|E!bms;oX{!_nVhFDov5?D^J0=t@(p?Mr5KmHakx4) z;`xZ4Zz6ZsP`~%&UTmrFpRRuLMVJr`fk>5Z`7ko zLx(X*Mslp;4PKmdQLPkVDctKobik2$4CDCCMX{bpun%!q9ht~LKza^5q&$8|$qaKE z3jXw>OAw^xFj566Q@R+$Kz$`J^iD5d-`w4Ydaq23DHgu=fS&kNtvuE;d-@mt?|$9n z2pM1Ed{ny(%;-vUyr_zG4RX-H|LYSvtf4jO(@6V?%MVLY-2`>&cTtvajYx}mqQ$bQ z?YSCohM;k#fljI8-1;}@0k2vvwy4EV?JqQLNkpB-sDzOYN50~0h-T9V-yWongB~GV z^BhTMOXoB0$YpVMC(l9tj)TTd7tfQj?*C>LO?@yriIMpB?IN#LhmA7Lp6!m(>8 z7YM*y*e1vrQV8dM2~N#%un~X^<&a<<=PcfMf)sULke%g8%)7$a7hho9bCPt#fv(PhD0nrr?9f=;$uo53? zfkdS!0Du6rde#<$ITc_DEwMlK#U(Ejvy<17agHay7;wn3gWm@T0#h-l#4rGDwnZb@*TmE(O>7 z-yt4rvc=3}do1qA?jxS-lSg8h+(R=FJqkH7VH5*MbyDS~^3cEzkZ_(rU8^7MrhB!X z)Egg%2o8beisQn_ZU0rINFoem1kx&WjSX3J(Pps4! zivB87QSF79N(3oB(DNse!oV=XM)l@cx)@=nmk*c4_EP$%0#j_-d)>uZ|E zO;lt>%6^zh@kNLarlr_};&=dNU-+Wt#2yo{{&YxE?gDg0>?Y)XXvI;n3aG|py)d(E z)O=6|l15!9=cj`V>^gAf9erftCUtrE)sY&VPa zGfZN<|CRf}_vh~}J-C)tJ(7*I1>h;Z*q*@7YGfPB*J!Uii2vViQICxS?Bp;FU1C4G z9mZ|<_cD|9P=z~DU%dDrK7U*4I?rEyfY!;$PzhWR_V~h+2Rno2GsKZJC^X%AFjS#W zZ$;H5Kl(7ypvT9QvIioH?IjDBdgmy8ZEW$xg5mvn)G#And*1qq;YP2>m~KtQn$2yZ z*hxINC4K@1KUlV>GWm*$eZAjPFB7A)e&f9m5g8l5Manmqu9m{Ts7Rb>MzU~TN1-b{- z6AusS+EsyN&U)$V*I9x^3D`IYf(8Q{mEdJaY$owEyxn4z+)JPkYLK3d$Qw5>+XwbO^Jc0L0}m_XinpqSgUSk!1DS+OEeD7KOyOKjGb% z?Y4ikE$PqrzO$m_r+3B=b(}nKn+%fL|X0|kAX=7e@0XbV&= zpvR)0&YcyefbTC6uBmvS$f>!46L$%Ru4%q2>gy5_g1v{J2?3QxnR|hJ&u^3ZVFps%bkIz}POey!<&w0Q$tn3e-K+)wjh5LJMk{ zfcC~?7)EU zY*B3!c^@HHL~~o z&L2H3TSMdsuoK7*Vd$J3;x@l@Euz=#jA|qQH}K4Bs4`w6=#7AZAdsDqd$FT}Pu7|c z>KC`HyE0q~Lx}Xy^b^z(1prKgax0~H-7MftdM#g9DH_Cp=GSCZ!6>B!#cSBzJ@*MO z9o;S4;g|X5%x&4Nw%+)ig{Fj}$^a5JprKXa)=e_AJ=3oIk#I=lNz;>e>xY0(N0ZM` zaE9*vbFiGkADheMVje1H?w(K?9vPlb9%y3q$dZRjvmZ3Bo}D_(g-Ve$=9X zXbPLGWTrK)Bwy6Q>T#%~;A)?BSCNT=7_`e73p^eRGs!V`>;4sm8 zu-3y^$|>M32%S9?Ea8XHbOHQ;7bo!b!C5DEnX})dqe7)!LL)@0hJ}`$DPT4<1g9N< zzg~OVgK=$%R|kBcjZI2V51+3FVT&-kF-0?PY7x+68N$Oz)Qg4{AdM5UJ3y0HAn{JJ z`I2nql59hw?KFWPGoghM5(=BK<$ti|6z8hs89L%LN*Hc>K8x(}h1tHtaioL|H-3XX zrW^zH!^T3qm=BVvb3iV*0ut*ZpocQ%{f9o?=(s(8o{9>|fDnJ6rEaKE&}@5VpA zHK-w&P_qQ^6>2jySUY%pbLXPJsCjpD&>?JV7=L8+NJ;E-A7T{fWX1|l0O#b5+Mi}Y zrc(;7i38vmo&eTAMoE_1($eF`e_-8Qc)9#{KbnJr=2yLgUK351#TGP2tZH)r!u{RtgER zXRn@_crJ6q(^uetppI{NGnD7T5^#a&9Gj+>9gA>d#>5{|?;T})wln_{WBu^;>*j5H@k`@uU`j&0~)%BM)1Akx6rPM5)&inNrC6RsDneA z5-L=rga%KTtA{ErsPzFVgU1D}AA!E>Gyw<#euY%K0v+H%yMHiK^SS@W*Ov!UwRZnM z#^!`fNlKKVK@%EqZYiNbA{8PUO-ZIQom;m-g%W8*B^kn1naAEpQHGLvDv8LHG7rDC z_CCt#eZRl+$NS!#v-f`XGp_YnpY>UClK(^`^3W!aF2_TtY@?;&C1ysw`&=%_{Csq{ zFbIbo1^(i7ILHx$%IR5-W1}LZn->&%R@zG%(AGB3$<$>Px`u7AI71%j{RUU$L!J@4 zqY}($no>-8@nDjDms?B9syOLGGMt$rP%7=G_l{-q973a0cLlf;tz+dgaQnOU0#`NUOqkK0RC^f0^o=IVB|eWWW6_htnZ}cD`&}0p z9&R$0*+<)DB{Oj%SZ)IBb<9!Y@qdCL`OxaYnbf^r&7gmx*0@2@@z;+^0*bCD>Y5Lf zwXo(tMcV-*E`jUcg>Xywz{a(h7*`r63w(jTfsdsx%aBFLW8YZwIkjJZ7WR|Yw&tX* zmIF-M2t7EG7+S+RO5VvI+$yCd<+nMQBn;3Krh*c%di&~8HLvN|tpv39_{q-Hwi>k> zrOj?Ysm<{9)Edtyjx}8dV)jW_hMuxk6~hX>-*7RWF?h;0+&?A_##irqCTqyYh7Ja| zhnr$C|w{+XU7^LA(DLFz{gZ(K?thh~D$I|iW3OSe5iHidl$ z{qA!&&^H>Jw>1VPFv?mQq1(x$HYoaupOOW1|J;L3v~q$C^*5p&;AC)L*Syy>N|O2m zT5|By%WioK_qVuL@lb!14}~SHSQOnT;73$r>^ z`XDJ6X0`6@XZdGK_Wz{40>C=ZrMo(|SenD+6Bh07|K&2^mpe9Ba3pPGfg|BpQYMc@ zN5(Er;rf@=iOk6n`b6as5502(DFpsw)jTb~%{NCsjJ?YZ?KYj1nk=<|oAg=?m!}3} zePw$l|Ja}f?DU$R#dZ7COQm7gK=(OR&x8z6FEgoM+MOib+c(yp%PEr=>9{!!6}_q; zLevkJ)9<7!8=4s=u(pkU7Y%<;6Z5`Z-d!E%z2#bIe2>wK5;%;lvJbiJ(vPK57cE6!EK+u6}Ahc&uYoH z_oQ3vDu7e9YVBZ;XZBCuLf~e)-^K2LkFHqbWa8PulmI&c|2_8%0?$A(Jkfh%iq7Ow zRuy(a0(OQC9jj=cfOIoMKb@YR>v)_7TZm1Rf??FYU+)xcsJsDb#$giL&8DHTtmneL zVex!jIv<$PnkPh-7#`kFPa9W3QoBVOf?~C&tiAzeOYv7nAi+8Ndt<)QwBZ;D(?!jx z$ITKS#3ooO2v6MS>elnE0yIqzXG4%q97QkQ0CCScb14Z?@)sZ@o{zSBxoh&tZy0-7 z1tYF{`x;T|am}UNOeoADX%Z<5!7v#3-FGnAh1bNPOkQ}PM&(;7dfSjiV*y9wtJ~dH3)gQXZaKpfWV^h^B$<_&fLzj5qh>UGvyR3)O=%HjBo=D1=ASRUqTZtIz?WJr>ZUctl96--a z-C#7mF==-?aA}bBdGOMxI{4Apdx*dy2?Z$)K=GyG8=!_Y3xwytrNrgb8UefkSzt+! zpNg`DzQ|3-1mGu6j`5Q48*UKK{q}qo)iEL3dGXsL8fmNHRalCp2;(?H2q?IH9N4m( z?&+4#9ZEg^s5<^*y~prC4kpbb-wY{y)DjW_<>JV*o<`U58>!gEXrJ%s1z0j`fNCg+ z>U>B+ZLQ6%JZ@E2^-?_(`1sU3$8gn&rh@1%RU9Nw+7V{e_AIJNlCQ- zgj7fq<1>IdVtNtWP6C)NzPP)Be`?tFB*nO+HoXCZGZ@u_{Z9nwq4gdU zr0hiKDn@|6)y@BmIR@7NtJwkGF$Q_W(lXL%j{yb{ zvVjgMupMIJ5V(e&Axd|1?;g`%j6a#iDa2^Z#uOm!UobBbwFZIqs$2l`7OArFIxWIZ zu;`G8{R!ylm>8jt@a>kpdc3~_X7X~H+YEc?rTir7UL}uiHT2g^ls&>o#Prpluc&;! zvH@B7K<_28XV&{IA;x3mDSfTgYkuzSr{C)vcqO+5N7`;ceGP+DZW1z;_7r&~sqdi= zzU|!Wqf2MQ>x!cZ*qreFtV2WVm=zis8Z&jji4OhyD<+&-VqGAgunX?REP)?R`i0r< z%`1MaEK;gQ-FR-)EDZK9gSZ!T;YDECQ58J^nxvpEz}%3j^kE4f2{GuGuIc+_^JwQ4 zbL<{ry}J&uXwY`TqjVia{abxZpn3?V{Xe~Ez(Jlx>uwGtwx}bFpUBYJ`7?L1o}UVY zG3mhkjegSNLsLo7-T0Z4BVLvbvKY|VMqgQWp% zpy$)HY~3f;OqP+lx~$b1p4Z&|T`n`Vr0nEm`q|+=_KSAz9_w`4Hno%sokj*v(TA75 zrpcZ)!-r%-N3udMgusOgFqHYOa;bvAYiaPuD* znW^{uhS}tisb80_((=}9czCP4a>ip1@A#K1Wxhm(eK6Y)+2t}Terx(p!KxBbFK^KY znj3c{%UuXJo?N?;5wkY9L-MVy(|(bgclW5R7(BVIpn_}gX5pK(^VeoK-RW)WKgn^$ zMD^W1VqKS^3i6whm?q)bALt2&8?ccz=bSu%i?k+(gG9(L;54I#EJW#ZsuWS;q)mzC zI%JE1mWN0`-U8$n{J&cg<}(}RG1rFQByQ_H8boA%%X^egjw}w$Pj+2Qitg_=C)GmE zr8H_#F44b4mf1$fb{I~Rm=W@C1z~1ON!`*OvMqYSO+S3Dj7f1z<=B|DT95XZ zxw8c^Bj}<6HwnLN?j^{a62lrMy?3j6<>GtkG20_UV)no8IDG>(ctPs&6GUWA=34+u z=!nnIuO&S_$KyETg%&GxkGVFS0;>Z>_)4dx3VGk`KNeW9I)9omiFp1OI&nnUW zL}&k=7k<)5y-uA-uHL5p*0)1+WP#SZ?|rDdfdnStLBFTuY%tOdNMXf;;08dWt$SVE z-G}FxOdz`Mw8Sz{b{Acq=q#$rW|B=IB1o*X;DU0uBTZ6?sS zK%e&#=9+fht{Vz#?1F?5Bu`zISgV9G76_PuJM%{qi_nG|{o#D9`Gf%Lv3|K4HciO4~H<1}@9xIjSi#6X(F4Q7&wU?94TT z{N^BuOmXp6S97fo)C;)H{EL$FnWI>bA*+$d%I!nwqcuuC{YzH zzZ#EPzftfe-VU!^Wtnv1KPf%ECbvOjO;&4WZx0@&ubIWDeNeuSXg(v}?^} zYv;>uw+rP~O}2F(0fXNhBrZ`QBYyQUG&r$HPHC*EB=7-jPuglaN2z}NM{vzRA7N~| z!2+gAF1m@7q;S&9^wkm$JLPu}5Bg4qfW2SvV57;2MX;wZ%uJ!oo@!5 z^|niZ;DkKM*;YQbU@=q4co0O1-}22J3@PU|iF!Niy8ELgt(I;EqU~`AYPOd)agmf* zy+;t?|Dnj*t~P5KR)?3cwj|gpR2tO!UvGbDnDIT}dR-u#YLFae)qfIWqF~KhcHb$` zc)nKcSni3vnYF-JZ-C61j_L`p(|dFk?NiiRB)koI}3V_EN=VyI`M>93x+PHt>l4XF?2!1lmc;dKkJhHP)k zJ;yc!0-yHcb>>@~u;_>ypLo0Kc+p=I9Dly!V9wgH==#VVw}rN>`a`;tUi8$h?Wu@5 zoHqI~;bMANI?J$!8M6t22-I1_h|6Qs%nY4c3y3&jBwk6-4LlCXDI!ZQV=@+ysXn3d znzy*}CNTdf(ITKWA);|VBO^nnlp8{4ZFgmvQx?#tHvX zt+snHZLy~*h*MB{Iq2E}1t;|fB;mJ-V;(D*d=6jXn6KHs)6ais_Sm@+w)5renLuQB z8X9~WCI9^tFUwMZ(`&^Mq<_H>qo&uD9z7_vRpP~w#abS74FEHaSsTA>n`naR#swTr zZ|Ht!zQGfckRydX+h%6*BtEClM!oC#ji0)6r}`KbN*MlK7MXRL8f@k*X}Byz9_K^t z*yf}CqkV_$;41scX4G$9EyBhcM967rdu-!lHC$IlzPSC@Au0f^)(yCI@!^E5vCjG+ zW%@T~Ibq#m33ZD{ySJE^u29hN*!O&FQU`=<5M!@0>OsVEr|&Z~0i)AL3SRcLdIn2w z&m6FQUATB`gV6WVwl->J!F#FPS)g+5?QN8hyC-p-kV0KeNkr2W*5+k-HHwjLH8!Oc zf_nfR3aMC?=@R$8>zIbd^F$-+ks;dppEDkAVs-iI2}BCx;P8GHxZ^_*tnEJJcs>J4 zivLlgoqDC+-N_fOo*CG6gteD7E@N#yvghGqcOY>3e0*^}7yTA3y?ry^*PzS{rd?9? zzd+n$yX$Hw1Ccizv*J^hN1S2o9HG4sfQJv`r2I0DB!O7!06;w7ZrW~8n;FV69oo2Z z<;rZp>bjo=UQ5BSDzeHjn+}9Bm$rd*Ap|B%M}MIEA&rB=tT*Ej@^b!}N!|I%9?tq% z;K@@Jm`3{xb5Y3zpqaPT8udVcU4;eqsHiR0DYB_bIM`kX3&_OC`k4Mq1rEc5+dH7L9iJ-RkC)js1bJtGVvr8w+l=_NWh z>Qrbtak7Ez6bjnm5iyTz7I5YZtYb*-xtVUfUs$3Gk&4b|5YaUgX?t)&M7~%w&&kd~I-fyrQrfBSp`$3ZG z6MCthVFW~GE1ip;LHz@b4sRq^V`+x2?V~@oQ{W4dd~N%x_NfelQ1(l(WF&j*JUulu z5N5^HQe0R7f-M8&5v5UE{Tz=~B`g+Rx^FgmLqPph!u&ZrlJYB^?))g*(N{IlTj=&> z#qr^vWtfFoA!Ef$-W7X|BuY6K&^vbXq9PY~@s`dKZ(FUS)8(?>=2E5%vcMPKv0J}q z)Q2z}Q0k=6w=vCYoZWm&Tfa7^_1ten_`tx>L1 z*6V{$Q#;Ds(l8STChbdHD1fg2$CSLfvTZ7HDs!dU8DiNe|L@fuUUL7T$JIuFIL`<8 zx+^}`eK8VvDG_26N(E!v>a#4Q-4W8#B zk?Z5KIaPwA-ke=Q-Iti$lM-awuqMx;pPOAd9K2B~67x^Xla5;;RnHb?DlVM|0GUhO zubHSKRmq*&I1pYY2~0CgE=6XU2CVX&S`Y=@nj?^TKB+;Ky1(vQ`KN*V)#(v`q7CG= z4`pSPTr#Xx+qBV+fDT*U(teZl@ zZMHt-%?e1eq0df+NQ4IY<`GUk4&W!Ckiatf1X@a$AV*}eloamjl&1yIFeOijsasVE zHmPpjUl=aV3wZcIX&#_P5zJShxN(?54>{a z=T@y;i7!3`*{>%xG^}ecLoIon7Rh z17$uJb*dn)<&CPNC{ik_WW9Unx#ZAadBHPCxXjj^ca!T+8`aX5x4~n9wPMK^(`Xim z?j^ABp*V{nmC69)^eBBM#56C;_>h7zD@T5pSNhbdd8|(Ar;I0l{v3gYq^Uc`g+9e2 z16eU$unr*Z9H~40%?+e#-^#J}V{o3qo;n*A`iwIvgk{7>?%ue77@A2?Phh}o1v^j3 zPk_tJIgQ?>BKOF&AG92s3E(>LV=dN79YV?r9Gq%zd zoYi00{#xiN7H}VkqoIl~mB@uv3Xv-GERcuH*!u8i=8iF6FWmm%vBTxle;wk7b-@@3 z1Y-nYd(qYQ2Plag*rOk%EhlsHweJ$^v0!zZ{XyZh#%(iLMkM%&7J!vYYe@y>$8X^R z*ZBm7Sum`Nc_9yWFA7WFg2SKljuTR~_E9~lRF2} zs!%QueKYjX9fYTo1Do`|bJs7~OLsf)1J-h=bmY;^d$p*FTMVMUzI{=d15vvZtoIn( zzm_QmEC39hM@O@weIc73O7Zxjq#E*WQL_nGY2$XV=?u5Z@MiI_$P&7ZdEY$eZyEEA z;8nLE)<1~CrpUJiWt)VXL#a_S`rss>&{iK1+q<#KYS%4Ez{JBY!f-FHGogBoL>gqg z5x-T*8gJ~k5~PY^F5x<`0FGB5&vk^uSPj4i+$Yey%0)8hcJ*NgON@^Nn|twquKC!! z%MaYsIsR_dD20PbJvhNpw#n&1U5^hc0bx80vn(*AdDH{&{M)h%9`a;0?o*_+&%wkv zh!8jkLm|y6TV=M9fQC8=pYC?k@XI)t*FO{zUMK}*lmx_1f?7L?ULNx+`Tj18HWCRmaoU3<5KJ)(8RJ2cC#bw<+9IH0@(?X>IRQg=BN z>qe9Y=WyiqWpazbUu|Sr0*!gonKtLCo?{%E#FRrYvjIi+QMjwPsHn*HM^!Dx(H3Fu z7Zu2cWLIhqYx~b4BF0^;^C8(jaYf#=3-n%EDMP}fQ0xz@{!z-ypv>Ys_3!yo7jw*E znMq*cF*0G@AmuP3T9Rxwje9nt{5|6}eK&)cZ%jj0O2ti?+acz#rBi%yK-Y4Ae0^^L zXL+UEfX(#3jm|&6tz>f%GB@NgSr-xqs6p7g11zd?2}m7)57RPmY3k_MpaOs&_6ahN z%)t@r!u!D_C=(b^(#+&9ZvUqq%E@Pgk1dH45Oq88Rp;{LX#AcZylLZ>fWu9USt30J zNj;d1T+^JGZh_)5m_UZ26e|Py$hZBttDUt!c9W0l>!O^zX)a^^4q(w&dq8n1qYG4x z%|E}onkvCLTIM-ycq^Zm^!#fc_pJN(=HI_ud1c<+xh&QmU^A|7FlhqyA+dlWiWLY9 zD_Kc!a*>LiiyS%s{k7)$m&d+|llVQkee;^SsVcRIreX3UWO_Z@GR#AsL_@5hdhHi_ zdvb{XzK}Hmq4y5?>i9_m=|K<~x}f-&Ut&t;LXhU-!@I$Ssh{a(7;f8GJELaW2WkN3 zrlPNyl88hqwDTYrBhK#Qe|9I??Z;gloe8BTFD3_5FO!e8R+yHC?H=cTM-;bg1l8Dt zt)ElzIuJ4k{QchBlj}`M$o#D`9@}MEUMW*PaH%t=T{#~;@Q($^PCszx6Sp>34fWzi z|LDZpi|!}ZTHAV^MmD;6T*;)YC1a-6?MYeG=r9gXVjeAnlc{o=JMLw73uf-Ko?RCv#_i@fmb4#e?~D9LhU;fs3E$egf<$7@Lv%0RWOA*bHEGM=cn*{(T6nr;U(Spqa4% z7&j{eRK{6&#{079`#Jc*Ex<{(0LaqD$6!PA?ZPH1(HFc(JiYUSA)BLFGlP#5rTeRp zUyCC$urRRK?UxnGS&ute)wbNcY3@4i-l&`eCjRa6L@1#OtH!AnA~@~Q5!swcx?gz4 z+?D9+Nm&afQr&=oyA`1ib|)%?4NMnTdMxwZX1WI-#J=ANPbCMmu>-MT*GE54}J*SNb4AWPvcS!+ca>%%w?T+%S-Xup5YRJW5|lnA>>RcZDEgeDfgH zOadw=V2(qj6*R}2b>n`FBz~K6i2g2RZ_Jy2$_VR)V%#cW4lu(2F+OQXC#VsFC8l2j zR*$p62?<@I#hpc6&*;6Ta6_<>L=(G4LeikQU3r3&WsSf zGOrQkADPr&81V|O>Mth3U*SU|%n=HRB%J(hxPi62mgQnn;AzVmA(A@gfi}YAe|2`u zX_H5MIl@Z*`WzxM*2DmX-g9B&c3NnEj3C!Nr-ptF)VM&Thkd z0o0Ym!P}mz*7z4LhaDJt|Axaza=Pp1h70P=M#(v>A99TK7|dkov5V$nJe{M;Em_Tb zIt_%W--O%t+b<-na)xuC>I>5MT0&|QGYs9DPH6suSpy7vxa-F)T{D;=#U)zT{bYFVwa8eo#28kvE&V4Wo_q zw&2g^r!(lw%(mwTq-XB;`~`vlyf1%C`wlVwy^Kr@+RU^li!k`lWiF zxwo7O8(^g}!M?{qHg7~Er$d-EeBMVzpKN~=d^>;RA>5sOW2RjRGM61<%+CS5Z+|0^_Fze!wQqaJ&u zFlSV?v3bdEno_E(Kn=c>931+`V(6EjHt?=|URRFAgpQv6WaI2Qw?i72)m(y?7z$V+$)Q-^m5hX$L*%?36oldqF4Yyj9@(6xfs^-`?XD^K? z=tkqY4l&1w-FrvHd04Nb`v9&Udfj~H)95kLnX&0lmkEy)PKevz-E%#+wcJqXtTZ5jMRKZ5nmKbIjQq)#2Q zW~?5ezq!Ist>qm9zxWHRzfVI3&4O_}~V z{lClCgXw|9VPkL(5%;}tK~<^7+3=rCpyPpk)X^zKPd)nQuO>sJbulFPBL^0>Xe%`` zKN%6T?Q%a~&Oe*hLC3P_-$K3%b44?<-eMtr6-_mC;+vJ*ju5HZAGXO3DdY16gj6U8 zFKQb~{&DSAEXFPFMzm11&}Ipha<;4uBHJZ9JMcic-of^ zIHD}eY#Y}E1|YwcsvaQ3_U$8_dPDnm>V4v_Ph(l)^bcVVu;cv(*h|}-I`C)a?3+Zg zI%Hr5uz+IvS5(g`+JAoK#C03j=h+W%yI7dT9Cm-PGzjP)9{2}D<~I4xscG*50KA=k zYy^j$8t%!zKh!&5p{&ZGAWF;I1!Ri!_VN>khTh&^Ml1dM`@cqMmVPdcoRW7-c+zz+hjOv7&`%s+Q)K| ze>a&5?4m%*XQvx?oI%wf8;XYCd>6^Ij63x97DZu2_Z~HP5IZsn@&u3bCFX(n0x7xy zMXR9DW!t>~&KfN+)|1AdWY!xGct_@_M`eEG9@JXFx^By$$jQZwcI1p>iaqKa zV*$jCzynek7-00i*SGwI7Sd0Kld1l4GUm@C>$EA@Gh-{a8}QCIf@&F653o|_pS!4L zl;YU>Zr`TFe?buw*vu1%*#R8Ee`hV zC7w$|l!SCHd(M}de3E4_&^L$7!uqL|;H*=^H&|G1?ZzzMb>BB*arpxE(IHH{$W!2v zKL`WU^~iJJ5lYGUuIt6BB&a{@gZdbdr)3VAH#oIjptC831(5J)FFjCa3R)b;q1=Um zc|Sv0f05(RF%1^jKsSK-xEb7o@)ebrMr@Nlo=XD7FiIv0bfE<}AnkbduY?nn&)N>L z1q#+hN;gWI+tp_QS-f}7p5A%qXFt)bosg26*?&9J3kJFU`yEVI2jHqfysmE({Qsl3 z7FccP-iGri`qxmhbGtW2ZUOI|1wGKa#I$>Ydf#7es57PBe@$I(a0RK+*$L6p|FPL( zC6!CYF%3t;eo6zOZYi)D_5t6z@AY<%cRw#xqYi9aRboe1@53IU$!9UF@eRm>T|eG$ zf0TZw1k?^s;3;Mj1T%3k8_=v7K(`#SP5**yHmo#=N$|kfOUpljG}T<1VC9imHr2uN z?(IK!^m({HoB%3n@8R4NQuhx^*>&sJKl7-60GU&m;CAQamz!OU2JtAQ2!w=%PA3a+%|qtTT@NbF zAqf78I=Q7ES7V?a6|!-Nw`KAbrLT0n|3A+88+tD)SFW#KdD z{oV>eCd+}KZ^+mM=k$WWe1l;=U9r)gW1|WAxnK#5Dq;Z^gKxvg4+2EwYiHMJZf*Jm zErW8eIirrf%&D&~_nGlrea@{dC2w(HKDWcFCt44Gyp%4pwrPvGr7e89Yu2Tx8{VGM zMybz@_LzEA+*m(t!5-y`bmc_7ye|usMZ5Ujq5`Vv!`&_KCSa7cx`^Gb4>(4pN zO5CkmRXKGxpuz}>`qgz~uoA0_2xWFq#G%a5!OULQ5ft8o>Ad-o`zW`x$!ZR}y=ELXf`ga^g%PWqj%ibuRv3$M zjN!HP8*ZMcAj&bT2scn#wl-kUXO1c+F75oWiYwu2^0LxzqJ|yw4*IK2OMV>&j`(0^+Ge@vQU;1IOM-STEG@PqKF`WaW^JE!E}$Y>RLF3vK-X z!|~OZyh%)U%N6Ko9JAhl!*(f19SGp?V@9v&kxe080dZtEoAW3Q&SS`PSYF~F{|bES zmK9SSeE&YgJdN^=ef9^rv)F&CRjdyo zi|{)Te$58F@M6X$;ud<$z10X)6%2>fBqStwe4U+~UZU#d&%qTd9i5zdT+^jz@Lwy&$&FSPUxlqO}8qpt%2e2H{$H z>+um*dwIE=;xA}ZRFV$ZMcxk_TRm+xUy+E@QJ8iJ&M z#(+UPpMk^`eny&unboC$aY|CCEE;m4ydpJlz=G)>PwGD6W zre2>A6&0mW3!#NmzRwkvz#HK(-Fb=hfi1AHQ1b1ac+hQHm;?ElJAMv2I5=d3CF`Eu z<*-J=BG)H+U|8(dnzd`E*mi7t^d56w*KE;O&8&1&{Jvv^w-Y(g<#CNRe7u`eq}^c* z)L{(5d2lYA9zPe%Ty!1{j~?Ri+eX%H`62S+`m7(*1H+wE&gLol&whKT20XG|?mi!d zi7BRwLXzdKVYL;9-dw=y6q>UoQ6;x|gJdK&204f2sm>kzx#C@Qmttc)R!XhO&lpKl zAAYZ5rDv7%g=4ed|Gz2S2d5DjN3ZpNS+8E!VK>q0yiVxU4aLRl>O}@5?d5HtWD)cW zFeS08_dZE>OG|q?)Tbe!}PA3xbcZLdgal z!zIe$t+zD~nCDH(V8zK?7N7!&4v}hHiqAfG zpGh5gtQB4C-&M0}+~lF=;NL@Lmu^nZ>Z14>;UYI->-fcT6O&>F9?O(9r$d-|fYv zrMrHLG4ILTRv7KJ`Pkp##dpWajpxz$=_XpqowdREq15U)3F%x23tkNJ1Uonq_cEju zP%q+NHCj6oakJ}nZ?Im){&8T$6q(q=Ibdw!Z-*5d=HxYr->_RsF{9|FL>}TM6T{P`9je(mk!rDqxeCt z4Lf5lXF6|N=X5}50b9EV0HK)n1=2RW^yNQv^aEQV8@yoS_(5=C;1C0kZ3R$icTl%T zxJ*<`K6fl1*97LK1-Q+^Y0wqaoA#*L$^*(<>9>t=rS}5Jg$LLM!_}8^*=-;_z-(s~ zLDCKM5>T|FoI1ey7FJa+vSwK11?(V)*F}u?HYdqMks}OR@*Qfa86A}7f}v#4uk6`({Mri~j8Wgv3^YBGTiD^|)A%3P}W15O#0<(y{Y-f8YV z?2~5XJ^+R!H=3gDJAFVct200$eN>3;xb%V!3y%YC*f_dIry0L^p0PiSM<@E>J5l>lUcCkhVGA5rh}DbpAagUz0RdGyv`Y* z8r1bbO{_~9?T9_-EJ^+xUMF&7%fUs&=MOU`JPg)~-AXVlgR>#js-5x$bhH+o@_>B; z3BUpC^1*&zZl=4|A9Lxbijp9eJgZ-drxuGi?@qQqh@6V9IA8Zg%WrOZUY0&a9R_i0 z^RgI|jUDcIegNh;VU>E3C}r*$uQcC6fgsfRVW9kmUM8>N<;J|-P)?bZ=|IoY&9boBtRI4+r50cmdtN}*ZmtX`h+lUd z1CQijokD;%vY|yV2|nM0FC-2v-9MMeyPtC)r?A<_UcLKfq5e-bG}=K7Vj+qR8vcYS zrdPmQ|Hla6gHIn=ezUK@IYSVERXoOpJV(*h1%rJy5UV_mx_WufB~q&+NPpZ;#r((5 zfJhfX`3Fg>vKViuR}?PQ5xDIU79NPRtw}*nkNo!_hQ;ej_LWfrD`V16&`n>82PTdp zX5$0vRR6o{vxEdHqYp7ZNKJeR3b>JqazzvKnmyTfEc1YUt{f%LL5FQ`2fsYlnY`?_ zTE;lQ7-0P4D2)z41C^3G1j3`2Q8XUmHWv^aMH>!k+na;)OR13~8i6Iu(U(LB4Eim+ zHTX#fX*oy+fZO*LRspEGN{Lw1WIhJs*{VD_6Oa%{>tMuqkl#H@7#Oe z47f;0OWq#0Abz%$jawmn@g(`(l>adxkfRi+V8Qc0b~4Bjk9kbW|9A@YCeb&E`SC|w zNBTO(bt3bx|IghU9&g_daeDu0aP_Yb1C|4r-6_il>Rz#9&;M9P_7eTNfu9tuf~PS4 z*)t7SS6Aqu7i_^?`2@-NF)uU-+<(FH+bp#Eo-*)3QOH4J0k**K)TsDT zRkBoi#^l4#XO%=1Ms;YI_baI8!Xic`c>hb(~XF>$DcU>i*y2|657$5(^ zMS#qWz;-6EuTgmpJ5JQY;qmpASex+j8X;N+n?}X|aG`ZM>$x$x^mDi7E@ep6b-ck# zHs62D*2_e5E4f23J@9!$s#9BJmo#DMHBNRDd(F`MuN5Yph1PGUi>9Wg_d*Wh7kLL5 zwk-Wl`W>#|Gci-eSLHe|T_6QK;>AkB5NOoy@SMMx4Wk#(h6f`GSz1~e6ui^(@==V+ z-Bvyp^Io4Y{QRGCsI+OZIUllnHgdxL0PwSdl#$e?jDY}CX>w^yT$DtDglH zHeszh3~20rc4P;I$^(w+0tdMy){cf@hVlnqpz6QbFuC9+Xipl{Ns@4HV=o1!4cpA{ zgC@^_REDpU+@^d@pOoY(ZU;qmLCG}-^<{B?hiJhE%j%##kkDayYC8#8qYZ@Q`D`~4 zfSb&%x!O^j7UsODS^|_I{1uGMIUdu=*Q}SrC(RwUAxmcV&dK0UD&@{4MZ2|!t+zj7 z2O;dC`@>55!sg7gRXuG1Je(&oYC8|C;~UpUWYYB*Bp9sBF!rjG`!waRao;heVKVQ} zhJ~Q|S*M14v$7ojCAT11xH;nEG{SgzK*yNlPR~P`abGiV=sy9WG!}Gc8K(ovM<=t* zbPc#V8xnd9z?)}s=Le*4sF*w)|8R1S<0$Mf27&p3qNIxL^pn0pZOaPBIqVML&i(6y z55>LL+Dn|tN;agwWBAcuxB<_1K{Q*3`%!$N4+l>G5#W#Q58e=R92|jydlg9^zdw_} zJ;0qK%fD}8PAA{4f_^j2D>*LKG{53_#eMMbBpQ2=c_m~3Z&tGf3g&d z0KgGdgUN#7BTQigX=lxEb(!iwHJicDkJK-$)(8cDFu5I*&t4r^?ieIWMCG-oF;}o} z{Li_wezc-`K60oLklvl@WCK~zcz>UkN>DeYQvCo5>^kh(bC{BrgSrcj6L`tF$JR0M zKA;Idz7t*p_tp3ATIZL&V1`g!Z;XN$cDZ>O4NjL>GZTgXF z2~sC7qZfVu1Q*$01mWaA;IKU@wOooTvBnCDB;R1wexOvb)Pg(u1-l9sWay1(Xax7- z8(^|EZV#74mijzN$i}BhRoW!{%!6aM@dK+9Pga<4%+OK57?E@A)QN*Dt>}?`?uQkwSX1}n6962c*d3E_@s+#sISA8r653ll=TK5X2RCD!<(?hTWFYT0pjiBL@KieAuGg zKUH67R_;-Cd(gq~oNjnzE$$=uxGpG*r3lQv=TW5Kq(VDwHfK}wcX@thz zUL&Ii@$svmYv8>WVwYiY7>c9|9s*QL+E~}!Inf1NUdnaCMyT5<^a{wd?P|F>jbTU{DR-Bvy-=HsH)dTAECQPRaC0=3RGB zXE&Ao9=58I_@{8E-5?VDyf4xD#%=9~R7MQQwk`0$N;zAVYi5FBu(}1oq~zq)Q14R$ zh12l|sF|Jwr2qMMxAj&x*wyrALV{ug>YfiRok~jHRvJ3LWCG1iSW?+pT<-wl(zF|YJX!ChAk?rPT{;Dlg_jGXpqq@;GBtY>=5 zz*R9{wv*9bPC%Z?sz=^xmm><|X$;LG|6SHW+fxq|V z1Qy>q{&rQ_Y<>>s!X60ly##85rJ4v)bg3}z=jaUHCME*;$m{>WwDzF|3wF)_^H~5doPfdyW&0zYu{0TGoU462b`0oTkzE=j z%dByr-&pe1>TAB2&W}{3-LU_3WAgU#0V&0_iA=$I5P50tZ>p{GMCdCCYWKA+)1%7P z;60@V3Pku32P(6WCT269Kp3Fy(Hs%=f$9ksEqxYIiZm~dZf;hm6nF|)cL?oy&nEEH zAhQY#*N$00>PD$}O>2&Vrf$tQ)5%o#WaF=8ZUIAvG}B zIuS!GEChQKwn7y02f)2`<%d)_f<%znSF-=(cKLuc=1#<{Spnd;mpkRgbp(SiVk0L; zx>ZN3T?IR#gf*41rn;$xO05BaL_=eCTtwgFrv;I@n@QH(&-Ng_ao&@Eye)zDkDwW3 z5^BzFt>tus%D&mKIkqZ(pj2|OzWac;2kak44PJ!#JnuR`In4eZs_-6)z$8KPKfOLu z9I>czIIJ7o_mGu%!8u{HXZqi_VVGX#ldPia`GNf85!*gW^@k$t&Pjk?4*ru_6K4Y_ z5T!H^@{6|$?`Xbe5Q&B6rw*=aBP6{JwD+2(q z(|$A{rL!xB1h6@-J4o)y^_47w*afG8A% z{`XW_0b;UL>Nsq0zEDcOSDd4Fx?^f#Q+GdP%5AW&PKs+*oopl8p5B$1IoGA7Bm#*Z zFCiqJKgz?wOi@_)2dF|$h2lYuC7h94XAW0ra%b{)Y|2b8{5kS|(CwZ&m&yBR=b^R0 zSHNF<0>C_`-*XPcBfv#4y{3hZ#P3fEtSd{PCUr%b4$A{f>lY;3+c`r;YG9i4rD2GF zf9!n?Sy4a~$^n&I2@wAYF9l7p5?v)j021Y=j-QW;TeKDnJO+aao$R`S(nJh99ho?r zpUZYcb*S*;bUshyd!YR>1ZA>)z$0xLc>>z#pC_-IFg2Uk?02gO(|Hop%PJ;$0jg|a zMl2i^kqhe=C)7C4JsZ>JQ3rkldb^Kd76R!*H>YkY2|xc`iLfD11l|s$`w+;a#ET*J zL&+fDfhjx|0{A_aT)~pWL7B^mt_%W2?7mykg9tG1pJ9Da z^u($3D_{y>$pw^ngv2Z*Y%}1%Ya)BafaHU69fu0;h=~~6{Y53=KZ}nyIC+Yg$;vJy z1?6lrwrB&{l8Ndzm<@(S$E2j5R9IVs{sw5H%>sSi%NS{fV7Qc&c}e(=;_B+zSX&8j z8D- zd3G776<}dngr#QfSzjJAA&?jfET@aj1AVSoi9` zCd!}ap}^<7a&o6fe?0D0w88Q!K|1&I24G9j54FztK~%2&u{qxcTV+W`->3OLjotlN z=Bq_<8Yyaig7g2sHw-fns41?jtn5C~;`{eo2!^2i3IcXV^!u0pxdv+y+=T!L(r}-P z9tNJZ+9Uik2FFceAs3moH34Rxf#`S})9i-8 z{|O)-(MUE1F7uk71%ZIo{{D1M|No7pUOK z^)DO0Cxj3DUlRyqbOBXL)5yr^^QdUEgJu>QDwwzqaGwywGM&MBPc3*4hwfG-!^+kb zN7;-@#xaV`RsQ6lPH-@_`GTk$%2uKB_(nM8N+c6IV8nN)pK?Sm4>Q-1*8q5*a_#6y zZ!W0ep$ois?_P9>-+gUS`V5$2Ov@k_2{4409fl;7Umu1k*ffZDY_B)k+_5za5O?s& zX0LIOg)=@G!443adc3Ql=gqqh9}M2Ra*{KFZv%w?0LO{|pZM#$W}J7d^Tg`G@?zsD zWCs7$#a+o`8h`ZjsGki~5o6hQRk!(e(UW{Q%=+>Ik~os)6w*T3tafdRQ8Y@%|I4c}uN zqwe-4K5=@sg}9Ty!`3x_^h7kAe7f!+y6FoX43TwZ@7@WtwY9AZg4L|C-7$@S%4lPS zU#!j_`zY9b9B3$Foy+GZAf*?vqcaIjS@-%nM!S>CT|=TiTdiQ<1=YY>FDfqP?{^!y z(13NFAnT`WzZ3~6cIy@qx2Q6jke8x#H>MMgoZp`p5EbD71~z{L=k1?}T>vl>g<+%z zCtDho^D>nF-1L+OO9evyhz%8)O`o0jGR4LIv1iJMh#kU;Q32v0JHyiPiTYuO12}!0(O@y$PbtwtiJrs zSD;g2^yY!s7P8J#V@*M@lldPQzzB4Z9Y}JBtjhpg9?zVW_W>X^9cUgjf0tDJ2cf19 zuxj=Y(ySfH9G!>11PL3yv5o3nIlkR5g8%1Pa3m#fA~W_zjj-v+(!&~S?neGcgY7Cj zK~Sp#I47#=kMuhJQNr*on7n02OUeSbA>c%yF^YT<+O*8y)9EL4&#JOiiapgLh9JI^^8+Q@e-n zP_Sh1^>!b6$>VC*zw5*=A(JLF(`9c0jSb#6#)}s!L>u2^^Xs9kKf#~j&NtG zLMik*@ z&BaRVOSbZmExhsTRLK%{^JkL`h>l{p4s>f`hr6SUm>u9{00UnAhkB#nPzagg|+-3QnKJ;n`|b2O z`Z4!2Ge_eK_jxmc;VOt}E8x^7UJ~Raf?GeZn}F*lF&-xQU>-){UUjdN+ULsz z=US}eR9UJyobbrv1t-ol5CU5-Q}?QFSJPy(a}`sx6DNeMaB8paHyt^NjwKd+egtf5 zM0)+TAIb)dm|nQnbP`1;P*HgSCDwL-<0W$_+Kd7uC@?W~>eOr$BSv+K1AAP>zk}Nw z|8syaTG=}&M}YKR0A=4y;Xa?wvC15oDbrL6yG7^B@j+q@!nT-v^ysC#&2`K8%3?T| zzTTR|RAAqdcEDS|in`jd+o!*Eci#t5QDP?jmOE?D8Obf6fh_T%R&zTmUah-q0j*$g4GmG~BWrPz#rS&Gtn#!msKLk?_- zzi~pq@ghc=gTY@t4mh^3z3=Wk@-n?1?Akt+x#Ewe?@636 z*8~8*bwk5OCxbG3K4^j3-wl_@RqVfmF%r~WC{?jd<0Z-ZtgGXu%pM3@xquwfQ0n3& z76ws|(v|hu=j=4}B#vlVk~{1!#Vm}=6$!B0Jr^l{jLd6srp|wL6U-ColU#Ot*v6^| z=+Q9WO1?iMN!ILBYXdcd{8BiQ{(Le$6)pc*L(=%xiz6D@A1p;TKRQSl7eUDQDeWB& zM+Nm}?DMDS3e~32V}zaBz7l71$p7_nD{XRvO?{$MNBkUo*hwSa1}P|2B>4W;sGEF7 zM!VPN?mYHJp2IGePVMk&YPjTVW7A^HK7bZ5(1e(opX?8?tnPeTx60jvow7)`SlTG) zq+HKzmxo`w|ClLMSNg5%`Id3LAd!t66S52+r8Uy`?)mis$s47HMZb=E?5bn}EkY|A!$4Zjkj|Hs~!$JMxYf8V>5V~B$&B^i^P5=As0A|iznX*xne zlS&%*#$!r@xq${Ws3@Y+ywPAtbJCzvG!N1|ziZufwC}Cw^ZUI2y`T5%0D7tU9prPL^CG(-eR8?;|2iHm+Mj46Yt|xoFtD%A13N^!0Wk2Od`U zk&C%1TV63zK>lGBwTS>Yb8zfop8)eTGL&<*I{JI));qULsaFi&mJt4v)|;2}-&S)R z(T?p{2%_*MHbV3Ou9WX@MEHF1 zPVt`$SN6bh8USQORAsmgdyL9gb|vhJyYy?6XwKoAw#e5ha_1Wl^9WTMAgf?S;0F>JyHOi?iD>H~wI(xQ5qqWlKR6 z*+oC--KYrfh>@VaaRs@;jqhkrb#}2#6NC3SXyhBvPAuhESVZzhEL%s_8l`Gb+E)2S zC-GAKJWC_Q&ON8FmBLeOU*C>jXVW~TJ3O!rnC3%NH8Oi0;9$4!;jDVBb-Z9A;Ra>J zrqg*zv1W_i7>vsLPjKj{N8O?exJTA}=#Y12iw2C2cFm5H^rf$<))=612_oaMZq$l^ zy;LQ$43(SYQT5JL>H?~a{sInKwgYS`u7L5rh`M)m)E-|0z&pY8rfTg{jsO0~qEl2s zOT?e@KWEdkxnwXg<8eh6chwE*;*L&4#HRwzDmAK_zqW~dZ4sROQq;u+xx<%$CBiPT zqXYhw#TJ`X#@HfZ{Ank_c3udKPQ(YcJwf`^#z(0_F)%tba2QT)r<_M)9bGql+_qdnZ`i4y(0*>129o+*6cEJO1{O>%lSrr)>JMF(8*3Z z#lf;;f*#qR*2qY`J3KVgs(^mdqOttcJF4iB!Y$CBUXxf;Ih-7ir~y5y2nM|+H+xO- z{iQLz#UmYwcOw6xP9Hhd5Bpn$d(x+^7B+1V_`Y+3S$wq6`LyAOVo1*s{KSJj@J91;js3W9hD0TLT*iikjVIB^fO{~ zE~Adm5oD}B;GpJYUbJzIWO5V_Sc2ovP8YH@+n_tKv|jZU*=~ZX`!20lXB~2`V6-_z zs+hgn>eCsa``(-RP8$C`5oky50PPt66+(t9y-Ft>&C()pPMnWKd9nPEc(UghL7ek3 zJ4X zY)_{l1Rc<+BLOU3Ird%N`Z68G+YBEdC1XOOxrzXx86Y3VIgY<*#p?VUT$Oec!j6elp z>v+%V1VY*JJY8NuziP@YtGTNbsR~aQP<$dUz^SlsD7Z_y-4Its#C={Bv?MD01kb&wFigL&Cw95cN{{# zLU_*xfTJcT%uvpGR8&x1`3JRUuCVbkk^%S|2{u4yP+?2ztXa+|-M=2jos|%E;?J{8 z_IKK47+-jiVj4MI#e;B`_TA5f-aFJ`_wSDNSyIzWsyY@LDKafRM!3yK{Vi4+%+9@XnEBR!Z&rDCEssf9I<%TzsuO zLR|}-mHORK>>{8BZc?rSWXW+SlnqIP+z2H7ZjaA#miU)Z0>NbMkg*eEuNx>Bu5Lzj zJFw1GuGj@`LcI(wV@NUvxDi$$3H+f#N20=P&A_h?@P4(47L#!YLdL5xQz-+}a$swI zSvXnrt>rp}-=`M#6mKnJS{{$px;6LY;0@Hxxta5f>TuYSGyM$`Mz8ngUQ*;mo>7ET zepzU;lO*W}s-7~J0A$=x%ei#%Vl}|6PYevr4}g%^)}f>_y2QdS+UklXA8IdEYe)^c z&1bY9l~=MLyyfLBi26y8AS(N+gPXDIM-nY?4*W?ZHg9<0WKzpIOaKM%Sn@6;!ZHkbbqe7?C^?=&aZ16U( zF{E@NJT~%6szDT9?wr+gE&g??$#npa5=2lcUc`2NAY>n%?i|Ug4Ac{InZdGs z7zR=fLtM=N$UqgOm)~yeI0W=FIFw$1o-MF&EGrYpNOdPOq!68ox*YIt8yee-j<2f# z+--VpuIAnz&IH6Tk3YFWkYcv|B%s>cv0w-HLTTyNR2;YuBdz1-a+~*|fKX-uB z@82>_qb<~XprdCH2T3CP;kqj>Q?w9>b#hx~Ip_xGr=->n3=GsDYXKtVKSk=7{rHU3 z+jvE>0Z4hu*3Z;T3gIwPGGI-53xtD$Up2hwc=MOUxH4m=_ieRc5;6?H=BrS3$-|)> zHUWveMGRtNm5s5CN%lRY2reZha4oWs$T;~QIndeD6E`&MrU9J%yQ7LLf7stS0x?@R ziJhGZYL%8MS~s(Oij<`KAJe$`?J_z*{@%S|6~bR~X>{nr+Pn4yt~KM1me}o=koQ&t zN=ImoxpNWZ@2xlItU?4uWPGh}Y^4dRZCDo>Cq;M}W{Q-#fQ(_m8vtYfxR{gqCg5si z(a4|Aj2-hgj&yqRscwW&nwv~bAEdK?`^qkAr1VKX>-&d?=-vG%@uC^Cr#zjTjd?r) z>ScmET*&ti(btwO?n-^nu0Q6jHXL7Hf&l=eDZyJW>3lRG?rF1{{XxF!u$mbPWBD~EaHLG zdEx?pBwIv=2bD%rE9P{_Ym~+QQ3Gj7I|N)t;BdYopYu>FdO5GiIWz*O$JM4s(u8Oh z0I39BMj$aAxsvUU@&_I%0w>P-h!y2JaTXj7yhn|Usvc!RO5{_{o5Yq!pCGFgiunA$cQEQtou~ zvECtM3<9EkIcc6;x1mcHYx)Be1t!nXxtY_l$}xu3&J;bT#>sdM{1{Bm6uo|ORZEy3mozyGi- zY_u<^8yR|R%C(DPBqqW-yl6%WDK>bGpbsi+Mk3ItJk%0fH<$njMciBtm?DVqQ*MxLK}svZkgek+AKnE}m-2(P1@ zp&%hyi40GQsX*kU2=U9QMl7<&c(8IkAzFy{Z6(oL2B*!@6sN{rjpVPLBs4FB*?}mI za_9tRwAwf>2%G|TWwu)Idg=vL8A$)lEV#8Ki$p_pK#y{~V!Vp=(At4}D;<)W<}P2e zXy<;o-U2_5HPEG;hxZ|jLnyCM;rcB2Vy;l?dJ!VtkPoW{uH&vEYt1!Byqp7~tOc0s zmIM`(Ji_*d&O4T0t5>hyc67d#C_)A*+#sjEzb{sF z1V5!FPgU3*%*agS<|-`)c|_VEs~=UbHh`Uc_`p0YdW&egT~KEktB2QM?V*lrxz)Hc zc6dp+pNcQ_mhisaBlu7{aEP}K@*2cRcdqZM-n{M=}&zj$mke(v-L zEuIYEdJ=0rgf=Z-QMhMGHPV z4&H|Z^`Zy+N)WU1^oV<4mQZ8`V?~!Q*K)A?xt3!cxFZAihFB(X{1Np=$Htc>bxVSVNSQEf78SiOLh|ognkf*aU@xDE^lz zrACqYNycmy6%}!dC4>Yua>hEN*=%PNh#<_twwa7oR68XWLqL$K79%fC#6rM({0Rg^ zIgUo<$(?zG7uy}x>CvAxfQ!oJN0Wig%aVxjkNVFY&jaOlpP-d!> z_36G56XD^POA4cdU4t0Pj2pA}CI&AK)=lJp_(C*;ZffROlgfW`ifNdh*4e@k^=;d< zVppx%+2U>6wjJSA|L35X&8$0Iyw~+VUzqGKC6$~Xcw674Zev~6y}o3FIJwk~ zsdX2#KHk;PrRnwEU{%iEQ%Yb{z)<2$b990=Sfde)1Da+83W55~eS}WBn*;~TD6f%O z9PqnPZe}ng`^jh?DIj3|uzWpm^_bLrp=6U1{mP{B2wF{ep@fV-W38w-5c1I!A4zh~ z=&~pfk=W$;BQ+*0zU%R31~tX6hxr$|_OWI)uR{GbWTnEXzkH6n?QQu?xP0_4-8cq-m?iWTFce#r=Y^hL%p>MW!%RQQCez3?GD991b^y z`}cd!7F>LV`N9=Xfx_ z)hgKaC!s^_)Pd1Xndj&1pJ)_~BFTh=GhkoFpR9ZT;RLa``4{0y$q^-_LaU%Og4UPV zcP8%-ar4o}e?nB5;3itDEn_-|d1TgZUaGY=)`wk9bYrc48`hQgo;-Il4AVDO-GNF} zEGfKp2FSL1695;)T<3pb{SiY4!<~o4Y-umqHd+U{S+%}kXU3oY(G`A1(IJ6eIDgTCL$u-Ot!7Kko|DT-0}u zb-t0q@(AT8M&w%i94BvuezmVGJSq#+yQR*tE&XpPl+mx(FC~Skv5>2ZO~hx83g#Tn zs(cPsNn`4f>shpnn~A?2f5tx0jspZaf>FjFZ&a(W)zi4DqVd=qf3nV#GZ9An@pht@ z+)iSnh#hMQ?v%qPY{>R5Kf9FM;};KyKcj5BTr@yHhW7rpA4iA1d^KBUOzo&TOMrVM zwlhM0RJ>P65MJ{rvNiUTLgEb7fE*tK6*VTwhkcsf;$pSj|KP$Eek&(@k#!SYaeiu7 zoZYejL2dZK_`|U0w{@lwL~UK0xua;xkEqJK^^dtI-{^aa3hl~(aHUZ3m+suOx>bf0 zidgH#HL#7-){S&0^UJiP)kWloE**aX!IXcrfgslA#+sG)e10C`psLNgH-U%c3&a2- zE#5M3CVJJB@a@~z<*}Ph5+yY4BSE4amp*mh8{I_vddUKd2Djd5hqZn#vg_RDXqEEkbp~7C4p!k zF{bZ~X4`S~Sn6UCXAD)4E|8jysY0{Fe~dr%=g4nUH^RJ2Z?bGZ0o?rn_rJOw?&+`1^Uo`S@>BKl%e(>d~?v@eYjX(rm&oDo-^47ouu# z8wA$Dq^nQ+F9X=6M=V4IF#gDnX^S8QL(&=i^$8=A6f8{{DE-4G=A+YEXja-045J)> z#^zgEU6;moTH7F+2jpZ8yM?Aq2B_z6<6-PD*!hPaL5yMn46ls03X^>OG%5-6->rku z1%v5-xt3BpB6t1~FnqXu3%QIqnUto;g*4I&mH4;D(%7d7qw50Z0sCed{oo5^+CHQn zHo0?2opPLNuuL1>5?~C3^HTQ;xi~b6_F-0!YOC!$Y)9hgyl~1y-aT`u=T!cD>N~#R zD5ihz4(&-xA30<9GoES?=lbj}hPZ*z`a3#}y+3qfGvJFN0YYpGZwzLTQDDlC)gw~7 zAwy*MM9a?&6f3=T1E+U6rBGeL-1#sLCec#fb!hNd&WAYxRDx+6#NJCPSB~UO1K+5g z_HZTD#6$!cFn`K?49^a57@V~?fpUU{p-Sc~e9@9-qIzUjs4)E-uLY~tQATCXB;1?c zaaJi+_C`Fjd0V=&f>nny$bCcewW0OiGc<5j8vba=<~nUdrOO|fuwAKRz(PS{J^fqx z{=I!FtcGy?jRa1@h>@Z0KpQkkwY@P`{c2QT0w?oAv0dn-*-xMFPE%I!P3~l|nJ~KW zg2{}BVy+E_tZgz5lOsRw+sQ7OLyI~9oDkR!>RMZus+Bp(;TAoiY&Ijv4xj;3rw<%~ zR4veX7QSf2Xxz?WL=~H4)cgE_+d0@AsN88}r^3sAKLfeQSF67uNQ-rRC-r0SKvMZ8 zgloBs#{Wz(46rZLb5&?hC;Gc)K?oOf%dFjO0~~!zumo|C66>kQSPzp3=4O7PCOG02 zlT-$a7hR9>CztftY2jt))ljVh=h5XBv7)_vG0|@XRzUG|%KQe(j7cHP&G^IEg2ots zpe(2ywpmAq1ZG{N#hyCrL;p(JD#i}O3*$`@MDpS;T=E2UN0%V#it_|dhJmjGMXEPX zDuGqF2ojsZDQ)f>RJV$Hd|IHw=6(cz;6pLzc^oWn>b#JTl8k;}%1>?9=5hu1kg|Fg zD$R%1- z=I8vH27Y$SF@@Y5nqT0sW!nKfYuX`rXdKN1X>KYsaUCYX^LI z5C3v4(PRD9n3_@3CnBBZQY7JGAxZ)`f6;7Hg+?wYE!aEkb|l$1<_ojCNrc{9>TVbv z(9Yv{eoQnX#$cw0zSXOBb|L|S)Z@p&xUdV1eQ%GCBg4lA)5T||P2yxyC*C0q{8=U; zKlrAu=Do#GF$DKiRJ5t4Y(FVjgwB`#%J!cxeR`ePOcinyPm44y{oFrfqSG}4rg{8P zrekCC%6kGz1anfQ4T|JYGR7Zr=kB*mG}JrLCAVw8?3t-lA4CAZJ}uI`R6Dh%v&Qq@ zYxVKp!qBiJ9`oEmGh$G1h0xp`mmd4&o3Vajzc~4Yh%z|FHqYcwFS@(yZuLapxC_Ua z?IqzqM}DZ9WK7vHS)*?&YdeoK9yLKo@2M=a!5B2lWSYBX6>QWeI{xtU3LnrD?qgU$DgnT%4 z?wnCi?zglp6A54o8yKRXaTTNcq|FwQM*He%RR+W&sbLXi3lyGt<;$iq*(}buu_b_@ zAe#d+);0GPx`h9$EiA(!yr(w6mO6Jr&~tzb;eGBQz#SkR zm8!P3)#raMrNgD85F*I_5*N31-cmK!cM3;Uxad(!O87Vg9IU?{fB*g+>z*TB2VRci zzvbZ?@)>04evUbzBM%qc$kMr?KJa|?qlX@@kaZ~mg=>Py>h^H+?G6{4a^c~P{W zCHL*ySDjcnWL^$zr{pd77rRQK)j(UUm{Vvg^x?w?k{SnrS$2S8(->*Fywu||UcI-U zo$0g)-?io932%hm=-C!&lQp&9zkh#1u?Me;fhrlRggtxlf>(Ipb7uA4fPO8YWHG-O z$7P_7=Ead&2Zm(;vHa^X+IAUV#LWdP(UOTXvJsajj^6ndpbER0B0QScI>I7)065H+O7bqD+3s= zOuFTqpF(xCGi7BJ^MGTdEBtk3Ko4{%6O!wON!;OTpt3KlnAU9Q#~$9RhwQ1`9aw7% zIb5aOUFg@zN|4C+2N;cw#g%?uNN0(qCtue2!}|r1a1Z&b+pDjx&Tf`r1ZWqVvPTn@ zqhJfVWJ65`L=sp*O#(aT+hL^uPXR)qHOSuPGx7;plc4O3Z{uspAB{KIedXl!c$ri1 z6o45>n^~i7;jowFv;orY4ZT(8je#JWBwqri%Y`5rCi4CD52G5K)eF)Pd$9pXcWa!X zih-MjlH;mXtE}47`7$8~8GvTRfCa!ye?7}rTvm-?p&9x4dmcZ2oQ8D$FM(CB=FUO$ zD}cDOPo0*Eh4*Rz;%9?(tP1+27&>{7*sFi9|GhJA%K_NZNu(7(GtP0qjww z4h!V9g&GZMP~p7#OPh;bb9uZJnQdI0(jDWR(t-FF%*t#BdUWd|I_Hl@v_8;|9DnMc zM}yW6+Mnv;?9^%&HwO=)KgTjU1)@=y`vDt&9 z=g*>}qe~;~Y5|>k6(G~*0XYi*=1#JC0^RBGNOh&*Hy(>Kn*sl^JTkevbVzZa-IFd4 z;L-u#wrN2pbg3rpX7G{cy#~VQSx6NExzT?OH;#Nx9N8b=nDDA5K+fdil3=Z=;;Hjo z7io$sN^HAjcyOwL^3(iW-hvC0ra#D-x0tr<;?q|#Wv;!<_Zja!8H@g~o#XcBUq|l0 zcr4(wWRK>5Li3mGnI)<;)okUh3LmL~%r}uGlN~}#TC>WnYf}uajC4BHxhQ$x+31@z z;G?93H8TGhN&>Z`fQx{{`X8Rdb``Dx1XlagR>AGK_k&CmKGp#;@d^^YgUc|58=AYB}B(jE{pKU3Ao5)6@p$YJcz+5aDiSmW0sx^SUd{lH?XsFLi|MUSp zAbl6laqda1{OES<>T$rjx4&KLdDuT5_$+JSUnd7VphCg2T}nfpSyD*72CT9vEpm*L z?)OF99Out=gr6ZstAt7f((e>jI6MQ6kjZA2c1`h$FB`7yB#h~r1ZWm-KzmQ`G}`f< z$y7%4nRr_Qpf(c~cdSr=!=)X{@0s|=123)Y&&qZK$CkNxG}QWRxjJvl!#w_OedfSA z-@a@eYNYG}+@W2*3`$>q7Zh~Kl6rEe^Z^!3lnOw|7jmH5Hm6|y+0*4#nP!THfZRjs z7ULe;$hDBZsqE;ITsZjKe1OoVwgVwufa&!NneTt}`Fxn7Z21l-6%qWB(Bz)szh`x*mHavg_XGpIN}RS#W;) z#kTvG7QS~<+_2&EZAZIO)6fl#j~=egdEt8V?4W>Y3VV*Gs5CZE0d-67nBb%?+_~1t zQ?dV8ZHKYP#*hTsfpTQBB`SrB?p&Tz5XOrmSMCNmuY9_iDUr28ZTI#T@5w6rH} zj>cg{EQ*pSu$B%rII^6EF>wL(b4kp=KhnpgJGiJNV;P5T(upJ!K+XE(%!I8C+f2bX z#2F}Tch+`*HS#E;M+1u70#v%zXWfZUHn!aSW6a+~0DlqyZ%GAU6}R z;d&@CuviiueR#k`Rv13nXZ-WqJ0BC>kAHl-sYG;7W%ai-4>!(aTz&}^<7&V{dM|Gc zE6{b!_iGu2E}EleF1anl&G;wprs7s5FcU%b73L;bb)Uneddu2);WQVzcvR?yX(ugdx{A7 zWBHGcKHykO`1NZUB60#X;&vP*0FOQ&6QpkgOR5Q8k6dY4b&1W%I`h znyI!!{=l=_%}IAgqYYJ5rN$aFVAZ?}9C)d#*C*c|svE9!Y$?(i^5^6~BHQlFNj&LI zp#}0eRT8<=QXngWt5SyOJl7`3I92v3HIv2? z@Y11z5WBK_(-|(+3X>QHKb$$0SO4CL@7F>aws{iFKO)>Z31aD2aLII2-_uB3w!F94rWq zg?-Ook%jQ-!@Z?hb`{eWjn6-!{H#HVvHJ+*D6GLM6aoV8-8$Gr@%Wd5s>rPd;JG@9q}Pq#jaJfzW_!52WK^^^Jx# z{rPCzSO*N~A?37B9q2KBFo6w`8lpAtuwTrZ8FDY=3$79`i!Of0MZzy2Uw5KQ4q1{H zOp^hZLnNMJfFSFs;liuK>mfte{fXx3}V*ZJmc);i2-EhlVyz3QUyk0MRM= zO=<{-S3Nw+@!DdyuP>xAW`SPouK;yA2NTPH-@^Z`yo`A{$q=~!Y7;5=KJJJ$dEN^3 zDH0V`OE{{K))eYfCAj1OPQ3hJj76x#etg*Ai|v~hB+Mr4}M0B%w6+h z$ZEu8pjB|iJxQS5`3>+a14D4nm@XaMEa&{(;oazZURFK#et9XKnUVH}0k}0Q!%g#S*z>8 zB#GzfgT)EXtWKxVgX>bZjfGitcs@$sZMk&*$zWd&J=;kUN)>MS!Q@Olt>nhNIywHx z{(u0<)0ZHXV!TyCS>_MM*?eI8Z>okP$=tpb3nn{(*VXh&WoZ*uIzD^W%%TVCiy04o zUrlc)9Rl2ZmXiyFF}6P0*Hk(rDNtBovp--YbVM>`^G%kPiCjos4lKk1X2_)U!5a9N z4D_J5p@R3ZZ)8dK4ONURDNlv&{l%>oUC(FAH9w8~!t-#8tebd6Vq4PY1xcANXHe2A zltW=U^K~JY7CoN4le1p?A#KeY9+|`D=`Auy(p1|4&hE<-c2SVn*I^$~!uTZcW5xLE|9-mR2=B-G{cv;vmqiCj~d zR4t^x#SFVA2jhsyCdIfgL{30093E<^^+6; zQ=PM_W`_Ug3sn69(MwGMEdPD)bg3yOHD_7F$w_8bAQvSx+yM01@10x<)Me7qK7BSo zGWugF&@3sa>wYw|^?cr6X2zVBdrG?ZS+aK86|O>Wy@o!`L+*IACpyZnt1g@mOnq1U zPM3zM-ke*^2N^k|ZVOg%w1Rqdr<+qQOyfJMs8kDS7=hk` z!dwiXAzfHU`PWOr3o*pf3=GturaqtkVq3fc0%KA+PIYpXS5QHGwo`xr1ex>Nk%h(I zz(u0pT;DO7iFdr?kFqK3j!g$4>0$be8L@6!N>GJ?EZI$(K!;l#d%s>X22IwXg#7)g ztqG8|@o-;+Sw|mKu&RNS+MiEbKSR|)$XxV>B#)=9wBh>|+1ypsTVZ9mf$7)CMeV0?7|ZA5$9-mB%F)I@I6ymNwnvDY7a6iQHi3 zqq3wb2P%4y91inOT885>y%akZ<W95em8Qr z%;)F7jD;jyAwg%M`dq6YuO??gqKm_6!xdPm8+F5m@3;0oSW5?7C^3o!C@DWJeFl~c ziWjcJgdr<1ySLm}CVa;H%|#wEiiT-3?lKi`lN_O>3-12uCtRwA1m@H4#4UezffZ64 zC_Ra(yci18(U04Qz)=Rtb&irBmEd657(9)!bjdEozHcv^qdy?Ss!tu5mt@{55GpS9 zP#W&V2$b>b|4dmUEzKL1^i%DzUi?~2hz1wW)ZXOAGBR_t8;UsW8Zsu@Oo5g@o!f|I z)*1QWf4I$t`jwukBSURgP!uj!J`ti{WS#SFeM|$w-30kbh21$s>=S<}Vi%=26cM~< zegloDcOMb_js&Or$)S)*1!Lzo?9cZ~aG2?K)IEfHjTrzg=~i$P$Wnq>gL-#Fk?e5C z3Uyyzh!0)`DGiprIYp~(9hh(+v&V)B?f{R|>d zr~lbgRe2()Zz@})JpNl$GT{(da?+#o4}B@%7vD70p$_>rAsPWllH`V&Kv-xr4YxcN z4#%(>bZg1>8(5{S8H{q=Y-H^4dBD&~tfU4Lu(e;9w$*QIHvJM?2t)!dCxGZ0LO542 zHxVM>st&w?7q+HwF|TWheVNbd-ZCOJ&jShTPT$%uM0xPvEDKH4Pu=(jq5MwTcOz%j z*|QSAov<`QE#$g2r)4mLOU573Ik10}-+kj@L_j~rAI2U$`)}=hXiBwAln{Lk9e|eD zO`*}2q``}$W`o>9Hj2Q*@b|gYoP9Nfr)aKqKMHXKNGGC=znyrGexN3>EVJ4lok&fi z{4Qvt46%YuNut~kY9b&|X;h&Y8%723vf7{%%Mfh-*VqWUl73V5qaD(s`0}~Mcy2B) zI5y#H^Q9~M-ZQ9rWGDH9y*USn6&1ZK!a=BQnE`9GR_8!WGe}*T5mpI;8R^srSr*4BCI<$kPlajt9aX8GkWZu>1mnW0>!VW zb}2*`3FTKj>+)lj9N*t}O!q#XKjAlG5@~08{4&$%3TDSIg;HLEX`KX@OyOH$V41Z# zIoP{HH7(NEuKu;k_&h@L&R*LfAi-O7aH+aA{pdTck(H+(FV~0ql;aP>{5fojz$y^; zg>lB(lmr#cLojQMb8t3rROwdFrKpXp!o|=59gPCLx|{Eny(XFh9gA<}Y;auBb>z^C z3Y=(`B!Sm>N8V$8oTjBcXO(XHDp>wskFrnLW`dX+S+UL9PeY7tEy%r!osSeTX#e#S z_{aO5La;R~?PUlZDpSu`7rs}rcTH-vYl0g&sZ}lsHROxbwCs}pXq%$j?g|t7>(M;g z_$SOzL@27_3A@(levf8}`hEP-JW5XMheXn`$olF_HFp!imd!N>O`8(xbw!>ARYUTn=3se;EJ1>$rjJ@ zd@mmc*vpQjYT9_`iCaFhlZZg3fPL}EMXJetgw!`r?{6IjbOH6)Ck66s40|ydO(d&h za74)Dmj{GRC|X9g)I)r$5X#TlB0;lB?B~8O*{?=Z-vKE$8M%w9gxP2+C&=JpvJ8bd zf@x2pPaPh*vlahk>>=e~Kg=9GWI}1=hzRWiX@qp$Sr>_e`|uI8K0(AH#MDG`bfaR~%bP>_Ryjf5s+st1q+{Godb9UkKiy>x8qmwRG!$ znSjl>s70<54)-CI{Ei8o!Zp4B0?42z6zg^Q(il$slaq6zT?umm6WfwHJ|=?rJ}TG_ zRH5bv5d`HN8{-eVRXwSKvPt|l!6pg(l=O37`S9wTx_&5K@_UPcbm!z*p~Ierb;Ek= zP+g2axAe&~rD~+-v_f@=5>NUk2dN&Dh`IFCY2#laluK5^Ni?VNWv^A5x?}&>l^*nQ8Zj>EMv&50mKWT)hx43(^QsPLfoUQqvteaL<>R^OTT{cHo09@gKdTHH#=lDt{a18hyOHgvQxC`bv0lNRhF6V0fdQy#rv~}) zFtHEgPhixq4`L>quFKS&On!TrS*@o%n@2k~h0=B0RTC(i@wI1NEMkcCQ5S)E7EbL| z+vt1dQj~<713BgIl4%>-Whr7}!Mha2#E#RFO?6j}N&`5kc=U}w^>U-DhyEVEYW(R( z%K1QLH2(G_WwUo1%~KLEG6Qn{@1_*a+Tx~nPCH)r+yl{cm~ zxCPHzf2dKbI>^JL)_dQa1IOp2hOK$NplzQ0-CPcJ>orq({%&|ZTTJw^t|-UVr_HCz zItFT*WKt^&pG&m5C{jr-J73ZQNm$)fjYL} zt;UmxMVnXA`M0_M z`X<}piQhELZ8Y(V#0j016dAs?0KUkWUQz%f3ZC#iDDVEBLI zkMg_SAk=R!XIG%zs^37Bq_8}G8hohWxSKdljWRWi{wz73_EL>%w0#qW&K^#yC?_6M zdZFpS3!7x^Aq&_Qk2`HC>b~$8NbKRXT0g%LH@4Z)&@P3Ae6R1QSpAOvz52fGZNK5i z)FF_4*|r-BU?v(ozWiNqRd-{D_HA7C@hA9bo39A?omWDK<4vMIK;+@}+!V^zyd~fc zI+yq3!RG^;ol_ECQ`a_lE3WPGsC97}8L@+x9JWq0joaS27RNf(n`r6uQ*?{wap|oD zu_yY8S~ zP8;b7gsRW_x42mvVLaA^h1~Y;(n`W}`0dD*tGhM?QE!E=&BZBMY5L^@$B&@vwpL{u zg*_K)r@Uv?Pq!X~zkq}2R>UX27Qf*vcc~ekVKs`gAeuXAAh1%$QgZ-D0`6TF5(&gfCyZ0>^eaN1wFaR zRpqA6uz8b5WH7>kHhvKe;B6%L3%WoIcN_wvI>Oej2GKL=&pUR9hP!- z*k|kf=lE|R*__l>T-tN}EC}KCFJlF7uzq@t)R|k1DpM3{s?H`Cc(AU$G6xRMm6^W6 z?Xq5EM;te+<)Z0C?(){XOPi{%&Y8JOjm|DBETx%gk%V4Vw` z4Q0xCJZ+Y$%8?^SN|h+80t&25Wh&>92`e30QUG7jPywo1c}Nm?20)v0 z0dN(k0VQn7+z&v%Jp)8DJyqx6LBW8&ER#b(I*RmzDiU5zt-_0~fYoqUIn-Yc^P_({ zV3MxTQ+~6wk203@Z8ZM3PxCStlm^$O7;0Sl3RsfhtgP+ZTVt!YV&NdrB zNfM5Vls1~(UE%ah@&Z7ZEaEv}(CxrtxxO{Ir$Rz}WH^+(;RRaS45Vp9+&wlJl}&=D-z1{ z!$IFF>p)3Vz>KU<0kEc*dmt)-*WX4bs3 z5z;d50TRnJll3J;m6BGF5K(m=yJQR)hCC?S3;g&M5kK2TUbLkQWWYR;wa+g-$MW2W z;vCSdV?6^2=Hy^v`r%Sc9q9dN;W7urLk~C~lRsE|O$HD=R!!EFiG-2QZ%ZdNbWPe_KQ}0AP1&HrA7dV=Q4EW#$PLnECm(0O(2s zg#S{n54Hmb;`Jn406uy8%qK)7Do`Z^zOI7Ovw%L>&Sm27^z+@}*OZ=UeuCq=0Xx_$cesTb-a@FME{uLIG`Dx5k#&QRK`qr(Sv$}c0z3J|;k2z!{lZ7OSX zng(L|Gl*+khzr8aQk4}J>hG)Rdl>S~1g+jJ_eujSijroZ%#uR@YiX~4=$TQZV<-gR zwKEG&y4awec!gU5@9tdl_SK0%)&C>RR+ zB7*!g==E3epxssBRM`~fS_urrH9HLZ_aqJXH?vq+VEHowWwDfik0ye5k&*c}9b!3#77Qa?&wV(~^h|%4^T4UYj07M%Ur+|T>%h(a#b@XbRy5RG2rN$Vp;Ew057+R#=rJ34DOj#O~wo3TS4Ln zW77bq#S81ca)S=+f2c8V8F-dg+FU|K-@0G;t=v(g?roNia&jt2dOj0SpX<~ zWh1Nyb=HAvIHW8G%fAAgy+%JuM@vg3)nzDQ$SFDuwnu4MS!I{QmMvRA`>(j5Lfl$1 zk?f4hx0sk%z6YWF{uGoh4>O-FK}06ONiwK+ILdIOkz-kX+02j0KG z7?e$aWbpv(i%em<)6^@3=oXgUraZe@@RzU$zU&*aCI(&Jb#+zNpdzQ%n8_ zle7JuhRa$QK*Nn45)GC|0U0=D8AUck&B3bN{=Tlm3X%Xb&d*fbZy6aKy_Q7yLY~77 z&FK7fHubrX#k6#4HX55#f~mhZz~2KdcOTZ%R_L z7>b$*YnBk9JSze$u^%40A8y^E7@#4yH4pM?J|O(A)v^_mhuxr-ipaG`PKCwAd`@&I zhjKlq4$k-Gwp>N^^&0j8tRMOkZ4}Pva{PxL9c5q3F^?1rZp_)H<#PPQ3AuYEz(&q?Y?HG*8|>&g_`XZl zI(k-H5L2qQXt#YMSbLYGV7IDK16j)LXmBzwbz!*-$RmiJQ3uJZQR(2u2S6W-;I#R= z6Y6MlY>y5L3u{m?Gz3wHYV_;BN*~?=hcMVmsZCw3uCDb3p&I{#6g@fcyjH=Go?5wM za$qM~q%GZL7M=i1eEKFHQwA~7X!*5ANkFfj^2P_wb&+e!?pCyQ*I+RxP+D_XQRB+b z>_;0y!_deAdBxHGd|TJSRfieBBpE%JTK5lsKLLA#s}d?G8=*43PlDys})JO_) ztnAR;-F*(yUCQgK(WG~sO8>I_AIMmPpUc`D+e9^!T)nm~(6qtIQr?Qr4v==9SXB-% z*lMrT!6RDx_KDnjoD>rmm-*0BQP=V)pd}{~%-yEPj$OubI8f2}fMqK}Y!M6@9uYA| zEd!y|kjArmgLP+~>I$lr6nI8E7%gH*+6b+NjCyx)gw9!GI$YLWnbi*6%|4oImn=yE zfGVGplGlfH$fuaCc2gZsncCV~yJQ1>eWA%hHkwnfygdi!ahivaTt$}yl#?;;{qc3> zGLAsrk_k>>)C-L2Phfq6C^-~2L30|5c?eU8kGZ}^Js*1Sl-di(%D;DagViA*L|1a? zY4yXN)Mon$!f`9MLCUH+4f7Y~sNGT*`f_cjy#O3hfWiH#A2m~0QC>h$aPPKB$}6Ks zk9~?FA}s?#vm9-(-0K+`8NHpMNJ3ED2zFAoh@ZD_YbS6;86nmtmtbwtj70A z`4n};tHforr~uC}Z+ZJu;7>iPf=q~-YUH2?f&b5qmSkj608Q~~1kImhmtjnUy1-{p zpTOjjUbhZs^Fe%kd{sGAzu`CWv)#AEhw=tjKMu)j2VmcsR6Re) z;ih-du(b`Y!Wo+eJ}w^~F>!t!kjjO&e-i9-q3jC4)b7^T|6+E4(z4nWXn8wGh3C7Q zD^&OH-TNvYt%f-o^0Ur!^Qeg)utIYTIUCkEbk=*z+8&n&OguW^687Dg?}HUwj2jEX zgetNY%(D9VZbc@XO^M%5vc83JN)t`+o>P!om2q`-%6>}`5FzB%2SoLhU{?}|3lp=W zIcesqfE=uNfS>FJUw&`M&MP-}$*%O+SnJKd@zl4;F1rpMJcvd%T0uxvplIoH=Iyn` zR**;5W=8cTqrsOvoDT?b*?aHmIxszMQht&#XtXWb#Bf0D$&%Ta0Z>jK83NvHc-h0P z?yj3>Y+QyJJ1TG*L%>1>EFFj?KEV_IGvsI@x*Pp9I0scjvjwG(X`)ne&sgwTNQw1E z1CXZR6N&D{)c55(?xaC&mxRHR$qOu%2V3n@aiwhfo>LAMHGK@1i;9Dx;|j@<`}$Z( z-U*}Ca0QgR9CUR}$X#<+C>+HP?=H1soo2%I4u_=jmH8kM3m}UZR@?8bJ$m{Wt}uXn zAf&KZ0*A^e3D%z}hoR0U^qZKRGu_g!@}VLr5%sbd5e#!!$Xue4NP?%cU~5js)zUlQ$_<0@U&ocU43ujq6JQvn*Anh-h{uVQ1?XIdpeXb-69rxE4-<>!)`T z_1FBk|C_|MLS&4%7Ko<7%jLe{M9>Op(Sn8w$Yn3+3 z3XB?)elH2IC_2A)^kMqaAb7f0A;k#KwIuM#G0X={G_H5<+`*xpgxjs~@bCvZQ3iRb z^pVeS4%AegpXmY08P828AZNJ@A*Z0BnxqvhewOGAP;bNi#i&T zIjGErQMi-R=nq3H%V{n=ZKiFL1qtfNskCKHCg_Pt06h}22~}QrM{L^!_uFV%^X`<`=m$up>WWAk_E z%*+&;s0$WE1z#YuDJr$%YcsS7TvDy|!F(c%MkG>UV4f9P7%*Fpr|nHq8i4zN8=)Xex$c;B1zbuxH8bhGo4pjQ z;bgJu_$ZV4_WIJqW*@@lNk~WtozK}z{NOyyUjl*IrLgn_mysOLA_c5_302sZV0szm zm}0%KgW2=J07t?FESb0kq$=)S-mC%cMG8Ul~dBa1**W>bLH<77peE$%iWqOIh&69ThZ?4yimIOW!HKuX>QP{II;LFyC?6CI2 z9aj1$;_qBd&gp3G-y63eN6`Yq|H~Ucc5*yTqCL``{2u@NSqbKQ1#} zo%XiX-FQL#RX~JiRHt99L8k>cSkhsg)}FSAGDxn5L{~TDr)tjr!=6*K2+VOIpm6w5 z@5dt`eHm#FkSWIP%SsC(+>_7X%wnV!o84n_inhOk&`Rd~2miaQ67wFRaGfU>$J^7^ z05=g(Bl78<>^m}`hGLFu0Rtvcl!v!1UzP?uEI+InCcoc4rARE7v8-ZZ zUicw!h1!7zOXuxRiyLpH8Q~pB2nLS5ci#8P%a@@t7kQ5X!RegOem}XZn70A~gprMB zx{$2&)TvX&h7@5W&b++5a2v5S+`(A)SNw{i0Yc%3hhdx<5}p*w4gn2f1P zI=FNwNX^c1L* zh(me%;lrw;EaH}-tsZg5lz69kgR4qHKOqfSvCdDP=>eQOBB!ja3;fB1Pl#;`%~`R_ z4bl~ZT5{gMcbzYFG!1S9bgN5tY=Y73*gcI2bL9rSEa`ZG2vk8=mwIei0`Aw|YANJ9 zL!WgJ7Tz5U=R}pL`EbRGAw{j{p-W&#dV%iW8ldQWXn3$M*v0IK1o1(T@ojqy;RMmE zG$=fIAgm_?%sCBBsUYtJ^NF)y{O=)g!#{D-Poa+9bHp2%!<)_;!ge;P~_F?<9)r}O{0H*}XfD3d$A4`1L~m z^Nr{>-xHBnM*5>h#Ms+Tr{TX)%N25nV(OGp*Wzl$|(rKqF@iKBZOjv&;;Pe)YmE30)F8 zz5l{J{r&s-kyj8zR~C2%y`$rH`N`t(dJHZ=FO-Yp%ms`L)?vE&yaP?(`XxauK0PIN zEg$1MkMhqTU1A}mm6pS;kB?x;xwnFh!*@XqJHgGN2W-mV<^g;ctcarx+%@X;Jb_>W z@-iZ&htLz z+S8b8c@}LNBY@^Asw_6`VAItmCx!Qc=QSOQc@~V3HGbmK2U}Ts|M`I0?bb3lk z^gNufwc2qw;ApLD~K{$hSfBjxy<8z@fl z>%tufg3(w7w0+zAGE6`TS3_{#*heYI5MN*r z!DXmMdf|{TE(+If@2&C7j=0lW2?PfD}Y4 zz@gC&42ir4qaacx52RLB5d1l68J-XMyu`Jgs2kolK(_i7&`I+Swt*&f<6rY&Q)>cT zPCft%)bvkquOf(jyim@i{Ej5Y1Qr9G{+rQj{|=!o`v8Txhsc`Ia{b-=7QuWG+g1M7 zl9OB7^9ADZrm4?{H0b?%BcNg>c{sG_b59j{nm_zU0_iK4B*YkQ_PuyF2 zK%*8;BHxYu*}5$};j>rYL|IBGbw$=0Ey-;h00tXc2@J=}_?jk`^PS_6@sE5!)eSW@9 ze{k^P_iv@j5Z5Rsxq$9)@1aI%P|9!OC9g!Hg?kv6DE`5K3x0IX4s8Vm1;W=u()Pkj z8%C`R-dr=mrEL=`O{qWEe;L+s+6EH?S$R>aK{=A5CI0Qs2M1?XB5?^!=z%!Knf4tF zi#VHlJjes`wt(8~NZr6LPrwl7sW5YI809Pvnmf}f4+<1A*KMEXK3Zg@z{8s&9Nyb# z!1qgVp*918XXTH%u>E&&Rg7Bx4E#=%zWl((vb zW?V_NP@4TenA&vKXINO)fx~nHHD1dD;jUBdMfbmi{n{{0`{OEc2R1GE{8F*Or;Ug} z?wrLJ^VJ6Y7VVpAfXv3X8Q5A>*U_b-Hu-?BGe^zd`FxgDT3A@v@=EboQTjGGbETT9 z#^||?UxyuPdr{gWLuIT}*GWiVG4wC@o&d@1+H+}R>Kq{8>vw2tXlRh~GIXWM{zj%t z56Kdig*d0JQVmEQ?qGJ9h)Xc6^yHc8>o3$EggU9pTRTzg1inHY2s2hVD^Y!~5Pd^o zo=ZILp4B|WPPM)C?~pJZ7JlW*2bJsa|2H6PG)YC};*hDG12<(hgcRg^a~o5z)w40@ z-v8h3;+0&A1mR3ZApVYuYsFs})z`x*i8}!9DmS}`Vu#@kDzUc|q*Zbn0|$B`5!-L^ z5p|ObaiP2Z^R47HdYW{4)iF8M$g++Ss8CzodLaBVd_vy=K;aDk98rtxxj(yveGlZm ztF1#dQ+z1du0*-H2LiQGaZXKAZazLXB4;~P1(h-tSGl7kudc;u$<#UpKP^$wS2Kx}05art2BYW;b-|t_) z-*gz1w=>ou)fFGA%nep)?%6ltrUg)q$XCM_Hp3>gy`&DypK+CM-|B)$kh2db{q


w0{&&>A3(HBiD7VdUF_SCqD%8UAGIwkEWdB#5O92C94a*Swr zZ`+k_;KU&bQD8y9{-00_R<*|zP~P5h$g3$Pg#-tW17Qpzix@QC>p*fHoX-Z!I;gI= z|NDQxu|5!92G7&C{zu2!9YfhgwE+dbd)R-YmZwN4{-OQx5#tG63M-$BUMyXTvBXY6y@vt7};-7LON~;YcP?yqRbwH3xhtSu)0(Chawb4AE*Vx zZnWVDLxFDh?uWCV{#lz!KjN}P4ae+CFZFx6pqnx+q3Ft{+kMu|u;I=3nLYNL>&)rT zW9@I9+TX5GHo+n&89^xFGX}f)pi>A^(?|&PQ*M}!Z~S^<3M`Uu!Yh28%U#6~2OB}O z9~+-VbBywse&CNpKTyA&?b6c}dJh$;u?!cx;E22cL} zCe=fyXl6{_`^Bzb1y@m9lB#jnYa9+bcmNHmy^X3?^I$LKZh)_ocmP!&?B)2GE?sTD zX@kG{$8jKNzU?#ked*2_65W3eZ(O(yfjRC^$gM$OmLF!;eh*oPEFmdy9!%TD@jKzF z`y{-A(iH+2B>h>`Yhxj@FY<82BX(Cs`rkENJWiVBi5!QbO5xgv3fG=lsrZn&xj7=U zC?o4=xVOibEp)65ZfXu%NPi>5V%>K;kUZ)lh7|8hhm+}ni1AorSp?W{5anolH|)ut z!c+(xk0sBC>4oeOD+y^1E~aUPEcdL6a1>l*#Qo77EmBUUnsM{?VIr=y%IZ7(DTYxhAKe=`{r#u^{W^=GDP#YqW`adm zO^pQy@Y#f&;AvWEtE#F_+WY41+bjT$9+#p5r9`-IsFo0fi>i%5B*=ipD*YE4a6ntZ z?+{rX2@S+`quSjTysRN|`aQu@(9)nodjVRLj9E@@t{3BN+|`8i7v`@-t9+5GE1Cl! zJAfdirz-oT6@J3U78XLO2CCA#Aj3Nid0=Q#avWfga+cnKH{PRIqnc_JJep`px@EV; z2$5SirFV>q)Y~hpm0xvzIdL5DkzWyCS}>J_Aws4xW_Ij`2^$buJDWi!o=&_0GMWr= zHoSjZ3Z&_Z&P}+qE%1@LMe&HZ-XYAvO2g-_3KBTAOzU95at@zCP;db@@GktFQ48WQ zRpgzkY;rOzJ|e}xOA$Ax*7ws3Yv5}{lS364WB(frGvgu<7uD4kBgHW)Dt!2@NbURA znaBojoYi*PFAjkpy#s7b>~NBXnt5XoMdhIJcMnN}*?GZPNOPK1aV>U&<&*!E~5P>qqqY01UP57+hFhPNTXmv)Q< zUrr@wE_BV}^_bzfrN?hj(~k^;7?(3xXOXCL@OPOak<}F}l5cZu?Sn4s)i<3AB=27B|LUu+Y=i(?ro9rOI7JWdOiz9}0%xm3KMg9>Tn_S}Ne8|P0Z)ef z1aGcd=Y{wpJg*F%2}F@^mF?o)D@1dRPok?)5NlbCV;gqU+eY-w1=ey|Vh3!stl061 z>6$Fa^KE$F$psjWTkB5hcl^!jSZ0QTk{r;J$p7Rbyze}Tt-H%O*Rqb>kiwN(({D@p z1rf--wxd`L0(w%s$pn3@{5PK2-<~{IQ&V$yv6X*T|y@b&0fA>xBxeT+b zSFyw~4;jC@+Bc$3Rf3lw$QcOqJ}3uXsMW&RA*vtkt;P5ZAVfOZ%A`j0G+Xq}W{CNt z^#uS-KARA_?}maS3`$Op=eJT*5iS=X0qgvOb`@A0>nrhB)NLO}4`;9gwYx=NeiXDA zAc>$RwOR?SOckgfD$TYaS;>Hv?FHD*wj;;V+^)5NW*pnIg#Z;iY1s))U!`{Jq1y~aZNXFs0@y2JF zNB4&o!NI{b9F0;Q$2%YWKtZMjJUw%0a6%VWYBSzEtA!yWJn2{fsVdF%cLCyrAGB-= z{-kWT*ufqpur0W>ta|$%X3#@eYfA16GcP(u;;WgkbL_CcuJnSsQHFRI^s4#~)5SY#P;A4p!Xs)s%Qfo>a? zV=5)>)E+8g7wWO+BzOYy0vU^XqOu{;ABBSsw|s(i0f@g%&~kh~Ey=#)V--6;=xt(n z*t1QZmpV<-JAMov&Gdc=vOf<>+m8p8aI@0_(C*1`;{8y{4-nkkWj!Hi*3oah^e@CL zx%cIG>26t$$^2~-Vg*8dcOZoApKuw8vp{zR=B@nE1+n|D9nYVp%kY;`mlp)EAA;vO z=og0q=jZRmmG!Lx#_zqO{#Mh<;}dk!@2^9QPud6EU8BxjoZPkzENNl~t-~Z*P|k*aE@` za=D5xML^TLrDbI90#GW$Vi^>#!LcVxi0Zh~3jmjdA#-4ZOcqGCz6th72Iy3xx*u5> z;%Xp9oWurI;nn5Mu(|0 zMipH0MW_Sg27Z!&u5SFo91SvEwbnW+%?REnrU*)V94#Wx=;q>wsLiHR0VRxj`{s>c z#}cT~eif@@B!oaQVA7oO^D_;91)|X!@lfW;#zl}@9?c>`eqYd&C#11*`yTzIRD-*S z(*PpPQZoY$1rfly>N+U18?v3prc)qpa-@fTAYz^mDTv|$t$tIszO-YtI2|TvWT)@_ zGGekF!2QY*R;VVqAiDFfR$6DuNX?4u=;tA*`=yvzi}CMbVH0QVc=peo7KlaUzz_CQ z`voVkaK?{$ff|<=S%1ES$gF&u0aluJj13z*XU8$5BT=;t6$+v%zGe-^!cA!A% zwH%29TNNo_MlrdxKz{EX_bn2t8jPZRI}y^!A^cfcoCq9t1j9Vh#C9QJ`w3^Ou!WT+ zzj?nb%~j0~63IQY9J8=_AN8N%8Vg%Cf*vhYtU>|seXv?Q&cP%If|5#3ApDresw1~* zWCVe3hIN)0f1^qc)=&cz7r7jQq%80d6g zyRVZ6*Er9i`VP6rn;aj~0v|@@%cj1QMP}}ulRqDY_Mo#uvS}2`a4!aFr;U@c)1bK} z?UC8=Fen&or9U|CHNWvbTQxi`sbV&UQN0CmhYp6NF|B~`coH`uxfDj2)SVuY2VGuX z5qXTu`Q>!qYa@#L0Rq!2+9$_x!M3wZTRVZpE>6(VtM4Kn#a1Yz7NHWojwK#vGu(IM zA|0fFeXm%BVN&`pjDfl62me^o&LpOx?>=AZv+fz(V+jP*v#->$6z*L=ZGv0%FBb;Y z_L5a5sLBFcRq8xCRCdH^1p}`!v(sc;D-`oRiOpHhvL*_VI= zvp=#mWM>}Yeq|mh|EZ3`-u9tE`mGg}plcMmw57+9I8Hrs@pyZeFIE|;egA833ujFL zM?2l3B+t4Wy1GuD3JwlFpH0v$OcBLO81w~;daWb~v2!tK=e`N%Am>ZIJ0hEvoss)t zt>PccA|}FLo_mSdN94Uj0K20d>tCHZecE`(VcbLVV)RowN!kP(dE|OjCzbM(SA4PX z_vM41g;HUfq+|9ziqpZx6hdDMsltzY|$Z zE)=yGFuo1~uiYl}_%l3;4%@GH0pg{RRzemF+TILab)ll+oR4UV1ym)cdHde2s@@A* zvFCfh#a7)AqK&?m`rUWmZ9&;l$%&Y8S<|Pj*~5Me^8@ev2eWkKk_8K< zH_)A6|Mg%F)n}Py)5W|)uC>yv9<^jkD=R;~Fp++!-$K&(R7=$nc7MqWh%rmYH$mbw zE^=+YXkjW&tIDmzk3B}XOh1aFHiJj)ExN}>MaJo%yml4)FeIf0y`2V~b^nfR-+xGe z!V#CHwVDU*D_Giq5GhKisy{$Eij4zS+Y*>RELwy>*wr1jNXaS>EyOv_0Bu-k60tRb z;FMJ!Zm)5?7Gfqf4p>@|vMrUHhW0a*9Z=w0Aizr22#&1gttURMCL}>o-_5u&k=-0S z4&U<{M~*Yzko_32!!qk}OAm4khxDFNqHo3reC@q~2$}Gz;FCnv+9EC>EJbW?=!(^c za2dL~x&WEGcqb@mX=#B!b4#rh)jXcaUB9LxjUu~iS@CHwA6QUHd5>?G{TQ{W(P(-R zhXBJGdwHsY*J#&U#6}?gZuv2u0QQJVoGG#({S)9Fb)&0)&y{0FSjK9+J&7-qvTK z0dV!Rf?7lrQ3B?IUm+fR#Vbnd&I6-sqaX4+0=NpN?@idV6<$L)0_9q@h zmhu5<>?y%z{>L-|I;5^;6|on2m`>NOBc%lO1mXdU%J|0Rn2+FvI2>3ekyrNTAS3rq zN=9lTPzsRErPRZSX3xg$CwEaCf*D7e7(cY8LaU(ru!6iizi{kMB z{FXVi;32H(8Kh!HY(vC^?&u9rNqIV)z=*d{H&X=E?Ri)zULUtvgL(UJN zS~&ZR{ietG_QZJPd`K&LK0TDD|Cf zV5D-)U}oVsJxeE*9>##h2f>)8_5Lok@)&z*PmGan+VM{zYTP8yOmLs3lPbdgI`0ZGonS^ppmHbO%IP#e$Xdmsb&$57KW(KJ4F_jj2VzJ7kv#8PoG zy6Q{q$Jnn>t%4gDxB$q6pikg_>=;L<0Bqfiw{HMNg1lmV?R!WhHX|&?3v9d)Itkn4 zy&lQEnhouN5PYn8stT;OBg2fOi#Bv$m(?YgdI7W&_-Ff8gB4N6X$hdj_*-|m z0!I){)Ku;nHx*R9wfJS_9F8Wna_*0?X{VE1K|kV<7q!x-aOaE^cukKW+hHN|nd>c7 zR~z6~);w>g*Jh8Xbh^L=xj&S66034p9^ZG44ra{C8qjnbZ`602eKvw?*Z@0l2kfN6 zmiGXeU>`TWSKWZIQw|)qBz;ptD_JU`SFXTCFK@35J&8>)t=9fSZqE|-WaQ)B^wYj^ z8_WVZJZ$D~(~&3i)Rp#3XF$c8U}On0Il-g7X0FWk$A&+2x_)F`B!+yEH>kEPCqm!} zu5<6C4$_{9O|oLAuZg-5yzg3aQ@<2`E7+%mUiCFyABFwYfEq8d={V8ELW$R`1~y42 zJ9E>2ey4AXEQK}h`}LZHCJ|pA1FmabyOLYTv8AZPspn(Q^i#{jJ!g2}(p)O=-%7yW zM4K^*-=DxB2FA^@Zs@HZ2(VFTy$LyZ!6@|D7eWxs-?D199y9~kNKdg6+0;aX&;>## zK3el5SoTfrw~b-jnFG(;UwigyCtQFu$!;vYkurbPNe6H3Q-hq+9k5K6-x_mSY-Ze* zy-xU-XvE$O^OWI^s_PIf4V*=h$TWu-$P`4jYe_c~^hXe!nO{&B223J)*o^gNfBotY zze5gR?Ry~*4|sx{>IORgw*UkZy8UsiwxBAO54U_@EROZoLX0pRK*dSm|H54(Vn~7t zOw*I@%lZ;>#{bIXJ<#oEhaC@!a;l5JC~1@o^QjTQxrYM>%x{fu(yl9g-eYJ z9#^UXBRI0)X4z&$GBL`!#}N4G0V|}(Wwfb_ABg}|%%vh68xE+OHT2k?-9`e43PZ~2 z51yA=;V_V(`lS5kF%hQdE+^n(y#*kTzYhr#JElQF8^-Q2!&R$(V5EZ#P8WYQ3G^JS z?r3rw;RzS}&)67_`g%Utd)sg;O?&6s;1*e;HgCc1OZX9K`;6}W(>C6mMehr9$p^BC z4HDC0IIRfKP4fZP6PRY@MEtDKWf|Zw(Za2~XPZU3=)?0UrAZ5Mp#sa>}Xm73)F2$J=Et9?^_P=^O@B4F$BOcHpM|Dmko5iWZV3cCD90sl%Z`A@ac1hbrA#j&$jC-y>nlcY2C8LXc6sG@nOvebm6fB+QV|C+XOIn1G!x=2 zcstLy?zVe6UH~ILJwzISHDJ?Cr#<;%m&2is`aAAYo`?Tc_u;SGbW^vbrWB%h z<#DOI(Lduj5U#DeB89+veb9}0^ShzbRPg80tfH0Z#JZoI zo&9=N=gITG{2{X*$@e-m>P;Wed=K#5IN*ilqRBpDC&ks~>MNpK2u|9dpJB428#IC3 z*Ry)@KMOn&peZ2d9?2{T_jb`wKm7#bu?S(+n~Dk=muov;%prXO%naG!dIp;8adC0! zS+kw72XKtL*i`j-Qhlr7EjwT-V(+7;FalK6XNS=4t~PhYTejgL;EK4v4o8ZDeX@a( zD2-D<>?|gBpC9DvB{ypgi3HP;@-v zFp{~r-^7?04}^WfD=l=`Ppg2ouhaQjD7y@2cA!^3O-xB0_NAV>jvcv!z+UOJFX!<9^KdXo{y7kjCunbfd(FHxd9HD94BZ4G= zKUkd}HOj(yx138`uWh~Emc-aR9XAVKnL9skny7f>{Qs04c$Av-tNennFTQ>tXSTL% z-`o@HAG~_7Q!n|*!`dTrN4-2|=dSu-M8pjBNt-L?O!)PmZ+FX&)c@{Z52~kbul(@a zkpId0xmWdgr)os&#&MNFouW{KvcM+o*7}?C8^*b`pD_4XYe2}5z4La7@$vDbH0JvU!>Cz>k;9lZbIu1#${?1&5 zd0JY=nvOULEKiSm7z&P-Nrgmg@U3Z&PQzDykDvQn8oP&KB$r#CQ9iyk#zeCjkcua} zDAZb6@K~mrHj8QmCb@afrPpjQoaKZkmIKw5wUc;2%b)sf_e5Pl>)Fl~0D%14AM_SI zc_IxcV){9Qz&X=d?QVPN<>f^P211ZiT=u8 zvWiMM%67*f>#_|Ew$OcJUozW?G5NIi`E?b)63-MImSq)q%M-|rt*#;I{#^0i=I%6?9qCGIoojVuE$77h4RU1v-IC_V-`V2?N)Qq z`jQIhd>9;-C<;zoKOl0ebPncedElJ7=t@`$#g0Ho{4s@$fZ?-=KNAa|c;-Q&qNtbB z74QKv5AU6vFu_2(*#s?99cL>>4mqMYatMh(g3=iip{}O9355aLn#kKdW!&(<@We!Q zWtDE#zU2_@3XfK7?boVQh=2o=epp>y?N!rgzo_bq58%d9q0T+e89g7KTcOz302kJC zHYcNZCrg>=yvTw_AEDiv;itTuTMpRbOto|0(?9!aR#yPLhMS=c`e@+f%MlTiP}5vD z%b>gkmll`x>bCuu49RKIMge1o$BaDJYkYo{Vt_qHgg$BSd)UIH0SyGTBFIy)s(J3| z)2G%qRy0CoM|Q&DkB0g4tJWWwv>^SfWZax>3#@a4?pSY)iLzfEyGyeFa;~4Ak_0r# zr@g^t@CR}qeA?k(M}!u?dS$LQ0SR@Pdg9|kjZOqRr}C#tUP0#553i0DK`3k-z1z_j zlP}AC^%_^*=b*KP#CA>R0|6SFb=d*@nqSiSh zKx6joDGSt>u`?gV?{Elu_eF!R@9c5zjhWf^4w<{RAv@Mhg!0Hxjiv1O#_IwgEmKE6 zJ$Cl&*}6?s8uF6U^l5uJ?FppK9=-y@<{5I>qc8d%A+mu+N8casKVrEMCRDcxl6ymw zmoA3fUG^=&DKQVyfI@k0r6dhGe|{-uG4b&;0$M+o^u3i^`GA`C!lO9k%PJHg)egx! z)qqw2c77=!E2##kV$wVnSRp?f^T1%eLFuKa`u-Ks`LrSg_QK5&vavx;*6y?yQ2i^G zA*%-+K;?&J2%mbi!OIUh@-wc-bPhr#q+wJ%<@^52v#XI}-ooeps+cc!onJ*^RUD3a zVu!&W(4Sro4m{2$UwbXw&}3Piv@G^1kRRGHJ8J!kE!c0GhMy< z%mV_;$LC0b`~t`{_Pw$9DfWq4p1%eKx7#}l3JX_U|7O_uKk(I6~ZR*N($D zUDRXXY}Xs$;Zg!|Dk3yChftXETl>ypxw*T-ETIAwJaA~AfBGH;&z`MS(=i;9sV!~j zq?|DRVng}8d&FXJm)(Ps5%92BvjNpQL6wbu{aLD`y}Y%njP~JVc9uk}=zC+gYXhSY zEG-e)>LwzIxQosxwU<-1@$|wOqQ#4-Q&AMZajZa}L-Er+I2FLZ0E(gf!U*{;qOuWM zsS5qt@@}U;9V$Kj5|J}p(qia|9)0m=)JqMKYj|v|ayoe0i*0RfNg6d&963VE2~0zQ zRB>T>zz85O2DLAZ`oHt*H|IYsvXO>JFc?d3LUGVs%@s#T?fIK6B4X#SE| zeV`$0)Rs5*Pbux_zG_rj*A&|8Y+}-;l_{|Zi#~m;-;9!b^@7%Fh(Zw><9EF}Fey;? z&@Qo36eG0FNI-@U-;F0h^wAyGY6ex4SXtb+Z=Z8)B6P9J(8wv!W&JjmA}E`?>-EC? zTTunG`@YpK=Z2^K!tj=1CWCGOcBNK>)r}Q58=VL5Qi4nncA<>QlLW@tti;Z{4PaY_ zR=4J1%sHFW{YnmXY}NLQ@3$SE17XnD`qFNwl#fR1M>baM#5k=a%XF;C@j04vxHIGu z63PQSJQMWH@vco!toSownL+Z@ld|el{ZjhgbKyZq&-MM$GVJQrtJ{hmJ@Uqd)uJ>3 z+BS5XShc>r(`PqUmhG}U^HWOKgQKI|gp96YamI}shyOkfCrzrJ6ppEG=|Qj)wxHF>Jr4=Ni~#=*fPegCHc;nZ z_)N57>Hu#Me(?M%9FiTrHC*Iul*l2Og5C$le7omK zvPJP{k0LoF+Zlb`vO9f(L+t+CX=9VU?erU=6S#?~O8!C6XRZQF4L=x@FtDcs4qyq} zRg7khMQg>-F|!nJ?@S=46RM`u&S}hqNGkMTA$WUjcM{<-YNKKe@`K z--?TrUSzns=I;RWNY>8hl2O*$=NI65a4jblSN==P3wV@i^6{MnfA9D^tv!@TKU{lNZF8e z^z0TYs&{bOJSyxYLu=inPJcQJ;PtLkvw(@z3$(n5tIUkNBGN9YJC5XHs!x=$(82yD znCi{eu4N#y?MAQPJ=i&qbafOOC>XnAD^zNLUq@|o!NF3PBgqZ!4;zS0eGzH-J*Wpp z(1tj2G}#V%W34JV+Bv_LjYrO}$gf33WhXOYK_dO?mc{aw?-Bg66=5wft?X99O^YfH zhd|1DA=H#-Y}j{YmTvBO!nr-TX0u1cub$)Jd) z(qRXAmY4eqSA1)K?iRKMp{8yVxL~boy?bV{XT0rIYx>ijb3o0#fnHoR9K|!))myRR zVbp?T2oI6WdjJ*Oa>UP5O4INU%Ai1&WBoi;0ji;#VsDp7r%7mJ;C!`nsD|+I{tX>j z!b9$m&(Xx(>1tDfiQ-6)_Z^Tmp34I5mJq{OQCBELS2v@WOc;X2k;g?v?As9P2>H;L zfz}19nJB4yJwvRHq~&mIJBH%n<=h6g{jH{k<0aCVTYwM)cbO*RtsTth@Q0#PZH)y_Q&fURf% zm2Xadqy3$Gr5Db^535M5Z05Id;V=8u!-IzE9Und1bCfE{_mlUSLk>y4(vtLk7Afo! z*)Rx5PW_dlCS!AwA3#jVx|8Puda37DvV=y2_P_RLt~EZrqq+@iHX3a0xfO|CQDfZ@ zVSHp4ibq8T#0u1L-~2c1SxP6B{xMP&Ngeuf$jN*Whv={Y22Z^qpl=Ztx_mOd?_w{; zd+@DTl}k!$ah(@|6x0y%Xdkv#-KNO*$pQ0rQGFXS=hD4JbR!1F;ZzB`~Bj3JcAE6Ju)EXZ+2U)#5D-wYc%bK9e^ zw*QPu|6vqJQ5n66%U4=u^tMpzd4)#FLA&;JZ=I4 z!Vm>aaoY?34q7XSORhaihKG&KcC z0EFWPm{sB{h6i`Px+ScyUE&M7)D`^-kt@{(UN>wS1xBeejc+Cvi^>0iaAN$>^?szJ zY(Z^xvGxS8$5>4TgphMZy6>%5&G_sYkX8=`Xi#UE2M!w%2dih%^O0^B?L=E@d7zJ< zt0WwJQ$8@tU0gxAQ^cU@FQAj*Kp7FMTZT!*njjXBE%y?WM1F0w#Ht28`vl8~6fToG z#+VT3%3Nh91T#5T43ns%PjClsUKw3$Ytgw*c8+AJ8Z!r$O0w+UlcWbCV#)s{YI7ZM z@B{zqzyDAF>Hw9R^xxI^?`m)b{(BNWorC}PtI_+-+_77F9)zMkhR;&nm5btk{`Ft~ E2Sl}Jn*aa+ literal 0 HcmV?d00001 diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_x.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_x.png new file mode 100644 index 0000000000000000000000000000000000000000..1355e5f69732df0fd6b014ea79cc314cd0efa906 GIT binary patch literal 229730 zcmeFZg;!PE8#R2;Yl~czmQYbaO1eV@L;+eE59@mmQ>rG6jz4~O8r@Ll*Jw~eT>jhwl@jlH&& z9?DeP#=^wh#>7zPik+U7wV}Bg8xso?E5ntiHZ~T#w{QRRdnR)$gWEUW#)_j*S5OZ{ z?#e%loF6v!BDA5b{~5#C))-djmCsBsSEhn4Fs^+Ua8X3!3sD9k;e_=2ivzX3ao5gj ziKs2yC-%CQl>hzOaJXZj^ex2)_#gC|7Sc1?L^j^0O-Ncdwp9i&#aZijhFQDLVm~{` z931dqDahFB1*7lQ>g15X<^St-=j=;*fq#9Ee7Wg?`v3jaMSRrp|M{ak*N#2;pC6ze zh@j5@?@!*GcE|ajpIpJmVg8>Vpsrs-Axr!GrbwK@BXAT$QzY2V~4*&J0qr~{HYacGee-Pqu9sYw5M~U$tgg9J?{~*Ls zK>PEu+AL4MeSGKt;ll^<_CHYW0-D0Y!dVBu_BS#9N{%<@ zId?-}4#!YU>5k96i(%*D5{s3dUY`4rp4XPT`W46iyJ6DW=2l;K_h!X8c=OJGPtu>w zOeR~xI(m8vhV#C>JXNoCu-(Uco35&Cv6Am3E?NF?-eT2(U}o7uDeLWHFamb|dpORH zP|bdFw|u3EULcx_on6Gm#f6kuq3#V$G|5zqo2&oS?ee92466CbK5yZ3Kjx>3BV-4P zE-4}5Mx76-+zcsSyfTBLBfN3EO^1(}i_Px&R9MJ)--iVM6uHIccK??bcxh8pcW=v}mVyck3qv`K75%4# zJumnU`KJ_L5F%Gl?Pvia+zz23a$rS71kLlwzORB5UcMHqoSy% zbTWywYP!W@H{b6)kK-;LA>d@^yt`a45Uu65x5i@Boy^LVnx2EMhr4DQ+uvCnUD)!Z zawV~zY-hRIY{|#0zoIPr@>4^@H#a0c%zv|{a+=R^)jW<0=<^raCowNyzTXnb!*)Sn z^;_|nH~knyu2O;l&YddNN@oZDgI%mZ^kQDSAPcN9E7SM5vNAr!Om&r&$F{b%-F`l3jp>_WVHO-@eY3?ng6@mF?yHv5rNPx)3Sr&zc>3ijP(q`V}C7zZ`p*U^FR zFSz}b9InT5eZZhToWqz-;0$WJma%9^cEuU?IA_##C)lv{w&3QEm(%m}3=Rg>ug=J5 zXb61dyYEL%+LicdZrK?-*=jjxT7)}|@K4jee{oE9mbE%8ldTa&HSGuEK~iHAAzBOd zq9|0^2Vl-_S8nRS)z`Ojjgp(1ng&Pzf#NfPjaqJ^&su$^NlT#9o35g#zWUaF#38AV z?-I>phMIR?m(9yr*1sEPQMMB^sguwvrqebP!DseU{zZn(k7>HB^*l8-9Zu2?p69dNR-EE(Z(s}7i@%C&Qy6OEb7M-tNQ6s&bofm^{KJpf$bcm-C zlv^i&Xn2;TRfCI*3*kCHNyMm1U|zYU-^kae<>nIBYeFxFBFA42soG5#--;7`JC;#2 zLf1ux+`p>yIobkJ+WLYYx6GSdiy+JpLh`|p%IHz$$5lO(j4BDFYQW;M~I4Eg5Pat!t0 zQ)VU;Q`vm(Gi)mt2Ex`)?lI2Eae(Shcu>p%jSTRzz+9`qYVQcd` zj>n(fS2l8j1l1oE<+?qSV=|EY3<@)P)MaDuQF|0r;&S-gBrt->TG#YI(RGcG;bgL)l{!Wg#$+oD$xv1k8xUcMQ)(hQN zP*6~}=@6|Laf40x1TUdU98|pR)uCU@Iit`J0;Q&J%gYMu_dwa%9p zCoCt!4A!@J-V)zN+7yoZ2~<_9#O(?KEtfTgMn1Wu$BbR!znl*CHZaftX&sU(D+Q5G zOk_F->2BSKJ=ouvGIQv!H|zW;F4vP=OP;^XnckVF{kfp9unuap&Ty&i@^U?un3|eeenEjK zbkpwcZV@P>{GFTi}r=z|r8(!uz^MU+_Lh9Sw+ly4VxQYsa?}LNr ztcrDS$bAw{6XkA*Hz=XV2U(5>iq(xcEo#in%pZe@$uBJ2-{n~URW!Q4+n;YJC$FGT z`z==ZH`sx`@#(&=H&SdjmoaXxN@iBrc9L~+h>72gc)T$P6J=%5s6>9^S~Ut^HOVpIB=dPkB_ZvV5?j!Yd6+moxgoPa(@0i zwk7AOY78}ZjjN?T4-Zd&g%ej?T-=|RF1-w*k-8=*xbMa_ZU{pF>T? z{xraRvOYttDBEg6Ttr0VNnfT$u>&?SwGZjRtr1*e%E~0$t1~ZU6U1laZw2z|M-A!^ zFO;iSI+H>eeGQ}*v)J9VM819V=FPLEA2>rpLqF!`-nzS^RabLP#7@l8x!vs*;oEN!*t)^=f-eiL_^-C%yvsIv|($^IcF7J|(5!(vrpe za2YX;RP?Jj+SED=YinVo55zybWHZ}+CW_bgUWwI&O={>$P@X}%&S0S_REAT26nwAQ z4BD=6a44*CYiepHD`ipg+Dy9}#JCV$y?WI|*7D*|y-ud9iIk)y-0~l=MiwjM4y+ z%F4>VTApf;sjv1p2jTeic&ZbtlHdWi%Qm}WmZon*!-M(3B0N|fPX7rE<|V)e>g(6X z-GrdOc4e#f{b1<3rQx7C`8wwZa?6AGao2j4jC@5A*dXFtJ#(0vYzmfUokjIXMjmYRcu5YQnbG->Nd zKKr(XWh;ebX`HO`m9v@-6NH;PJI0)uUTO2h0*1?!QQVfttf$&)p?X>Dtef_5yuT%P zlKQ^S=jPj0J}VQ=X|5IcoF@J54%o@7tgIIY1_r`?W?+f4vzZ|i&$Nbfbm_LJ3+*l) ze~m|#ITKo#Z6~=6CD3wz*C8#7iqj;N$xWEgegQV?m3+D;$NWgeWhidBWL>EW^!eta zn%E)#CUa{w`pn#6Rp-}9@$pZ7R(mKHTU?F%^hu!)+0Ad?q|0|#nx}`$ikjIa4Szu` zuIWyZ%cv_ZE5ksKkt)B%&%kgVnuTXipHjLqKJjhM7Gk`f{t{~%m{r))wW>xE^#uX} z+?;jUS+DiNr;e{u8}~#{VG_W)7ZGzNyi?4i9pR;!3c@&LXel?(XNlI`zc zLM%sc0`9k(Sj+i2WP}19{c+UW+7~w;g+KY~g-^n31F6FhYLFhbKe>Xnt#21PAV=5v z1bS!4C0+2N63Vm|Js78(qVjKUYO2oFYi4%acP8hyxYMT&xg;DT=<+Q~OX$_BS5McY z`WmXNmC7E^q+)q*^Y2e58TVzL#=|47s{m}f3Gt4bJRPg$x^?3CsS6^HANw({14^x) zAIM9n*Mu0_U(0e+@dd!fnyA~biP-RO*zJ1C+* z+}84|blLgNE_fKgfpljNzrYXct$j;Oh^mf(>dRd!->Q(Vyeh1m`+ zOQS3iroacwOG^Qc2i-nVqel5RX=ub$vY$McO_jeDVH~h^OEEokrI99vRz*d{u7{q! zYLS?_A4{oGY;kvHq@qkGN0~j0Dmps43C54u>({T7?A%m_-s5Ksa3SvfQj ztJe`HTH42eMgIzAcinyVbIzbWI%B|TC0WpA`+@mOO^(&MKB>?h!16seisHscOH6Mo z4VpO#*08a$1;Yq;3vQ^-qzu+G11WwRzuL^LtgPNQ1=F7!t!j(no8qbSCZvyF{{kZw z?hxx*p~*lTyJ4ruM%9-gDu4ht7#JkqczONV`+>?Y%0B`k&7wR-F6nz^jmfvfN0+r9 zsTG;^FlZSWrRG8*Pmqcc^e!qYirqVY~mTJ1@RkYf!5!9+JqGJvP^4SN^z0c&&!d7GaE1?J{LT;TaD!KFg*z49e zzL&Y^V3lQeuz;WC1@^n7gc!-WczIPl8F$K{=+EpIF<|9@r@6t#);0Od%g2Xca=JGo z;`Ji=VNl47M9$@;LJ9c&dc1&b7ZQW(%C?!2?U5Si@@DIPwlKt#Z#GQ!NzA_vI+ty0 za6o{2(TL+YC@|Iy-t@VV+Ev_TNOnMVh5pV+AljkZ($XT?62XPXVch%mHST40(k?}4 zfx?R;75GF%uc^iSrlZaGw%4A`rX(%Fl}|@Et2CsW(3gp4ks&R%)HcngoRWjq`&#;! z)>d58!NMN?B9*B^l_I{|Vt(XzVTNWg8{&p}QY_C>Dw_Yz`maGuL7ygO8H*nn7+Cyl zIgZ&3HpO8-(`jRYRyN+t!pGwracXKStx}ezC|pKIrHj+BlBbirogF72TYpkEeUcAB zJ_>~fnJSHD7cXQ=hfZdqjd_?(xF;#JsiTwfS|J5u39&Bi82GFWDB?hG?l zYMs=B2cM$_oYLzE=oMQgdn|f3=d!A7+OJa6(w?TIq~xrsgwCL-)N_(j6Z1$yB9G_P zQ9)qfL|r;62@fAgNYs41`;u9|g@pgv(&vr|{=mHMV#BVR?10dqIk2-Y0yBtz@!|`B zaHQc%UscxMvLO`@VEro=blnvm9+eRC<>lqm=g!r{KMZ0wW>TbvZiGw5&g|?8LjbZU z2#gJkjy8L0Cib)^HF&8mJvo^+CE`~%xASIpYT{`DBW}BS60_k_J&r`cr?i^o#fc8B zyhW|0!wy@3hrh*%o)ZxhoBMzU6gu6R@b;&#YMXfCts+1Y(;c70qN{EzXJ3KAhlbo> zZMLV_X(KardvzTKm5=atk2fm()rEC*;yy`y{#oPMQEZ6}dL11J#n%_mEJ{L!TBSBf zx2%COlcDAp#b+M}rKP{fJjRUYfflqS(O^1-cpWaYAxNL|!$y`9SpQeA{>V2SBmxZ9 zspq`SXHfchrs;QaCou*FXlZ#Fzm8F(lz@eWrL+ehkRpI2#o1E(dOr#nZ&)FN)0%Q% zk#!9W)O-zxOF4#yR;x6Wo9pbH*iHJsW%dD{j74@2Eh{INV>-xLw({rUjx|0x&V00Y zfp?6I=y+{sU&Xj?H+Ce9H>wz^mp@}Ewfi-jeKT-;Tz7S*>lFMhMR-N1?f15|wcUr% zUxubR7cC(}u)9%pfVA9KTq1^s$jWx7TpGh*aGSS^fpq%_wV0{u+H)v)uwn3aKfOte zOrgpuKxQ_i(=p`T%OyL)tw^dP3neb@y-)&3DPF0?QV&6WfB`%#;Wr-eEAsx_9<2NO)-(SRAt*adjKS!0TQ#E?`Ijd9c&pZM*3AJY@!$rb6ZC0an@=qpV;{-oGb+rl<`!815$_H7WTw{=)<_su7{< z{RrzO#>amQ+mH4nyp{-I`Wa>refQqI7tEa3um1tV<^AW!PRLK4LHaUmt>Rj-QEhGQ zPY9~gslbkpcaN9V2RO6?-g;tBc?1UW|H&hjz^EwS{kO*lSw%>? z${nobvotkGX!6Fg@kboz7$u|m2fp!$jXwwr3nSsSxN?D<`^U8G1Ddu%e~rC<%FCDE z0-RH?aO??i{#%&0Nm4PK3^axY{n^^t$_%nOj_QLJYgm6s6b-B=x+93E%T`<| zrcVl56UK*1h!Vnvpe{ot?><%`$b7ie1KQOXAmQr%j~}l9pN#`#Vk(x_`-RZKt{e$5 z8Cj~MNkQZUALEmQv!79y-Juo3tHI$JcPZ*n*lc^dfnzPm+?7GO3~E*Pntu4zt|N$I<+TUEW;?zNS;k^tmOMnCzO7zJ;AagF29^iOx~}maQ#p zGyM$*V8FcsqaJCX$~L#QVxN3@@!;XZyUx!1fKWUIoYt@K^Q-rW^B{vC5U3OEX}WW< zkTaqD4!J#{US6jqV+1vVoZ%ihhwr56;R1AkdCapX^w^2BAE7FTkF(7Uan9LI-QedZ z2jKh88%hs*s$vE*8&<;w15hruog>QBs`BgaSMDh>Xbty3rZzy$ihHU`SGs)E62uAl z_g1@PF}M&rn#DLSpD(k%NJSntoGQ~H=%3>ezScgB_*+H9TB!n1JJK+8MSH;EL$lMC0&&$uR4sJ0@f8v^zAP{%LdHSt?5)iynEij4& zP(%yMD*m1p$K2ffnS;Ys9v)JpV(jf~Sgy?~0Fp+Xx0%Zo1exeC-pfJA$ppSt`{lfHeyr>nC%8DtLzqBU!t}}%Y3;ucgXZmUGjsUU`1KNeRyH<5H#fJmf@ja3(ZWWAj{{E; zk?N2nhASf@Q|%1F-FrP`VA76>&9tb+U=so{7}%4vm@MFceO7AlglLsA)pNoZfnR8X zY)FKfAl5S~4X8ADe%_?Dkgtl{aW%Pnhs}0Yeuf3uVZyhy*T}6~LRq#=LqFS(x+HB| z!#t7Ol&+HZ9=3llas#Njrk%yAtUpei*h4!zwFgGd^lv4@Kw-pNmH%YbX)V6piHnOX z0q|@SjCaAIp(HnGXzC}IyE;4HL#KWSP@o`{N5H6?wzY6s1~g2>z z$&?G%))YG9FXR^z7M9YTEF(O-H=1u4G`t15{vNtTinCtx2LⅇwMU#(7q&G{CK~^ z!oRZpa7(VPLvR0O%kpf5d8MUI*x`IJKGu&y$RT*?>SS6`M>Fc0`O&H7KaH+Bhl{JQ zzBp~udh#sAg$E)rHSScy`N+nVYRrKI`{ zn^%Y^C>YCQ_d2K`g(n~o)W7SM>le+nEmr>B235tRM}5a<$4i^E+z( zeBZ5B=B$`k^;AD_{+^}Y${1C|L0c{_8pD%ZVNB?uTP!}c3P zMpyHe0ScXFJ=QjQ?M&iy9dA-aa)a_K8Z(p{%viXktE=x@~z1T?q^F^W_vT}*TSLYK0&(m ziWj`;>>KMJmZIJSU+R1>vjCYxz^K~2Q2r>K{mb*?r+{ju^YQifumAey(yz9e^zTLH zw|(G_zFqHwifH1R5y;U{PIK)y9yT+Eij4I?n3|gMjB(p1HSSISA}1w~;D}rRXcQ-5 zR=gj3&m&%w&3uHv$6+N8<_ZRlQhAaMScOl}8dK{iS#`abL3-jtC@uwG<1F}-^Q5eQ zKw!%*a~O4hjurM~24qCQpe)^`3f2D=bd9T=oJ62Ckd>F0vs1)GN&vP*c+W^d7c#)V zqM+{EGqkJq)ykqW%;>uF8nevQ3z#bF3A7V{5)e@63Fjs!Ux%?7=zvU} ztdRC$R-KSu@oTC=+7f`GPe45!Y*xh4A`|hfWn&KTsI(MLOF!7c#e8yXh&251Zky59D7Jm_doLHxT} z0^|Ezs9@rwrxDxv~dTxPZ_GBpI)PftmpX&-@*LTk&JiC(|1rm772Qw7!+(Fqb484IVV^Ba5pj5Uc=6;$R zU&%VeK77(Z6k8P%ES6Jk6xu^DaVz)_CrMFlZf~E(fTW!4XyOExiAyko26^M2Ir9bH z$Fx*i)0b7R=?7RP^5zmPtjwSSAdqVb%pGJa!xex&khkn8u{O}2hwZljm0{S}$`&E| zZA{$2#}ODBO6y~7Z(k4Km<1@jGHX9Fj7bxFtmnWO?n@&{=nL6 zw}ABL1@5AL_DWSLfi(g!id^o_)EEqK_S0Xr70+v#t6$#4IP14ZGZJoq5PXe~Pi<`z zQ}167`u!`*6X%G&LKU2^R6NCRvLxiTU(U=#OWUxZzTT9D`*&1W8qZPzGT#LKlG=w}`XdU&3C0TX z9MzGL5zxjf^PCoBtsz>o%wPNcxN=Lh6vP>HEmfL%&E>(KMjxa-N%*@PO3P zT51oTdc_0$psfkbUvILEn{CviI&HXvT!E>`Y5 z&RcHC(Y>5BZ}@|&c}q-R|E7+PPI?`LoX&VdU~2tMp8J|f?9Jt_Fg%AmCR6WFy#SbgPZ*NaQ|Ao zaX%lT2a)UfE<1LBACor2xXh!4M_vLK)!!|teVy7^p5O#XF7Lf5pn8Cg87n~nsruD8 ztKudhpFtbBuCDI1tS85o_5!ym6k$Z6gJNaKi!_}j=-So8!x|))@$t1c9`S-SA0;oh z3$7*)Ks#ktZ{*XJWoGrOpvhw(e@c7DXn~ZtREMCcO!Bxs`{{3Yp9#l|aE$kA^RVTU`u|Wx(C&0p6A#Ras|_3n-_u^qbJj z&w>3VQQyHD2)NT==c{6;3h|-ATCkw(1ZZm+rl_C{=WbtNL_Hm?6xiL}mG_mf@~M1m z_`zY1o6;?^PmIdt4=E`r?V)_bu7K!hCXPwK#|e~7hB?YhK%K;W*qcT}2br&7+b2BCS>>zu@*X zwOELDa0kbIQPH0OhO3Lg+wm}KNIwlvaP!XWNgsfL+92AO_O2A~GTTRffndQWAxUoT z2jQ(2L05!8PpU^CbOMj{y5Y~TotYYZDVSxb0v~C;TOD-cg|5vc#l%5sm-Y(lz6VhA>F&#uifB-Y z`~YH*$m1Kf4s7JmQw%N+mqGd4yi1}4O~D!Tc)O|QX1FsM;0A{4XwV?>-KT5oJ^6$! z%5A8^Nr{Ad(Bjc7iAz+cBz9Ydf1kSuhzM;^=&OrCu0#X1TwM%ljs|QlTQb!W_7ViH zhqX<-NLj2SoxE#flfT6KVwx|Py0P376b0sw7Y}!VmHr>{>P-2@h!b#@mNuk{q#8(J zj32A>r^?zfG6AXup&{hcO@>t)p$m2x^`^f8(P=guy)xd25bMll(5ivY$hjq^s~g{q ztHjDBXk-ZXhU!qbu*=eKmUY85^}-FXR&%|KVWk7k0O>h(-vzf~d%{X=Vi`1D%F@FTl{;k* z%{<64IW%K;Z;!=g+vfN3GpZ@lF$oHeBrdnw>|f1`ODwQ{nj6&tNSHl~sutsqjbPO~ zdzO&yy3Y>S9f9t6Kebq7HtbET`RuMy!4!}{KYY1Hq!p5UfN9Z|1cINvJ+1dQM!~(z z$^P-;U_-el>&}bAde-o-tjLYCndy|}O6Gmn!7({L{$TiziMcuYHFg)q^HhT5z@A*H z^YHYf=HVG|_g<+VvOIaP)$RrwY^Jf_HBs*;FqT#q!DqL6K*Sd{Ur-@F!3ESC=6fM?;-Ydb4ZR^MF^N#O1~-{vi#mG}yq(?^t{l9lgo18sGY6r@%8(o&JtK0 z#y#v(KtRA1ADHE17SawTSJu}*sEXbK(Pe{h&T7K51oIT+MzPUK7u-fb;It`;$slhf zQ}RKB2i){$-5Q9MYyIn1V5b1+n^6~^kf05e)=33jhA;*9B9j4~uKu__fp9f>&kSJD zDI*8HOwJt@pxc$3aSJ>sM6ak01vE!0{RY#(IoQOxs454JLr`PnNs6FVUB7wrd(`5? zg^`N48fA88Fwj|UuklE|9|Z`dR?IsJHskZDuUCISln49$0$v31C@`BrCt1Q`^XNm) z19#v<&Lg|QA0PAL#5wW$#Ds(tvO$w6DjXb~>QE5)s6pv0KQiD;X$W~aaj**we<$#PlY5%OA%%E?c;Nt;QrV2 zM@m!Rr+-jbgEy$V+@*h9{bc;!ko!1gCZ%pXf?lBR-RCR#4Y!bQdmiPl14Tm)n@{5t zRPu1q5~jT`K=-BB0bq#(bt1LC_a5M!S1cVJ9Vg{=_`@cZ2HNxMRdyJbS66ojcbJT% zyFQ&980rnRHH)w<>si{^2-%kGxhE|hz7H8{Et7j$WLHJ{8HJNXDv>^jl!LXk?snPt7a8RYiN$qDQPq}9b= zzlu16XYpWX5p-;1X7KX&C$21n{s;b2eE3j}g2@RGux0DX#kf#l!}tLWLlF&SOQyon z_9dOHRHDi*^qf)wTHnLE;`L9AJJ5nBl#I)4ewsDiO2l_(W0ANHKKXLxH8q&+Wa325 zXhZqkvB|n2WN?ZPtni1=1!$o#K;#%<>>6Yh333OK+?MxxidkDDU^==FS*qZh77U8_ zX|#F)PBDaHb;Nw3*>I|(UMzO1T}`9sD!@JH9&lG6p{Qw0G<+b_L8B3AG>t_eRUV%+ zL>b*%V%qyl@e?%k>WK9M*`&u5+AR=)xXE8xT=%yOptYXHj^LkXEBJx@5G3}({N8u&u*j3s_#t2 zg`O>aOtn1Np1ZB>qnO6}Jx(%=wK^0yRj3ooh%^EwkTe$i#gSU5V)DN9sty~=!Jdpn z=e`%3rWxY0a&>**xpMNb){p@-{ARl=);RQMbU?t9J2(8UcInRj{P`T`_{paq@({-P z+__72zXpq>)`Zz~8=NU&dbsrb`Sb9pn^r_|)+y=f3?u5%?L31>4wSWQ@Pv7uFl?PZ zl@MqLtZV{Wk1~FRmMz+?A)PxK1OXs1kon_*l#~*O;9e9pu!@$N$NBfixu9`x!mQz8 zX=rE|%58ZKq)R&63qZ)Ap^Yi_%q|xOI4F}WEoo=?UAOid1v%w7T~5@z6Tswj>l=R| z%kp!9M`8a8n7ZSlGLd6b(1e*y%3zo`R%TKo)j)$VX;J$S^|UuV45w#T?!f~u=9?@m zGPAe#){)`91DMoPR8&;L)^MS6v-(&VH`B>p5u@gJ>O{S1gb*Mf9GG<{0GnWx26)vt^l#j z3{$y$itGtC{g%%#wM+rOr|JTb z>x@l#Fmcrd?%ALJ3oQm}{zIy~_k=;5_je&Lx0$&}Ac|iH?z?7pqy2~LbvXclH0FLU z?u(Z%aob^lh*u;IEK#|wbno6V(4v@poWT7NU*9bZMlDEWsBjI9jV#Gz=tlN0P3&Eh zvIHlf2DV~1_V@RtoKL?=1uqp>24uC|wVELpi)QwLuuVRBxZ2E8ow)7EKVzM}dd z3ABL8>C_FL2cMD-*jnJhFW)}Wu?*K1uw^T3QFh za7rQgc0N zG(F`Z#7D3t?s7uGb?YEKMa2&|!6fu-Y?olk3F`=N$^HRUb02?IQWA~kv!5rlhoEgN z!7e=gptMdhKdq0$8Utj|D$J`uqsxf1xcU3kznTpLF|362yb65o4H3viJP1&3I*dL&KkfCS8MrgR%54 zngdKxlV^|UhIrz?;vXM>0-0U>nC>=Alj$j%qsaSE^btybt+|TvD;pb44y^E_yzD&d zp38cBySvfF*A_n^z6awzrj%t7`ZZOxnZECf`RRAxOT7MVYEoky;ZCoDgjaFtzmo}# z1ks2~yP0jKrBjNb^ca1RTQ|=Jr8RuwdhShLUNR7nM1jH2(QhS7a{S@`A7<%x+h=(wl-r;bY0vZ>ZU=8-&o^IA95O_p-iuDB#KvAp)cFRzy4SX!=YDE_S zN{c`s$iPsF_Tm%UN2_iVP9>l0 z2a-Wz*ym~)MPU#26HMF#R zg$m6K+yi11Lm~};6mrr7VKKrd8qE?o|KrrDIq6{A zT-@ed-)cv0o9O`NM3~qCyiyI+X$}OxIMhhIx^@1VSMX&hS5+T9lDOYT>-6a*_2nme zR&&GCp-6rc-qswt>Tvwnu~#hKaaV5K5H%`?0nkap3bD|^`f{$W)4)N#1^Kiu@9c{GHPmEf-!a$8Onq`6;lqrFKWU;L_Rpdcru*J+z%o>+|1+tr!2W}TTSd{ z&;fu>nVy~TnVB~*tHy!U$g3F41#LQoTTF0OCK0C?SeD;ww;^p81C$Q(N~t~hVVGKt{>`>#Q=1q?RD_BB z*w-^D#gM5An3Y{jEc7G_FhAS@{l=y>4_3*Cgyk44K^;h%0fB+B#)1Yvefs=0@S&V( znV6)n)@VafL_C{drdOFtUAbA>8`eB<*&Pc5aPDI4yx`TtC6Rr5!29@!K^5uLRTQwW z!KO(DomCRG;TKS}3%pu3`)0n?o0V%L5aR$t7We~zF-AwT9GWueA-RJMe4cuYfYx~0 zc;;K|aX_p3*0^egCis&9D$B}Wk5)xAF|1c7=Lw9RrG2uAlB72C{T;JYG$=%h0uCk`G#>)S5EwWlYLWAuJ^lO#n?gW>)&S9Z9VzyMR*H8X{a3>dV>^Aa&CiddR zi}R@scDHWblC}Js%KTSR^NMdAqJ1A0c1Bd@NsjXQv%UV%_ViFR~22+7F2WPv`ew$9tM`)(g zBNcoXs04jLQ2znvp=%)iY#Qz1>_EP8-vywu>w){RZPdPh1Y;0;FI=;N3m4exVZ&+) zO$S%$B|k$HN=5PBXwiV_&XcpQ`JD@%i?g#$=BxjM(ige@sL+yAKwwz=Q6VdRQ7%sZ zGAk=9`8y>$!ixhu*SeAk{`~XGFu&+_prLm`?~jPcNFP`{C~JUzsF|6iLyz01Siyg(rMMhTw!;qU2rh|H7%@PJ zhy4*5`F(vA_P)c&g$BwSF=(%QJPg?LbA%2YMemRcPLMO`Zb~i+(RBd^h1BqXDHfieg+|Dmtgb_$%Z zflN!ULlP3mL6@;bIKCce(8YA6X!|w_v8jQ3oU;dR;zqejK0uT3^uoh={pJ)ROYE)> zn)@-;=!3Tm21XAJG@M=L-CA2v_woTZ^#h6Jpl*JFSJDqyoHLUQB)@_meD!U z^v^o_wLL0?ju+saCLQ}?DH3bRe-I!ClWh6k`rz-Q9aL2QFhe=7^(c`rKS9wcrYAr2 zgOligg6Zz%O>|h)VfsqR%3g%g(Hl@qKYtyZt0gZiwYqc1y}Qb~!TD70OL`8JR+-%+ z5=5WaFFUe6&%FKzPG8SJxK~RU>N`u`(Ud`{k&m3W3veap5Yt^D0)>56U-ZsG%09w7 zUl-ZVRc3fPSeU`gloe4X%H`6`i8?;k<7Jw0SKmbCkhr$G0PKAG2A5uQ=99<}I2l1uV_twaC#-IBtiBU|EehSjP@qXSOjxPJiegXVHfUBwkZo{45-# ziq}!ge;VuP9PQRWnUWM;jo@WOYzDm_k&!^v^a7pi6OaO&{(N9d2dF4oBi`DWjtvK5 z8q(QWus!?@8FQ->?O5_)1Ir=%gW{l@j{SKu%MOqq=`Q`Nc=aGvVXHa7tg zQ6jQFPZ2{Rr~!Y1j&z?$Ae0&FQ@w#)K?F1q2#1Alp!9RGo5_z#0jo8VAdep_&V zND-WkT_S8 zk}WRyV{&-SAY%2o+QNQwm5s}fqj)`l?Bp#y|ENFjtOeAgACoutr<$QL3`D+62g#in zA(%;}8xKmr@1BVPzpVm^9Gpl;?4o_VRtX6SKcNl29%ntbfVK|giD_F`v8e60@m5{$*Q)cl#Mj7yCJZp%usdc?W#Z_7X1P=cfnMt_zW;b~)DRAw0+07Sz!3FefcU5%6#gqn zQ!Ww^T=y9$Fb=^9-t7Xe*nmr-<&VZbOgolFA;Klh=%W<7(he=Wm<7eHVBj7gc5e?N( zj)9c{w(~3oR;{QTQ}766y!@>_&`I&@;**llurHibAIlrlHA8>%ws@j& zCMFsKM?tGe3P$mMeJRNhSU_VfdryV@8px|(iqwq&fTRt+BiS5KuIkU-E`MUp6zxVb zh4B~qpc?kUEp7dGM%O#Q!z`433%&Euyx+p9qW#6HQ|C#p6qr{5ofgS!+cZgL+L0_n z{j;eHy5L^fn-98em=%edc@TqNvA_{DV9q%|lKr3Jav&X$6~W#+;2^Qh9A5-}mAZgc z0%ib+Jl+00-j9rkcU9Y`RwvMi-%%cPyZAA6L)-d#I6ZX^4YT_BWD&_pwkJS$92gV% z`})?xn7HBt2T>Bbjo$d5yKvz?7&qdL-~jH$wiqFE+j3yi#534G9a1Y1rG9zT!>&&OoK|$zE9_E3Y&|qsk@j^8B?7{cK8FguLY|GOU z&Ks~i`HcEaeVtFPD+oh|T1=$t)&y}m9Q>5cfdHvq`dM?ZegMb35MnzGLcTf_&SgTflS=!}u_7(2ehV?+3BNuc=vdqdRQocZSD|Hlz}mu4ojnk_ zfe7q;(i%wuaIWDRQm43Y+&E!rX{m??SBD2!Q%DgEFv1t+a_0yl;r&Ai2GRkeC7XtV zL%-j%gM9(%~YglD-#MxppUAUEc`S>(({BeOfs&NyKq=P|cI$aJgAWATalfz87)8 z*zponA{@dui1<9K&76y8;P4KB9!!UU<9>j++acgjYDpC#1#gNEqn6JOz(k0kSa5o^WvlC!f%WbQ95L=( zh9~gc1A_clTQe39)3A^Qs^Xmbo1+?BGCx#u35;HMVGLtlPYBVx*d{tq!VAYWQ@As@ z)s8QL8!(pEyC)QwWm0+Hy}xlloBKbAJU+ao$sEND)_WL#p28z^WG!L$I!Z3ef;@c+ z27a#VeegUN@EKTJj|KTq3aIuo97lm{o3JW=Z|hANwsthb@-Us^qGg~`9wa?o(Z+<%@o8Y-a zr&FrFfUSUTbRU;@E+-G{ugR(fsmx~3g-iQ%goVQu=q7x##On$ZLF;h-b&=ai}n!gGOo)gJPgi*#S@R}gX3l> zk!~BhIhfwy&W&{m35lR>wcvqMMDP{(c%EN)bKo zc&a57K2UGCMP;z^F1T0>s;joBL1iRroZEIdQj|;+E5m^w3 zp#UbyWTlYlybg2*DCR{7L`s6^9Hb~_s8*_W9C=k&X#Q1Rj6g_#24=AY9pq$38m`Sc za>Uh!0(o8lNQAa2FHJ(gwE*6aSx(o-k1rs|2+mIXfCDmKqXgFQrfpt72*b=U8kSk{ zM1a}mH2OEx7I_RRI^ye3V*wXyD5q&SoYD+_C7OMHy5TP`K)UZ$x#LSq`l13yvk7-@ zYYu#Lcge-IQu{@w9)e|H)%u-lw!kwOZMONg0w?c)74d~8`9OoKfdfq127?7@$K&@>vY5r85;WuyC;v4skNoQZCg`u_j1 z_ttM!ZQc9uLXM~?U?3`KfdV3ebSp}iARw(G(%rdHL=+_iq`Rb%ZZ-y>q%_hYxe4iJ zf5+mS^BjFX=epiM;C_0DP|sXtu0-v`H7x zC*&HlB-a!}C`IWArVmPexWE;JJ9LS?x0 zwJaI0;$O3OcAI&%?L`e6cNp!<1$w?J@gih)Ipae5`Z*p(&|dVZ=gbhA9=z?iN3M{PZ+3OzCdcAL1k$67+jrMT2#Zs!;o(& zMd_oR)yvC4-hpbK_YSk8WbX|1%b-JXZ5+aG(jAQu`Zf-hrGdWyp6|cZOCJS7oG}Wd z0Do^EZ||ExC*d^S2NFm%Am*5;D(L`(k2}D!lC=sHf)1SLAa!8G_ZS)u20)rCwHvd8 z(?O|@{k(uXiK2ykCK$95)ck><&TLb94a7B|V|MFqmgbqga&A%{1eu4;T~I5mJ==P4 zm8+2mfR0RtOG;icfy&xY6i8Gt$`9GA{zWXK@fU!RRR9S-KupRh z+)Td(w=@jhTQ?vHzXp7_4(6j=W__ojo2A9n_TKeK%nS&|pll#mBWQz;XtNH8a-J(_ zE(uR4Y`B(9S3Byr02SMB04|{Hq0<_1H}{+Ltu!5%0ddT|;O$IBq0=FFj&IN+x9ww=r_6(2-DbDDx zz!ww);M>y@WTEW3rG)*ATjKYZS5%m~RZyhk_mP=U3lIb4 z9xYwotsJHC=XOY_Fs71WFad3Mg{TL56#C|J+KGvY1JvJaKt72IQ^Bcp?VEsA5eERj z$q~+jYdMafz9}vI9tuSJ0B#a4mj&>hKF;NQaYHd)teYUTQN4x=;xLH& zi9yk6+7kMHUO@V7y!i8ddFa%(F5Esq*HozAh8h{#I!~#*B@eUlw1C4kFn)}$Ne&(q zfq=j!z4~YmieHtit9jytzd}klp8wHGx**admI&$bjJvb_~v#f+-9a);} zkP~^59h8xiqu|Onii4X`B;$7(d#h>z8YTU>oDLM(z=QyG8}-{aPX0AR!hW40;~*A= zS|>9ztB^40-+T(L04VpTz2j4w&~*rKU%Jr|v{fJYUThsDUmO6ms{ydp2l_;M1jN9- zLMr14lo3GRBrC=}$b`Nv6Agg9Pg5tEhZ68X5|Z2Sj2smuYyd9;jB=XWj2b-dGgPAl zh>c>vm3Yic+mWX)zlSY-D>T)B?lWRYiCZ%%&Op?03+5?InhNHF!gbM)AF|+%{uLX! zp}fmI+9z7EEi%_3WXkn{8si?rA`+y$%+@h|P^m_hho;t9Gzw#3`orZT8GJ56E`x$5 z5X*Ui{Lg(bctC~^QixkG4Nm;83PwXF^9niE)QSAyBHb7GI62p#(!x`EIy zG!CVbYpDmWB300pj{+cNv=@&7KL!Rx_iF$>m*0&-X=sYKu>l>R1#whz1sXj$yeU|` z;SnBylRzovhJ7%PFPuMrvuk`%^D#f32b!ND((r@ADN1%;hZa%G*&a^W8Wr;WV5V-s zYD~)J^f`0=d7~!Zwcc_fhix_~5PX4d*S%Jx3@la{G9fh0E?Wu)WdR^$9;-otQ)qQ4 z;E#C?Xb!P1fQRp#X;A7f3L3#US{k&c97F3kDBX3fv^_vAt~-pb2Ua6`WL3u-tgyEK z`9HUU=0Dfe#Dh>K6iXN&c+NKj+z^7`k1(4uYBb9o?l{?M2>$S*v~CP#BZL~!ot1D% zjP@28%pwJFCjz7Bl7@g4je!8*e3nKHtv`IgTzNOmd49tX%j4bPybKdoU2Eq(REj_e zln9z360MlLpMvKd23H8cSBuR0!tU+1H1U9Jz&7yhU|s(b6wW zWr@tm<;wtgpfLkjuwBedzoSj?Sd{RtJcY!;vh$aTFW;m3gSpvD)F?VTh4HPd7X47&}+@XY47DH8Xg=;H!N?V>`rqa_p3ub^?r z7W-uIdK1qD5QA-tbrNEpa-IMHVif*L*3kv1@*}7|a<=QNv1J|OyIVJId~mB(R#B;e z>}wP#QGU=oUIP;l7ikS5!V93_Nqud70p4{DfFX)mwir$t>jpLwV(OKtwo6$Rt39VV zjqXBZi)~tqOG{&dMBptd3=4%JdKfC;)L=I|vLCi4N}j(SVDrq z?U<=))Ht70As7$1^z$QUj?=j=-;o-9_39NW!Tn<1WrE-G%Q>$^nwp22qU$DRpRdHz+-AWFMs>?ZSYPB172Ft za^3=M&}pwbkL47JE<(866KjnM?_OqM@c}M;;xg|V-R>~mL%26t#ymN=8idjFU}AOI@X=m-s9Xkq50DPVo=8@7gW^U_&~i}v|&dr-YbIXa00maxKo zfn3A-oRo$VOj-*>YL~BG^{uO`L&ZfQNoGg&Y-=DCqHU={>JI7@C-B~F9 zUxnhg!^q1^;T-bK(Six^0s)EiLq`|%ak$_;J_Hmr2Ut01Y>!H^LjLJ1))>>||3fcC zivkO}b#3gbTCK;5d-Q>|Uk;Z|-B;Do(a{1DJwbeJK%)FaGVKz<4DqoyWYu&QeSp`Tn25BN zOXzY0dYUdEu&9=@STl63PM~kKcKEyNAm-%BlPIyX8r;taxHTEWESp(z$pQZK^z>0w zgBk2Q_j(@~x|%!UG$)~O?+2cp#|~yK+|es&6lMnKI#6+PBmUJ@Z**0{0?a)ggfjQ3 zb_Bb?ob#-9>m~r%35sbUDOp**kiucMozm0N6vHQA#rh6zk8`UzHy+EpgiyCQ4eB~? zX#@4}#^-_e-&A2)^1w4ZgwlFTwhk7Qn3R5ujk#{`0*;8=Q+S2=RZiVjWfddBMEzf~SMs(nc#`J{WUBarEw=pqvUNm<1mS?^%jdm$&YEr{Md&6;= zmDP`X(B(Qvo?!>Qil`+ZJ0Bs#tc#)w_9Q}Ud4IU$Iu)~Vo81`p32>)=&d^QjJ_=Ff z2x^T`J7t(X+{8aGGxb1PKgw1`02Jp9b?|vtOMV0pKA#BzNn9Xux`^Q*w-9w1KCF|% z{krciwDjHAwEM1iCd?Up*nvJW@Y-~c!eGQYL4(`9nW@1R1b-2P0|N~dY>taRx`8ph zy;_7d{kcKs^7BSR6hF7=3N%6qM8k~C_rgfV05Apx3oBH)wh*)`Cs4^M>T4JKPQyf6 z0L6sISGK8g*2Y_a#!!vjuE&0c4&5cO<~*R=p|?iKTptOAHbL}!eEhx_8!NNeQf)9B z`B2YDF7So0q!!c-se#&O{LK;MDUCWmVUJ}l_4pc8WJfFm?^#7^co2|<8qhuu@$?P{ z_`;IWRtYooxhQJqF0NoRA!yUNsY5)_$IS#BW(H5DZ zI~iPoM#|lJ{4VR5HM$(Z5JDI1YldtLYUaT1lXknl=>w*uXrE1+>_Y#%8}~b`>f*+z zc}IKuXOP(Ljg^~At*ftprL(&jVt5Fzi0yRH>cy~+0#izsal34Oi~q#%;ENaLn5|w* zw2$?t6IAW(wn3%Yyj6eXF8WFj96{tGxL8IBhM;OxvsSrQQ9Kr`!Cr`_*6dtsfGoOI zv4s)Sfwpzk?vII5^fe>u&%qmg*7Xw%Ub;$fO4H&78a1}S;*0G3@C1Y%&Z5)&@|A`; zYhqY^ROsddk?^9<=%mBYF~~)p7T%eXZ|ix9py(t^};P>q(why9J?`e9&8Z)vb1vL%pn3$azeao6N`j1@u z1LgP_A2&sY1$OoIIQVH4;dch{K9Eof<8Z*C5`bF{U9mL`g;=&4RqqEY;RAuu)=P(! z$Y#2*F39&n0V_PKN>NaQ>)8#|2Fk(<@P)idIrjaws$zI-JcRv>U5h*O7-7)bW>=B^ zJTRyR&_Lb*Tk127w&5Bo^Vi2Nh&_5V2N^fGq{c6O$BqGvn!V-#4Qr$AO7e}}n=tY} z)xK`WJVM_=c#<$$#Eg9J)s0WJwRQ*K+m zgEc_Z%*`DT!f$5dDWNv`8p^i%w*7>_0~GBc6bI+v`!(W%4C*Ws2$chW%Jwi2cDSNf1g#o^0S5Nt+*c>4irRb^${D!E&!sQCk- za~7~Y(T`6A2>B<@N8#7~@TbWHmlaf=DxA`?xr1)<&;l>yb#{R;Br~sIZwdBv=NWYA zpc`udE)LP0~f*AI9h^=DJtqQ3Zxug z4YLw@Qr;i_njtH^LYPNl+1eE&z;pI9hviywHA&e>wyR+0k}DLXDe=+2kp(ZMMdF$zO zN&yFp8d}8_*uw$c`v6C?lxgnDe8Cvji-=bEy!ivvFiK>=Rt#5By>W=|8|$1dMOxeh z?RaKOXe)cy{>1mu26TGUVz>I|+DH#YmZKGdhMm&$1YFZDE#NxgNpM^0Hz z#(9k=K7Ucc{WQvPJZ#~cC|NZ`V%LvXRzlW`D$u60aS4c^rJ%)p!v&`?D7C$2D7~?53A^Ilh9s5!u9gw;;lpS&?gPODZYWfjWvo=r zbLZU@B>5*%kF7Kv&+oRqUJR79JcW*dwN=zM8qUaa_miWsu^4V+0<$|o=$2dx!T)vj zPeQ2w0T`*;&uuy3G82t;rVZNw z@b>s+c|1Afye~mJYXaRcC?lh6o@j!9uJ{62wNpUE@P&#A2e40LayS8Zr9*e;LA9GL zVMBt?PmvZ=uj$O$ZbULRw{oI$rOpxYig zU>G9|Y0w${$YT)G0?fUh?@6(^xcCsd*r9;7xISl(jR@v#i-UKJngAel$n}_CWxaCc zHEOd#{|?fS!389NdI20EtlYmej7>ZmE{3mX1{xVef{XL z7hRTp16;RdGJE{t`05{5)loLjbh|kQ53Bc41s%5xiTv{lc zSx{-FSOg&xn#)M(vQ{j&9#IW+1CpRG>T%KKOy~=Jpb}e~=!QZ-cM}|d-Gk8NX%x(_ z4-gghniD0A zpMeRB$_t@c=aIYNv`}Jpx&jTf(cqp!c`P5I(XP)fKYrvC_B13rKE_!ke-Qt%T_zb4Q2)+T{3IK#ZFf_2saI7BjkmM&bsnKsr?|TjlL7EZ!O7^Xsz8 zi-s_+Eifa&Tx_n(qo9DlDCtW8GsU6Q3a^p21$6MxJQJdkNx&Ae>gCFUe{SdwZdrdK z;fCIh+o&@D^lcj*_$$!=1NmZPu&wv2SGo}F?(OCPV`&4}7|T+C+g~&H0qReHDK3?2 zJqKE-X8?Tqx+z+K&Is5jN_uKI7~Qu8WIcr-X9~`7%7R=30;mJi+cM?wcJ{^_Leu7Z zBr)K@v)32=Fw_7w>BF91mjRqQ1sX3K>(+DdaWuhCNNP%dL1rfl1M?Kk6Z!l=9jn&1 zODp6}0hq#AA;$vQofva;avQk!^z;C!xVo0x0f-q~pk0~?_`CF7fJFfROMnhwDJiLV zaHi-E8e(X8Q#|VX3X9*u`a!r^`Q5fU!4kaz;7jd=1yDqaSabx4`8AsQ@40EVTI#?L z#BKACy*yR6YxknsBQQ`JBwcC1ubi3EiD@0IQT)Ya5Z{o5Z^3-5|S90Ius0m z*O~xd+{@@;QlJ?%G;h+ri?UNEr{KcsE1UNgvP47Xw%!)AOOD1OfN!8a9=!vI8Bc(V zLPIC0k4S^SI;$`5cqja6378e?}-_nxWvXEiHaA1WOIW z(){rDSMEn&{2gWsx~2t$K;kD9HZ!7N-Updv#h)J4{c|tmcu>DM4@MSktGuJFO$%Yg zdU0>_11}m1bg*Hn2%-CjX@-DF6}gU%IqG21HXA6xJ%q#yu=`{C_wR3k`HDuQz}w{Z z6SCPo0`5eT1kZTVzwqpfyqp3rKA~6f*xBP}9!6dnXsw_O}G|q?3Of^)oQs zk5kXX>|TF{{IUss{!#r%OR;TOIvGprP*|abDs>$^--?g9%LN#C^@#=8)#u%SZykKq zUvgg+{P^qmb`v_OSmpR<^ZERWfV=_l#0e-R*F9AJng`R2XFOCl9yXn6Vgr2M2&CgK zzEXyTR&{C7TI=sqz)yc#G`Wq0$zn@82p#_rFA0Bz8(1Et!xs^*TU#P4Ug`)!mcnCmj>c7J;9T^|NTXjlincU<(qefaU$Vep{|x>*VGp5Rsg}i52IYJ5OVJJw+ih{n09KrWN@9bRGJH>go8bQ6-v_JvVZdS3 zhi9&Mbb7`OMSW^A)besQmF;{^vz^z5E!%cznE^gTmj?i3Z^zQ$tFdOkPDu1z{%1Ez zuKshUHlNflSp0P;9q390a;AA(ozq zMJ?*zN5CYS!h>VM%;B_3ZP2|j#^DcgS+ZeQP_C}qh={QQAfaH2O0J?it^IYlKZb(D zWgv8f;ny@{6 zJgk1+louDFH$WV=-g244p^+anno{5WLqz%!mf$Sa3^($~V~5DyW{H&F{q(G(1G|LhK1)(4_P<5AYnj&vI**_DnDY+2MhrO@&bamX4eXcv(Rl5 z|36O-h}(TQIRu;hdnfS< zFAv`x^OmZxwymD)bFO_+EkB*gZexy}De*{mbkvA+MOjVgIq_S)Hw9ZE5asedQt^Kauu<2KBzwRC;`Ziw47X}^K!^9HT?FPs=BA`QiKf{Ty^oGY%K1%@UN2fk(2E{Vn2< zcs3p0!_b`bP7HqSJ}&=X|H$zJqbqMq$$;M2f8BgsAr}pe`+mTk4R-%)oF&BV?Cou3 z+b;dv*ZAOD>9+8Yu^az=Mg|fV_qD_XA4qF|g#On<7#bkd&PGPzLWln4A3F>skonY3 z$mRa;BZPDO;cl;rgFI7YNi`G)3D@68tWY*Kk5hYnDf!;+Tw!;y>%<^6t}jdW$mDm% z%D%Os(|39VA^fqrOOH$`MEH_caiR&#f>{!Ys1Z>+1c1yua7JJ3gJlt ze-h4Ap_MpV=d}Mj%x5j#c-I=mV)$3y+K(h?br@zqfG8=t%Wc;+`7c8>)F#xUOk-ZI zGcdW7Zft~3#*xGXQlpR_6-u6_qTSKQ)-`p}2+r#8(~riNE&7Y%f=- z5HhWzl|Tq@^VY#%hwPg1u6oN4q??MWh?@u54q2-ob#4o;!Ofdw+H2l$({{lvS1!!H z(Rne#wO^L;gnM&}r0C%xn`bWwkh5LCgAOh|S<~SR&36jkJ+LlcuSs6V&qdf*{WSkP zaR2)=UgMGNL#(w;{T)6m$J}@JW+mn7F<3;Lzb>NVNem=Y+5H`<%{h9tS?jy`NhGAS z*)HbJeH#riRO*z-N{X!Lfg!=Ym%s0~C%N2Vc+hOtP$blTgs$_mPJKFMK~rMLfOiqM zD%Z3oBE(AL>`q#RAo+iI{+i6X2ggAkF)*lol9|io)hxd~W_u-z-c(nlxye$ZHa=(^ zUin(>^JiF!%9RI!o$AZ0UM*Wg0St`vuPC47W?rowwExJj4cV5$QYBzL*8hvLjpH>+%S2p>3A1)sf=P)EiR?}oZiJooE z@dNB3YwWMG`kzZAya?~+q^Bul_yDZl3lJb;^qgmonHT z@f2P?sq7qXBZS0ANS|5{Pu?jbMG(oezo0uJ34&!0b+;eRMKJnhXZjT5)-b-eaY7l^ zGP0B(b(|HC9D7G^qRC=Fdg4#`(e*U>(f-&gxy6e^Me+MKZ~NAtXoX4Y^O<|JkyyMXgGIYvVVXM%DvUlk?C9Mv@?1|Ag zwRJWf6H8MGX$;@px_U)Ku1MBjL{96b-Hoz?fk4Rlf4$4S`Sax!j%et}utxn@aX`=) z%hy3qO4tR-5O?d~IHLO}ChXyls^ov2!+YQIKUFlG=D;pW`2NXH)$^aa#ZC2N&$0h` zF(yQYpCA6pTdRE@ki_4PSe_D7q=~%JmVd62&FZjQn86E~R^$jdOMULjj}ao4wBA%@ zpV^-N@6O$$1#j6JsreM^REwii%kwKhR1DZACHUxFj3*huZw)|B4=66G$^m{ zcV{7t>vQn^z9-)#->&rUU8yQ48g3^OE<}%PKw%d0SkrS3ru>x%D1V!)dBm|7A|B zkyK5s70Eoa3M}z?V@M)*k>oW&tOeKH9Q!q~cTe7)rBOKgj%+?V=S28H%ot^zEakz4q$|A!y7Y*7n8B>?iOVamr<|EG`di|-xn`!U%YyXi zwskFaf!&7uA@c9jzIlZmi8QWizD4-6a>JxL{@ev!f}a#5RUgKyNlpfL6it_pic_yF zc^XG7!%E0BF;Q~0Ui%Q^CEA*EfyijQ`@`mTq+~eT9Ciqq zHy$JL%=NOeHYJ{uZp|fE>i%*MDL={Gf|%StlBhpIX^~i(?E7iAERQ?YT&O|{tJ4!| z=Ug8=9nPoR)t;&!Y}yvm6cNv=;}H4rf!Q)#&i&)C4!SaaJy0X?-QhV=V^G{`t!8Hk zNBc;aL@N<7`QZ~JRSY#EPP9KT9T7a+JEcou9cN&HNU0aj>8w|}ZPYwoI*dl{x&QY1 zO$}up!3#`QceFmZ#&D#-f#J$WcafZHEd$2WeNPh9o}2BnOc6CdxUkq0grWcfUWXO%WcYgUzOSKM6{nS@jEf5z25LBK#Tsa#ed@)j*Em zAq2m(vnlG^h!vlfyyx`5HZYZbZ;=0OexZZ>EzAhh(0rSzWpKv?mKAPbi2UE~$k{B}Ju63LfVzgQqtBR0;z*S!^Ws(zWh1 zmEl~gIYhV*&f}c@@+e!YwBu1kZU)ob?`xXINegHCvj5+n>nPKkRD$mNmD5xh%}lIm zchrKVQe(xlkM1Kk2rb^9DP{fifHV@PboGGzH*^NO@B6ngCRNmfDe$~a2hWAMT~ig4 zN;Gsa?pmxtsKE>aGDB1EK{P}-;Z!7Qorf+ta>ajJa!HyDsR6;@Sx%CA`L36Izptfh zT-0e|-ZitpDW3g7A(UAug3WzM^0WcsYuzxxqW8V0I9;iX&xvd|BUd18R9wYa-u2xz=?}~IQbcd=)#5#n+1uiKO zskCBE%yFFkkbFqiIO+}caOf&lpF=iPAp$exJI7Wyl-3_1Gj*k`a+m4P(x1VgLjx01W zRMsuKv_$8Cy%NHmHT0P5?@PGnoAh=<8~X}W^^HL_1ls`hN!kzoIbsSLlq#%L16)&|? zn^d>eyqGB<<$}_ES*}@cYioRPFhxgKmofAYc?qg0DJ1}9Q3JSvZ-jOi{ET6L3hk>P zX#UUPPA222Pd{~lHLGo-?YVJJ%8lqh+yl>0I>`!p;oK_jvAT_Ug!AS0d~ra^b>j)T zKcC*IUW?X9UyV-8Hs<-(hg%IYUo1uE*E0Rg+CBvN@Dqq*hR~G7Hx{I{4CRTHGrP0W z#>VNdi z*@mu4Uf|6fK1m><4Be3zm4dZ1tzjRU6Qmq#>V;)E>AGCKGHTRXenBnU_}xTOOWX`iJZr{zYZ70p{)@ln|A``?a; zTnpn7<888D8dxQ@UEb{7W!~A*G#?>4@$yeoMJ~3tpthHw){UD^&xX+s9F+d;T`N4h z@`+$bwyf-;V>=Rg?!8_v!My+#j(o$GQmxG|%WuSL_uuyg`+9=qK)z55bcnbJ-+?%91VA_`t_P4o$#j81t={A>EKB=Sz#f3lNSWp zw9={Mh(~(G>Gc13K=i|MwGE+#{KLVuu=0b5KJjL_8)-m(c_lzSNAH6z&953yb~Nvs zr>73eHwjzsnE|ewGH1csW0&pb^tF>q)ZA9Fa~l(Z9L_F2Taxf}-&i3ya(A257~Bko z%BXK-QFcnoHz2OX0ee6j^yco`+7>*_302q7=z#eM99=`u#ZU*Om63&^ZBc-AemTs; zNT*jXDh51Cj9ZX+$w4rbHITSl>Q=N+0ychtp1CAl?-bUV;Xmaq?Xsv4l-1-KVB!l}bUAVI>eR zw)!s7`WZtzxD!-!mtki)V`!se2nG}T&vDk>q?cO*p+yhXi;^u8_iBBpQ^IbrkTN64pL+!865*8I`6$WiH3ae!{K)DOao{#P zdu!$rY}S5Kp61ABv76_V-$wYI`XiNq=Yg7(qlL#y6UE@nY@r;@=6;u~OWCL^l%m4k z*e4>q2pqI&XaJhFE|Yf|IZ+DS5l#^Q5Ff35$QEVSW5@>$R?Cg%Zb~38*V62^dR-9u zKsK)a7J!I|IQqA|&1VgrkcGCh2NiP;QrtUssg&xaKF!uun^92*@N3S!y(_hPy~}N? z+|#`wP2c*$5(FboiP+UoYjm^(+6c-C6wE*04~DENjadJ-wS;;0d`H*rYJi)eb6`$*VS#RRppLYbG zo?ZwWE0Zu=zNm;=EH4hE+1apyYj%!ZNLJI3rsf$xKI!NLh$d|z&18o00!RlM@`q|uc3Rw+>|)=}R&52CeB z17taeyYS2Ekjt3opgFPe_vpS+LcfZf+hkXJ{JS&<*GG+ZCY}~}U#cj%bF1=r@T`V` zb7P^M&NvuW5z7k@IP6qqV|I*LfUP$=I&5(dyEAKU`(ghnatoB}@Xz5LW=}8_bcL)& zZpJ)!W=7U%r%7&fls_jgK^3E2@u`aw*=aPD&-9vE&XEh+J~e^8J}dMuVXcXZUy_OF55>Ukyqln?AFq{XOr~>jQIQ zbP7bVu4My(IkIYnmx8+7B>J2T@#>_(?SF0u zK1q4%lT^J7Ql#bJpfx~NnTlub3aFJncwfNZvqIOL)iT1uGA)^ii55+Nxak#^V1w&3 zq!ftFsA9f_$t$})H?^*{5cF3x7u^(?Em*NJuQ6E8Jz>f{H%+`;!ty5fM;E>OUaY%# z0}ykmZlLv3%|a{T=qM0LbI}&2eOYLS-hU2})Sp=dJY$l@JeKbXcuo@xDUx^yZf-KT zu9d6>O^(_Qw4Ll4H8<^$p68s3W0vn=JYjS=|K_r|r@^ka_8{dKs2M2;5BI{9&jhmf$ z#y>9VbhQtpN6_k|?bi`f?KsIn@QDg;Z*Ef3K}cLE;A%{1pxEHR5ud>uZ)DV>3%b^l z$eTB+)A*xX1u@#`I@_k!HMow_WYQhW?_4`;#t}Aam-MIlQa>FolYm%#XK$*fWoLH* zkve)|p{`C!3%W}8YXV;T&*82(qU>LIX;@YScc1XR{BZV#x9U`hdf!X+cCEyR2MH-P z%2swxP1{V+UvFSN;!k{h^Yww{P&@xY+4`>~Y20UKh=y*}1!sw)4>m({VbS`5 zPqgVweny*9#_lbBeh5{69AfpOQY;U78B>h`uFdNfv%QaI3cA(lbsyhqqia z)9j_uipCy&`R}APR%d3NKOLdS>}7-;to+W4A#7lB-%YDtB+}w%`O{5GYXAHzp5%*q zW=hv0-+W~ygiO?H;FEr;bXFj22g@E&NfW-gkb-W5En_kDA5K6t7m zqM0782@zl2a~%VyK1rU?ZjPU8h6poQn12ohZ*XsdXY4;r(@aZ-lD(l{J%B73?przk z^F$ECLnRfCM`Q^rdP~t2J#F8O4LGZYiCYlrb_Hy&OjaNj`!bOr5}7Ml=6G925%Qw3 z35ySDG^OjiU7JV1O$<0l*$d>UcL}V@-4Mc8kEoiPd^N`Ul$9=z*9bmWh3N7dH@F3b zrvYCR(PrF?-bl>u#(wqRq8@j}02#H-h5C71n)u+tqwU)`J4g1pCl=c5eiSu}DI3{+ ze1;uYh-7EyK9!XnL_S^ky6>5_G$%6i!*M^{oP?Ux200R(`0OnnmzS3yUbN%pnIKY_ zKOeq1m~C3;JfIkmYXZ}u-WgA?(ceD_ChjcV9V}3Iu9-u$Gd(%^Wqlnw;cOb%YL|KC zR8>QOo0-1LeHE!Y|-H&+oFb;Efq?wxu9&)6vLt z=88QZgcp3UZS+bUnX5#ImR(pA&*%})o3405)Exika35KYC@Q4TTVHd(RacjOs6CKq zNFe-$M+5sY|<{1 zWb{`w?$F6s(3Q-02os=bH5A-On7Xx1fKMyRQvqxygmN z@39gq3$A&Z#U%O!VLXC!3B&#mNj>m4NLC^)cQ$eMQ7^kcV%Ixk$h;O{D(zQZD5)y6 z*!h7<#b$+}z|uY>-BOh!KkT0N9qZmdXqTTGgQpKi&EFw)kPhmseJ2xU^%G-nXE(hR zgD;1618Qhokj@&{f-Jgny_(esnqr)WJx^)+K*;jXarPd-q2Ov;=k0gE#Olgot}9`HC~xk)>%I zE>B1ZG_)jJL9N9W`bbvKoVH8L%8~=}YzIqGU;Mn=TA8<4N#8#=44~(LDI^?Fy-aRJH?$P~Qn68y_|}0N z`sRue_VzT}nx3NPWGS_io{a6x^SjDL2-lx~@b-2j&00y}4~p=YL_>Ii_#MIHq*IG+ zHB*j+2)MkWtHgK+f90?@dPK+J>>8V9%fxO56lanKJAwC^Z*#KF|^^1eXF-=30O zOtrkY7emkZ;JdGfd%#`Vm1F{k0cjj3z8_XuV_ySLK2tKTIU+t?_?qM!3k#1bMnZyu zSgsU`6HvTJ=PsJe;pQ@Ko6Aa27Zp8c*!qphb#>R6u6Wxr4t!}IXI7zNKzqc&abt^=nocuph=1PPEh(IxO-gcZ!^*vl zzU}z-J;coW&X+=xZBr`b=xISgLCR}qxB9=rnn{8#s5B5$J8N7DMEw;=HJFbtjMIJS z-$d!=2k2bBEje|w<~xn@jz_CP)LT^6Fj2&F7e=PR|%qw%`&PHuTvf=NaX(aq`9 zG0LMPkMA$NEPX~%?BY{t^HAoU5Apa~gZB;nkDY$O)yiD~8WOYJ;qT3&Y1*ppT@zMf z5X@!D>M9x=kmFB0pZI|ACNDNPz{bV&UQsk{Ms846)>W1PL)0mz=PJ^Jj{Nv8OB-d0!3~ky zgH-#7&agMMcz_=nj~-U#9;26e@t(9X_Ip`sGtgXcZRfK&h{Z2O{R^_4!H z*E(6uhcXG;7E($|)S$KC8#E0pLr;_ebbo-`nY6A1;bs+Rs(po0w#A#16o8bU1ggvH zTv$Cd-U{DIopnf-h@ap{kl3Te1HXSfH`x_Y(SJ^|nx@HQeo|4Dw)vA(4Lz?hA*ZQm zM5azwUpj`DE0pA!V8w$HS0BDryYvJPvji7Gl~XEO(sT14wlafhwMtZDB8(XCj+_}9 zD9&rv|5A9d-Y#F>{QSu;)()+!yNx>o{Fa`2^@=Ys{x07JIue@LHOvy|1Q(w1@%4GW zc%>yC@?+fg^(BuTXG$rh(g-2~Wb+gTPrnbjuL&~NF}>R>*%;ZaB?FE$XjN7NRjCfJ z*m2C+<%-a5*a^+T}2 zep`8eh%$aAQ(WDZi4oNszW+>du;*mwb33f+o9LISmt)q5wld5P8Gfam&>_(&y_BKM zl0?@d!@F&A`({8}?(8EGVeHp^QRRp5P8akdN_P1KiKO0)u^-V%(FGF9kOJU|v7eWh zmwyxtLfl3Q`s^-kuKjc6*xP7z%1BUnq%Nq%v0extTQ_nYe1K#>|`8eA2Qee<>9_8QT z>_Fpov&GLXsEhia8-Y*TZ{;n<>vWaE1=}O;YMPcTxh|R`c9njrT=we~PnTu#*N!XH z4|Xx4Q^&0+E1zg=D7Y2Kn^h(Rnq57!@WZ)VL*s%FuPFuX@* zBvRq8dBEL~1js97@os?B+*i4H+_JnGdN-0m@2oW39(=VE^a9$n+&-n(KUcXm*9NUW zdbblapZ?hgax=f)Dx6;Ah*A38ODqHbq6Eu}`4R~~u0{{kJONZTJXs+$dS&b0+LXL;-OT3Y8g&)r`PXAOmY{YM% z(B;{enBfoXnW{(~`jE9_L-!y6tUT+wAE9TUc*WbZ3;1jYG|c%l2*Sd31v!dus0_sG zUX$KJ*=B*I*H_DC*e_Uzqxy@oF+%;n7(`l9FYpbs8`}qy!PuyEw&3UeEO;`YgOLu> z_{+C7&A~=gtq>s!2Y>lk?Nq_|ivA)!&Fpo9Zz9UUmwpJ@S?7OHCcMZif3?$|S9-`Ij^*TA| z-87&7vim*fWb5Xt|D4*f&Qp(TY&I|J>oLYjWJi8(2hT}znXLY+J|8_^yH*Cww*d=_ z)th@VZ{Hr16vyD(-&ox3=ol00yqi&1rc^hv_MA}BPC}XR024LwxDSs)_{U*^IR`N9 zjC+fN=MWO|_U%+w*&I6`zNm7AWe55l71+Zz=r&`Vrc*`syPFpe6ZKnsB8hIku3K{i zxas35G0?m}1zp%bUEKa?gYCRJT3RgIn>WD3$&CD$*Z9+cT<*j*GC5Z)yG13q3c2iV zIF;#VQgE8ES4QVG^C+t?K3}l(yGwBhm#CJP_*PmVhWXUk$+x9LPnTS@t6L~ISVJhO zG=11CTOWa*!(CD4X`T3N?B(jE!-Zgz^m`gdY{wUx1)vEhu5s7qBEWETJ~kGz_W+cUz|yozFn$Yxe@5?drX$#x6}C zCBb4bkf|t)Q$G1F`fYEL-dxt0wU9$JQ(a`gJ7RI+3-^J22su&FQ^fuF=#P+XXtllz zos}?rARdH2DwCei19e7T(8dg z*ue^^Gxt;k#uPlFqq1&c9cMmg+qI_!zH7J{*=c@^Q*(=uq}N0?oF?~0 zp0(=v*qFgb*Frq0=~;R^7F;KJcA{Q(oqaI!5Gof#2mwGbY>@L1ds=PPjssj=7s#mz z^6zSN=4NJ{(CH}<_IuHUJCex%<~c@kV#nj{BwmU4@~`Q5_&kSj^pDF3^*4@~m+q7w z(zeyEdYHOBQw=dQRhB=GUEB8Yai$j3f5(08h1gA|SA6_)qhIg4xe=CLNif42gu6L5 zo^fOSbYdZ>dZWWX=n0j?Ty=VmwGotd(e8CU1qd-O;akuLX7L>8CX7HqUZij6k797+n`66+B1{bMQh=v~Br*bFZxC<6AqBlf%?vpVV zt-`wYmY(Rzf5$vA8^w)yDbKwp=+0&st6X07_%xlkz_~eO`N_5>@thlLb#Y=2V)0Wb z!ZVoTC*`_j7TD_@Ds=pAfY=evIs&Z$aB^}+H|PNG2_%8wCBr{NH~f|WS5Yx~5hPly ziy+oyJ0jQN)I9L6WeD|7b_t}Di2uK>T2zQTj-}7(iOF5s? zbszGQ(mzf10BD9T?{3ZO_dkY)x9F?~@ZYrb^!jxNz?t7IK|1-*ajo9!bR_T5CK}B% z*DHe!E+(cerub5+Wft)Bz4pU&YYr<^QM!AaxF!%327~fcIn#O6$=>>vim9=Zl5_Ki z7}cQLHXi|sadh#4oOadHbF0{OXUAc-|M`Lw%^wTY+@W4DXZXmPY64ZXKRi$ZETx?; zglqckN?Ad<5dQht!(${~%RBY*ijEw)c&s$*3?%h^;c|YBk9VkH!9B{wz;5K19 z)0y_8s;T?iq1@S4PiZ@G-MGCo>PzV?Y*FP8}EzO(ylD7T(34(G7&`MPr294BXBs~Z9DPGDwR ziGl>T{-z^b=&?VO?q|rILi7+B`v=Hox7Lk^f)|T|LL;)t*y!dRTkx$A&u4Z1JfU&iUXp z@MU5s1ID%tY$|I*SYo!z4;}y*HM0R)56WsSt0qB2(7xH2-u!|B$I|DOHEVqCzZKT1 zuGEr*dvUaD^SCAo3F`;s6j1kk;kSKM5M5#DYgRdQPj{3~NR>wcs-IyLqHR))$hHnf zJ4AJKTuGWT-!jDBwEcT=W5LEk&pS=G$JG1XX=ty5$PZTJr5m~7#S zG#xJtAQ?5CiFi^Yp?S4$^h$P;Q93(6R+9-8SCOAU71{jan!S2v_wDMA+zMLx8ePMq z>o*G;)DWptBq)Yg<4cnc(pL}$Gmdg)W@f^xOG={0jY7G9*~abHw}(9DB{}Qqcd*fI zbYzOpy7j2mR(f?-m(`;!)7xsdbao~e!m-6SdV8HT{V+c?TP)t+)LRHjA|O`LjeYsJ z`s^POCm5xfDVOkW{eVz}3zWYf^t*nH$7kypVh1XMfx!TUPr>|E@9$17ocsL1&+qiz zxG>!VQ+>K#{G_|LFPy86Z}Qu6WX4*hg1|2-HbhKSHm!gVo25w%42hPP7a!1<~U{tfqc9tFtC9TmTCg+PIU%5nUfGcjOCfSc-`!F?$BwjXKx7%!*g5rGFc7Em`E8WgtP^-CG;c)A`VG03AJ)D{hJUHh#yScLI?? zM|SSt=Bqgm$=M`EB=}Ks61P%ux9ok^Ud6It>LFCleljDksTC6GFw2Nj+735rY3w5xN^~5CJv02o&mW6|z`JJRH{@`L z=3S#>*v&kKeN|yMwY8sNyw2&`a8|PQ#WbTN(z@krcM61BnDEuGesK27XcYabDa#w$xtCJk49Z5f z+Y=)tkO03W5CPJ~8qU$EQURF)3)cb&^pgOlqdPVaq|8~lX#RTZbxthkbCoI7etX;B zsq^%n|3`EJ+AYegAp$(Joacs+J+bcY3}^VYfP*eIlG$3-ha~;If#~XSa?V&}nJzPr zDQ74su#kgAAEHMU=0T=FH?o_F`-uz}O65npFlgKD3H z(7qgi76s-gX_&OsRK!nL01B2*c@pQF%e{J)(BV4IEHeLB=qJk|UH>?O7&hkN#wtf? z(JN4~5!gcUK$z#=fd6YV$b4D)o{~4Wd7LLW;+RrZZtGQ6onEd`{euuu%1B20FPT=7 z)j8@`4p_D1geHr_MvvXjvc8_K_J#*~>ZBSUU4tqV@V}$nu;frqhs5WAzPKyMVJ888 z4}hQx;GbulW7e&7v zX3j%d5D$^aC^rR!+}Gf~@%ZOL^!*Y%(2X7;;})e5tlp21Sp=wrn)I6i>6uiZ_tV

nHNJ#^F4qb#?n*7V(0@+q)(wI2sk$_cPceK8UhU6Pon5W z5>w^EJ>Vz1h=Pn-cwo2?gu{~yr+HnCt(S+B*t#=ju9y_ehF+DmylM5Mfcs7%kD|Jl zZt9q-eVY}krtjyj2;8IAq&nUA+|A}2A+F8sh&owG%2%q@97QxOboFhD;wQ)DXdJ#A zx*ehUt4~GU}r6Bx7{G;I^S?te2 zdgNP@MQYl(%FpgP@eSoHniccdtCxlj&?n zY(3u6ot3v__qnb0?O-!2y2-2^?aaD4OKKkn((Ezyq}TX(BQ+NQbr%gajEUcL6evhd zNhvaunRS88o1pMf;q+&L83NO72;_0 z-Ej2Mk;dlcy(rov@6}8ZcJPG+%6hEEAHozRIlje)?pMU#=C~VK?hOIQ=q|jp{!u9F zG4eirY`JG=l}wuZ71o{P8z!iA6wz*kFYSZvBj-9mCPsI&WrFXy7hD%kT|A3=P0$Zq zO0~L-Ha_36LyQ)){6q&>G;*{WhO-`T*12-#43~`aPalcNd_Q?R71FY^{)|9b&y0F7 z#h4lbOX&7+0$#GW4Tw=1KMANK`ar2DyCYL8IK1lp zL=J`EyFH2dbc}@w?lYfIhL_TV-I0;TvINIhE5e}k=l?4NW^sM%rxus)Bv}LYjBJ62 z6jsXZTfYs7N(KD3Kp8jZ6ce9ITXyq4*|24IAy8fHeoPh{DS@M)Y?YOPb%T-7b%}7k ztEiG*b0MK9FRqn&T+-Bb69rOHQ%wxfc6{macmQxb;vC2n0in->)}Z&#R+-xwW>kbqMW%Y}x3TB-N?p)JL zIcrnjuG}E`r0sK%Ym%iil8Dx@60mT$)5ZN?4{K$JBcvJd!nCq7{aj>43hoS*p9809 z%jMO$KjiQ0`2AJL1rNPSDtC}`(Qdunwdq;u^`En>$hmzI(MQy!Pq=NuUvXSWizZ(d z&69ui)chw&&e~?JGr!AjWX%4-1?`)=O7xR3ceT76&-k=KHiz_JPh)eSMQWA+3sB2W zZnCNou2;KaDTFOwjuk9w;%G;_7fvSmME&wX(xKS zMWx|=khFFG`}wYpP_1rxb13`<3e9F z0Kx{)xpsqms%dGtQiIcZ3wOT=^WK3+Ep>F{_~PEAZF{fWJB)CiX$G&vYF^Q&?)y_x zisUmxJp>W|LN+__b5i@qeNMj6vY+;#=7ULaC;s!;n~o5z*0x*|$Y) z!&X1!LtJ~`?~J1PkPDtv^B?lP+A{aPE~do){$gzgPAR=+Bl3>uJfIbPKLOA-#b_o) zI(Qh3AqJM^ryDs<@iQWtjHxUcH1o@8`}C$$RSD1DM;v4_xe{z_>A2Y8U-h{qmSUA@ zMuJ6i_lU~tLb90odi|XIR)hJ9>nC3M?b`9PgmO@F*2hihCVb9~+Kf7tycT50|8aZz zr4VsRG#E0U26=8}QQ`&lzfkG6WpQz_8%0+}11pKwOP~K$wzIoLjXFb=vnhij7FS{O zrp(klvsPzc?rE`D643Ne4?g+v!$M`KK1QRO;1w=#2miS!SPj{D5Qh%0tmpU_sfu_A z_}9iE;dOaN=*3+6<1LyR?Q^fs^t3SM?U7zt(3!fLgISDq$Jhwh{%vb(LnBVbpeSXR z6nA_}9p9G9kgg>_nGr!RE$&nkedlbyRmf^I&)6Hs(;e3qYijbtsi(SsA ztSK&^50}RteUp)z{K1LBsEr<57`r;wwuHB{vqO z2?SaCVzX2^-%WDmN*!0dsKwUOtP?GdaH?><@Kn(_CDktNViDp{aK_X0lndq_uy{o) zI8uP3F|%n{pa4Onl^fHIQ2eD zG_QGQe)Hx>drXQDGKm3kr=a%W?Z*K)3WZ1^zEbwNp^?&8JQP1*Ujy7?!JToJ5{><9 zaq=V0t1e(C@sO}9$9%J|7@}$ZIB?x5guzvLHx-bVeI(Q66-DBszR|7SuXGKXW;(K1 z?s98{?gJz`bR{-G#Zx@$=QV(SHJR7CB{5v1*q|(lRQYl0m)OR z=J2v#R^~n@RmN&jSRq1KtOdqsvD(YY_4?>0xzRy$iq}=3#i6*b!$T@}VVLFTQ!*w3 z!4}N!|B_Qu7@PrXoiV{`J9f_{>w{Gck<}lizf5WaUjqaDz_7ofR2*TPFTU^L<>5h0 zp)$n~X2P}YJth7e)AIludpraa+Tk+bXLUt+K$M+XfCPh_wYdNU#02D*(>AW^U~bo! z5DwVdjiR}oj+l7V1GIO65*-7NmPf4>5-Mw{%)4B7v!)@0@5~{>vxLZ~bO?{(Z`#?< z%my5##0UGpnSLKsm&))GajV~&U56=4KxTNrC`~Ys;x0}TeRU8f0Q-;!ipM(v-6yE9 z!MtccL2}RwIgYjd=bvyjEA{(1?DZk-Alln@ktO>GHP*$2v*1+ANJ{&M^4p{0j>SgX z(J&$>I0&4>O0T~I1?~)^v`&!@_3NA$Xe5S(HX7NVvRQm!{?l~UqkDU*!`v(Cta~f> zY&C{Bmre7{n6nX@zkBA3ec5`z9q~!)7R@4Yd;@1Hl`9(Rn(_3pF7+H2LSnl)>d zKA1I}K>+wtN+5|^9!#4U}o~IVsknzjC(XD!+XFj$Hld9E#HV( zMj$0EM@jrHqtURmDYiAR^?NT zhec}P@|gUty$+|S`=aV}!rt~O()v`kjK^Pe?;|F0gCkHDrbiWy!C$*B^v|aax(3ekiE~YY88excZy0 zmC7M;#R?F%@13dQ3P9}?)OO}wJuRW6q_j5WDdvlEj?~oFpO1N#WtsdyX<_c$AO8Vs z$L3rN1{ATCTg7l+9-zjXBHp`8i~AUK&r!ZU3uO!_ZPwD(NYmH;LkD+O2{Z6I{{R#H z5Dqvdr+}mB(nk;e?ZRpDeW-T_;!5hh-;uMQeJcx=eROz7Pw*S^bEUfVmXOT>P>sob zcwRuisbN10ZZTsHf`joAM-~yK9Cb z+}2Rq@&IIam7bGFxS-3*k7$2SCa2TKyKcf(xvu-L=bj25>G!5G^?OUf+4cyxUn+Yw zAmqFvM+zWRRNx~m0oj(8dHJ(6qSiZ`uQ4XuYJB<2@{~^nX%5EKh1}hCSGCDinec(Z zT2~qo6|~)ogc{eVD0I;|1nMu%eIMP{fG_M1^lC2TBtHD>cJrO?^+PU{H7R8zzbmHc zWH%PUp}L>Y7W~Damz^f!PZQ>2q`aiA0X)nx;gzA-X&_1n-+SM|RNh@wRU-SI^cY`G za$-iXEZ=fjiLI0_b+|jJChwo}kJ238hEL3^Srw*~gr~`%b0`X3ETol`YSaFj)GhBO zbKZOt7k8?{m-YZ7Bjc_Qr0Y2kSD)%c*`jlSN}Kb_)+0}!_x^1q^1`@=wCz3x1G(_C zg5Js(TBT5_Z*;DE_)^Ql&T0GL*D1E6DUKDW75&f{D)xO+O*kgGDDvB-Ns z9ej+1(X!zKdQF$~`vTlsMaRH2q5Bh_%3P-2f%xQ28djZF%ZtFb_CXq|AjYZ{6hV5# z>|g!O1)w3!6;Ro1t|$!Xcj=UE)=B4+=AJ}jSn7rLfV|1#RXt!y!gRbJQK_vcw-a9Xrfm>^i6-uw@4ZYe-{R!RH71OJ0rI;S|`vBtvB6U?p)Yi zv}>a7$NX!;u;2Q)$D8(unhB@^bIGLn1}q^PIvzM9dKs`keR< zO-H)#zJWCf&KIy(HJ3>Y{-ZB-gy&_IXRG~~tg$2h3j+p1$2JO+&L0*n<^wD#j0i(K zc?4$Ci`T4atZhYT3i<`p(a|AWlyqauTX~UX-CpBht!kv)d=)4qQQ)oYf}E23=5yA* zPr2*Pg>&j^Bus;NG0@JOoOaV)okV(<&smkyes4H!bM>R;G+!%nSh%vte5DvUTCd@V zg-fq`5>hTX0%En4$ssefXU8SsIGRg@9JTT-S9_T8UQm6^y8bJT<~^ z3!-n*FT1>yFd^Pt4(->l$}R;208QriwrASye|&eTjH@7(t;-%T zN@~H3)%ouW0H)=Zm76=c<#~WYtRCbd{@uNu@6VlN$CPN>_cL<%8Om#Bwr+2qah2H4bA?Ov_*BrB+?l4Ij zbY8i4N*><|#OZdGzTM}(x#-T^YJR_Y^#Mm|v$nH^t-ZY(H;DozK7O+#PRMP3OlN=Sip&UmnY3TT{6XzM)mgY@luH8+>UqP^3)Z2L2~Q(=>dYp4%| ztGOKOjR!|t7`Lw*=#}Knf20bSY?6vM6qd8LU#ZR2v%zc1Q#Fl*_-dTPu zyQXXDW9M&A&cj=>0?dFBkR&Y|V4OrUG)+tfUZrA*f&x4;#HQO&TfcGXQ!d%5jP@A&v znG!PiIY-hSp>5VYrlnxf z%xYU)cV|^;klWUDI9P6u75{wI7yI&q$W?-h;Lo~g$?D0WVJ_wU_^%&<5nIq-yf=9_ zXO-%{+xx8~-U%6y@!Ll zIF+rjkQ83@LwNZopx@P7Sd7%;F3or3cl9r`(9yXpbBkY8h;CroTxqqhC@@k|5QdqF z9_y+jdcYHnjP@PM<0NMr<7EREa6qbChwAE1)ynJ&d(JR=n{?-M+LL393z`X}JC?&8 zMNu1(-%PHn&%tq!N&`RD>f#u|VJLv!QzX-M>-@O)9;Ce(3%sVo2}BLH(P;{T>hczYf4-7k<6!i~1L4!`D z7`qB);hncp*K%WbS??kGDpGv#A@4tThU^%u_d~q#actAy+NwLJr-g#c)h0LfNqg>F ze)~Go2O~TK#PLY0po%%hba&M1M(cLsn2}AykR}dxDkux<2%KLc7eD1^VR6=Uqb*uY zjg;3K^AR#8T}fPKzJI?Z1|VxZr&Yhc$Jo+zxClR{vRI>Jj|G0hz|KH0X>R~>IU!!T~qwl zf6uf+QEhA`4R*%DMMKqP_1SxFeHG_qM|vWv^0kWb!blC2k}v~|(CE+oiUSfrfaFD) zk|0WK7U2@WfYnC4OAREQ&IMd&Tl-BPx;aV@~>XvMRhvbK|Q;6QFv~LYQ18YUw4^#9_ZR;ib+Ip=sEzT- z^N@;eyy4K9`9~oHvP-D@9;#zOn;L4z$B^(X3hJv-sdXQKYLC&IqNI6sb@gfyQ4I#e zS{G7T)hZ?)4P-ULhkW8}xNVoJw#|5LNQGU%Sygh}EDe!Q#C#vzLwCVA-6Yrfu?U<%Yg{pulb3e7g} zd>8R4wGhia^x*jy17X-Yxvjbik6gTG;4)zo?NiC@E<7?aaxZvO_u7pcIIRUb?Rd}3 z%;3EA_MFsDy^~ShZ(qo>=!4fj4W#Z0pj?EfED@haocY~MGN+tghY$y}5|TP-f0GeghZZr-tRXu8@nf)JMW2D*tHNU&TM^ zOWWsZ$c@)yiEqYZ^3irs!CHa3MfwX(cxhO^KLr($UAL!mV|&ekq5}OA4#0nuBqYkb zs895wZiua!M$(d!lGmYiV_wQ0K++SV)v18a#CKLW$!Ai&!bY$8g};f{r}v@c`(X zS{8H3EgQ&nv5`HE$puoOxH_Md*HY5b<1q=Y*F08};ln;K2!g`yOng z#Hc`K*?u2*=ane0Bru-!gU5+k5%L_^( z#G+gmTHg$GEHXF`44aqu%T__72K>t)KF6B@JSM@g7B!Xw1fShAy#>*nwR&_|{dG~x zD}e_Gq_tG5q$fKbj5v{S2lKC0cG!^OC(nHWsDTnHVdn3+dwCC|pl!*{QZPl&zWmY- zaE+ccFOg@CjAT77*lATeh-a8ak`hqu$=4Fn{Lj6Ti)pHaGJ`MlI8-3{Y?U{5Mf$dz zc7#nwVpg+}AT@4y2t{n51( zs-^h)^{WHS!h=NaH3(^6kCgg3TG%I5d0t2CgebR#Ce2Cmqgvf7;Rp1}VtTWhZZwmk zI|D$~*VScYWS|kLjyLo`JRjw@GMopc-m$M={~{Rn@U=#56j-&|ciT*AP^Bd%dLbkm z@7V!WEc#yq**X_1NMCWyT_q9|ev@^2V|MrXzNy>W3QkjF!*tw<0vmm^tQ9TCwy9_r zkoZ7HQ+C~B#GD?_){2Rt#8F~Wk~d_)EX@5ul{qS&Llk3gy21#OY zu)=EJsLLD|7su_sv4(FpPbH$iiE@kKE8_N z>nVDj`F0tWo%x6iWZv@j7>H9G;^pO4*3h7b|N35EzaOk87(cpglvKX;_4P;K8GM<= zMExO`ctp(2MLt4+TPlDlvQLfVq2HbAYQ06{(>!^_#BXOQR&@E+V~QRvJB4YVQ{lY_ zR4XO5wO{$D;8S9bc_R7J4j4H-m?zwZUjsFzNmFI$MoF3rtL4o+;eI>V<>#mjP1c;( z=cBoND79Pv+?;8BEa3DjhVu#qdbv9HU;V_CF!~<_Z#H5C)7%YijaeEiI*!Nmu5n)3 zE}j##_q4oOXYagF?>lF0AFXVKTSSsnUCF;34z}e1{h;r49WR>N>W?2FkU4pP!8GqK z%;dCO>wkQfSPnM?kum8h2_88`@!VZ4Z_kg<$I%}AiVcYxZsS>9T;Z?kRxnc$Mh}N= zlGyj~r+~2>-`HnkSC#{($c98cc+O(ESuFbBqjQajk%RbVEYX#Na~ZN0Mc>pKuTNc) zyd_I6u0|&ubFNSS&4#Z1VImoOPKoqwF|72GnXzfL@%p#vPwxV^6VfhNH^iLg{5;lY z*f_6nOBT0hb({abCuQo(i|gc5)Sq@#{QM;QE_4SWjVI=un4++ru~g;K+v1CI#9ej; z;$?Ugbo9jV-nohu&#U%7y>b%&#avLPe~t0_1e6w`69`*WF8CX+|Nc~}U30X%d<36~ z1UM3PK{Wz*3^W}p{>f@qYvwoP#sehrO_e93=*Q>~pZxx$VtbEtiHqzv!FxApUX#V7 zbl&~>>xh_(?ix_H6A~4zUs>4|!JINnS`LpHuqic$G`=h+|(Q&(g$$;A0GgoC#Hn%Ld?;A-jL2!b@Qu4KH8PA0(0~T zaKL9Wmr2Dm0bi~&3XD_6+)NsSm)1nmD{?ybY7vt>F_ZT~_7cDsMgF4$kVShTbrf(O z+M|LEKmPQJ?TP^8@NF20g{cGvV`EDh6L*-aEB^1u9-5@Kzb)b`UcPBaa^B`FlH5<7 zz>2ya?WIQ;G)hlzS(p109buz4iH|l%zE>eh0fyx>@m+0Mu-xTzG1ouEoDE&Sh21mW z!+b4*l#g_UEkT?aj{uVkx`!sk%T1($l=PbU?>vaBmhl+!{ zOUoakAB1S$tEavtbVFaxtgzTkdh7BbaCWKoes2jN`m-Ur>XuQ9p_H{Fzia&vu%x0EIV&p}M}-VHE84D?8t5_65&QW?GmekzU*iuY z#j4Z*4~R}cv-;0=_)Nesr}vD!e)t@rk>g7!gu=2It8o6&sipD9_I>@0?e*%Lwcb66AgYEb~hK$F;(x@2Ae|EqwpDZ#hn6!=*eDm42xuqll6YTWj%#A%EXs8UiOC_74#j6eB-&;D`D2V=w z6YFo|9CJC_kAs%EZ;9I@^T~EX*DG`JOX{N&Zq^pCXmZ~XJ5Y@7MDzWxRumk0p+Or%1wvzB~#vxPiG%ep*R1GxdHTDM}Q0nX__} zBjvX-+r%{PdGaZ%^ot@aew?F!!w20V9dO2v?4hG_cf*SX?)y!Aq{my=)=t}+2bhRz zGDXjK51$}+vX%F+jzTZG-IS_qx!xQYM})kJLegdaIh&H2>Zet3Us6Fqp`oEc0;0AH zyu6YoCMJ6r1kTCI$;D=6UBK5eaXAzr^t{`9i zjlEC^i5z){`9?MU;rcj;*m9dihc~Xvp4`7`K@Wc2w->zZIN2U}ya;tq1+W%{$*9?$ zkSjdSH1ZlJb~il4b*(`1q@jQC7Stv|iOyKAEByb~p!#xud3iX@)YKI6Lv|(Oj*gDt zNxtxqz~&^=K){8vnI6mc7~N}I(ten~EWCYj)44e;*7Ia9vl3n1L+_Z;_g&)m0q9to zv{&zCWmn~ztr07R5`b^!yI1%~zZIXnzuX^ExiUYx*zUGAU0L}xh~4JNAB2g4+}Cy9 zsP7|}`*IcT!#||aZb_MHztx%>%QGoGJap6I$3M)Fee?1P6|mNW5oJY5?n;EDz>~5? zQx0`N==&-;`Haz^m4$^LAR7^p(NSMEY5sk5tnd1-{iFK}lYHStQ7_vC+8T8|Z|gV)097&WahCr|(4GBU!3BmnqV!Ql=N zS-80dorwLw)W0l>D6o=Q6qoGwh}_&VTsw^T(M~1gm-t{T|l`ybhiD$t`8RNDapyW zH-x0(P)-kVL_&&4=??MD9}UmiHY7zKLiZNgUG*Aj?Gav^&US9Ery|$z2XlR-VKpZN z1wk-)_GPFL39`<9V(`f+udi6lDob{4Q&>>wcZg)PspYk(y$%S{-xRy`5SIE~lBOK; zqWNH~@ug_1dVGYjuT(n&MgT|@X}g+C+x^71m9 zQ9B4EY{5lHX%5`o#5Zqz5#m5czqv_25~)DZwfH{A0xc5Zjio+o;5Xw4Bk%>4F4E7@ z=&X;Z^`+>nn}$RW{&PUlD>*rNJtrhMxB`j?fAkL~7&!rg|0+MB5WM-|He)+P)kJcno3a5ag*lnBOkDSb;{FxsV9CoiPO5ZryHq#p4X~BszDg?p?z2iI zSYb*U8woviqRi|Weh!se`=JiWF#?DKn`wZL z#Wq&bHw8!gySIG-urNtA0l~KP(Ck&hygi3Q+kJf=DLd)In~pn*jbxvC{srwah<$}1 zNe7sd1>?m2>mUYIH4tf+;WC?+)f{pVcICGvs;vH>jf;qWS{*ZBTZ72J;jlK+e1Y>Ujxx|2`!jm^n~~m7-OKkbY|b(#_j5xZ)ujaY zl?0T#MzyjV{W=?`z*seI2(~SlIa{o56oTR-s@%f+)B+>s*GxZY?-r>ubMFfNzCs4L zL*0WJ>&v}d{_>kXi(+rAY5)a~@fm6VdlFyS>T#EcKH$a}d%2VXBVMUdVVD!SZ5%VUtfvy_@KBno7OTA}`j@*XWS z@i~Sb0E`m-eFgl|Oo-`=Pl|C-Z}M5G?~$1my#1e{GRi)rySQe<6XyHu*|Q}W6guGi z`yi`^Tk{=M452BZx0JQDnV@g;zILB)&WaRWv#z9<6?oFQH%#GXgj-o10I4zQw9Z## zgr^%-L0SHjsx~PPJ0}e(mEEuzJc22U#5hrBWRxvG&Baw~_vQ`#IbCsRU$29|8+`Ka zasb-fwYTcAmQM3R49Mz7cko2jWAG~p#RG}dann5^ijVcB_Q{%%D*o{gp8zulAxs^x z(IF6V3F>eUeez7$;CNN^9l`f_g##d_cxBr0j}p4X7wI7Y$XBl(az(;r^Z={D#l4uT z^6{r$0U-f0CJGQd3QvtV>HNJ9ojk`5ZzF@=W)JQDZs@4359zV#`E+*?WD*(KS%Lpf zjf@OZ)^k0MCl3LgkOqu@ZE;ZkajSH|=X-S6O7gK&582X}D|Oy@l@z&KU&zh6f9W{7 z0U=5nrbj|vo!1_iPk1J*Gu$E31sj68&1eai;CcbWaYlv9x7;On%0MY1&7F0 z1^p3y^&@IYnA4=%b5;mN=;;y~`tf(2SGeL#Axy?ur> zYGWqmmVQFfI*hwFM#lr2gAXsakYU3Yjb;+Fc9#|q5kP|5QLbjP7*@HH`=83Qw38Mt z<|<=m#*>!kuB_hQ?d4V9yLOh9JfBKj9hQiOiFP&O)SMc;BX zy=v_S8KOF!pu;p}xndVj_1lR#-3DJi*LG`C|6513@-iq~?Ay|jZ9ei4ZrFf@f`lc+ z8hSNGaK_J*OPitOPc%gZ180rWhil3)eWWE(V{@_bhvj3atE0TcopL zr@%3t?HOG5TrHZ8V%hPQJnr;8(QxbAS)>W(82o3*^Jd)Z|EgI@T1!se6~W(jmC{rT z2+PS}Lz6sg;4>C3Pk3hZM()cbiXX)o0VzUk8?5N6>Wc$}&37*HYeUZtoDi#}IkfEw zqX*?dNL)5DkJbEz(}xIACuX}N{^Giec;j=!KiZi;J=$AkcanG!LWHal`Bc%YQ3XWv z_LtDh|Gici>SBCrZMbM8Da|JF{2D3_pYK%ri`CCMc!;ZjTFwuSXtZqyPXP?&k1ol;9cex0BtWg zHdvm2Sr`OPvsFdi%geY*2I9Emd2g`Xjj8EkL>z?f~h#Ii*(w1Et~NvUfn& zPK@WA{lL#@=IChZSW23N!uv*As-8Lv_)b=*5r)Z^G<@e;ZI>;L9RIO^ya4b>%7I>Y z5EynUtFtJb1!IQP0#J1>e=l z4-ZwT{8U+~0ygay*_G!fJSmIP;&^GT+}{fM(~i%cN6#wW9Rv5TSEjYE)w4QN*=!>WzFWe z0LBLvQcOYM-qXIdk+u?RKMpXu%eWbdE_j6Wwnqyb;}q%toVFAHn00;!3BxpyQqM!e zoLN~}W7)3VNhKCk*LEnfJcp;v$>Bq}G>85mwYJ!gLP~ist6#N=ULF2C&?; z`v&A?5pxEH1_cKQwtzfd`=TR2CcQeF^E&#Ff{z?XNlYACQy@)?mdjrc5Mb{ZlJeXm zk0=q-)s<)To1T8sTZ-vDORRnv(gxp#9?>13UcM3uAQY!2C9y$Nk)g(x2PO}OUXY`8 zLSx3FowZSADr%Mg!i6$=t3qm!cWpH*`T5DS^7GRZvHAIed{$i@#W}J1QW6pO+e{*h zT!@cBD0(eOmX`>77h%HYii~m_K&4jxAzfYjqhGk)JWMRTw&j9_mi_VLM^wm-{2jzB z@bW^a0*dD#2Pt%xY;t*4T4BBV^+6Dv1Pu%%t>8A=zR*4^0LYi$c~F`lq|g;+a2YHY7)tWXg4P$ zK0Yo6MO}Pd5Zo* zYm>zbXDMiCXetqy01La-;UazoOkC`{0ebe1BP}CZ0yBLAhN{X1Dh^va0&gMSIw|GPKnvsR1D2m3yvl-;2Z)1MCw2hh~A&778!ni(kBuY%Z=o+O_&tG;M8obb2U6 z$$MCOPxU?AizTG>O)wB&4x2l#z`>T|e&SVPsq`M~bL7johbHM3mI@WkOzQjX{5WpO z6P?5Cj!4q?Ah^Znzhvv@g>8rviVY}@hDu-gHd(bP)1+@WYJjhZ4qFitmJR5=G~~fg z)D*0j2R0u9BAYlBBhR^Ypp$K^j;8`i3Y}gj@}JA={qS#F`UqZ|=X^C=ItL^tj(R@c zJrkRCS}a!oO{e;E5(KYR+ew<|*bpW7H=3KD-z8dJDO#haRt}v!u>pamnUc&#*Qftn{cyTc2~-Qi$iBD# z{_T_gQ0d34=E-x!Owf?ze;!`9I=GWImHC?H6Uc=;iTV!nW!xqqzG&mq%7C${NwwZ_ z^c;k=fAjh4;;yQ99wr>9psG>Xk6q~of2#76S`@hI4VKIF4^Fm(MJXY_kd_vVZ3serK!d_BDVf zx#79nzgllU_F2>VlAFt&ioC3*jXTQ))~n}JNcTGm!OXA?u&*X1w6wG!j5JO!UNJ@J z%GclCCq3_lIR4=&cZe5Jy6bEL8R6UBYF)u~_rg4u8^xLIBwXp89KuCVbr;B*;8+NR z+0E8YfsH9@l^ySG^cTijGi-=qa%7O<7CF@_>Ei*_eUa2Ag>cTDu6~EmMB#Nf5Hun377+# zPBTlNtK@8zk7J*|9mDBwOP^k(l9El-We|6)hUIO}{ zjiz1Wb?XLY>2fXm&O=~9)+a=Wx4<@}T~*CwR|6PT>Lq2cqe46Oo%ZVedrpjeaUyMn zL>2kW3H#t1iC*{Ohk`(O1z!tcYu4YmE6W1h*ZPdj&A(aar)7gAY~HVDa=k730e(m+ z2pDUSDat8fCEiMWQ?)y=ZF>*dLs1n>yfzpRMcDQ0wM)RxZw-7^r{Kz)oR6bXl05)s zm4%e7^$S1|cHbj@=B#PYg?0oMA zef6bY7u`3q(9g$>yfy>Wqs6jdJO^jeqJldhX=ODl zQlup(KL-9TCvekfkb=(I#$ri;0gq#8uN63{A3P`rk8%)S?+N?7LMq!h^0Tb&4u6rZ zc&+SFuipN`H!;ns<{oh!ja|j!Yf*Tp*H!5FRDPp2*Jc6$(be~5E2ipSK@^cV9(frzj)Y<~BaOa=a^sFXP}G=#__}t9 z<^hx$_YI0|I%?W}m&Efk-;6{Lh(TQxo5)pLdBZ0t5&@=D6(qk`5DGUjz2|GxWRR^q8GdMGqMTTYAyD zeafq(xa{4;G`|7Me7D12T&QWv|3NwZY0!}qz1VRB5={uWMZ{BTYHqzUFC;>RmL`H# z4jnp#{)zKTXG6n5plc$%Vu$tlW?aS!F!=>@XT`byFVd;Ye05S#H~<4N{Iu%o2kmtP z&vR}}v$Lf--)j|`POumAbuV#nV&K1XmnIG$%`1TaxvE2CfWCos`60D3i`>q`Ncsny zRYjjt#vqdu#}QV&n}*Z(;cl87D|%j2;Kp7nLuFpzbD6mVqQC+Z^B_3B;{j`HYl-RU z0Vs;ALY;lcOI#OeGXhmHd zaO@Ole0e_~(IZfNRRL4P5voO}u~iqNRl}8`F=6WO!*0%^NM@~ERY~L!L?tR4IDmm+ zZH@fd@r8H9U!pa@3BiUH;DtsvikbbYlXTAGZec!XTCdkbtWSshI5ey%35-f11v!37 zNyr*@$}>|s7w3#a%!TNbD3b&7jZ)L3NVBDuxyf9?5%B}(_{u4kx!;~%=X%@HS;yeh zY*kCzJm=nPNSEADQP~fDBh-3fM18>#7euOQr`gyp>eA*Z)gGnjbqc`A)^JqSY%Byq3LhIJ4kbMkkOo-st;^_fsD-sV4}v(kLEVsVcUsL6TkC+ zi*j1G*ubBS9LOUnVl9zPE4@fx)+yS=lX-vm{f4-rjn2s7bbPcwgPvB4G(`VM0BoQ( zni(RWxYEN4j_h|ZNLv!KQA4%;_!tP`}>VXB+}gqc$XN}#a~ZCfpq#UQi%WfaRiU0 z7tY8c(&=F?Z3e_eh>wro#uS@+)aBgszbm268v(A6-!DhZ127ic4pTkfbV!`fy7Yz% z7b=xD^EhMm0}rCnot$k3KRUpDb1m=NOkt z&O6_+F`w{Z_(y!d-q9zYgZ_;B``XK%2R9_Cr-#yyCYB_x%P6Z0CsRm@pViy_hvXAk zk(c`~UEH?!uPc9%|2qEjbENsZFHxC7=S#%SnURM-i45y(?OS&%nmN8Y<`TVp_7D0+ zN6}g|uZQ*q7rr~sW3}PiyDb?Yrx?oQGhBY7wIY07o09?3m(O(mT=pZ?sdj>((yy1m z$3@8oV4t79e-I51xQu+Y79By07gvISfL(W9fnMbFfcsC2=|&w6A5S&Q@wzb|jZyt+ zcA>t|X%8VbTzkFrgUn$e;?JQl?dE%P;SLQ)6CM_-lrvZ9upy^D&l}}RoC2I(BKo$T zM%}BQD6Gq^LZk(skN;zU|BO=lHdZmgYKbI9-TwL6OgDr5g zd%;yZdY%~^=M*%&w>G-!Kk|$)iD%h|@vC^8k&AVAoak=XPBJuInOw^6C%gPCYO*_~PS$CSgM{`w< zZbp~o$cXhk3=9;y4p2b!D)kQ+B)$uqXD@0S2PIH?(xl+eSj|R`k{=7ncLj$dB|rJB z+gwKLMfZ~ScLhnM-uPGViePt`VtLnUF0p1vfA>t#W8|F2%ZKf^@35AB`h$obV1>#y zDG*MLSyUWrwC<+qIvn>!!qces{ZH?_l|}YfNvAq@e!(x-Hn@w4;U9B8dME&owkW0N zxAaA_7YHiwq2c1ZFM*#0%cDA#k^S`bz+hX5qJ~6S_D(XF6#e=YaVLGXZ)7Q)S@>}F zUJeRH+_=_>qFDg>gX3W?<2nH%aot|7xnz@U4NMQ{FM8%y`)N}QQ}ysjktz;zu1 z*;ISM>7KgmMttCy#1|TZH!w~v>s1VM{nV4(fub8|lIhRdWX=W46Ar?<4aL3%WK>Zh zP#NM*oRIQ$xIApHMC~xCcNgLg6gMDFr~~xm^!c44{`5lQ2cuKbUf4ws^~ZfVa#i_7 z^F=1@_u1ma1+-9mNZ8>3V%H*)87g>#owGGzj-Gnl@(*pujYA_sHe8_$=u`h*)r2k2FF!Oh+eHM$bT<(^0mW#i(~1__kbEvG4>!x5Ywvp0gDP&2 zrZ94*UI9pD{F|E)_x=-wE*e^U-=v9<=Cz#s0n%!15mTFr*@i6PK9RYr$bCT?WN2Wm z{;0W=sjQ>J9HMpq76KAcx<;=8M@eAEBQ)8vsGo18ss?FfaUC9`nYV=lW+SQ;L`LFU z_g$q=JP^)=kGq!I4xS%|+K!&aO z|L|uBYIeDNhEaiIn4DOjY8=h(@FaF)eYFyVw`ie_o*yb-S~cI+Rq#jQVg}4&lxu?c z-~=a>-+?#ErM@*C>`g7dyu>s|@JrKrUaRab8h=|@b9*TyZY4f9p=+?*g3UyaG3DSn2s#Hb>1C-x;Z8}>!Yp(bh*}O3p^_{LCb2BW5U7a^P| zr;f`L&iwka8t8Unb~WbvgMS7o`4RuS*h_!B5)w zcu0820CL;-?tnr{RL{5Ax>jHhHUM28={q7&(Pb`{*$;@KG#q01FR{9Hk&HXe+Oz$D z{mk7CGCcLYr10e6GDS-6p>ufrh>s5^4{$bdU1TKf4h)_N)fK;`D!!g(X3&RqJB%<< zB;^i)kxIlA@yg=43nTs&g##(8L5EK7#OCBr?6~nuxZt*tYP&1(<_|$MUTX}gG$3th zG%>gB*yCl+xBAF}_=W%X#e3YH6lI9pXJ&E-&6;0#lwsh$Ck~sFcwlgo&Y}d#oC%E zfs?Xw9iot^;+ypP=~&&|(7$mGr>PSbU^|t(;50Xsx4zKchol67RXdjZ|F?Xd6D_`3 zjOsed@Nf#vekKPXENajSWw5+}Hz$;aj$}#WDf^5{-oMz*7L+d`rOq(e8 zl{iN0R<3A^f)ae89#sRpUx5*7xUH*sn~^Taf(AL5S_bN;iV1xPZbTfqz5E?Lf01IL zIkEye4ME}auagT8JOjl3T;jX4vd_Hv-G92RIZZ!uFb7YO=#{M;hqO5hI8lsZ>%&So zdIb5So!rKCF=(Kmi`02)>Q#=}2{!V{qP=_g(HNFxrKP6ePG2UPCdc$-ezorak14_w8Vpn?dayx=14Xr5wL``Z}z#UYv3xwQZ1>vY^x6-LTukbsZSH z`cOv0ZB!G1!e}JogcKKW{lS~XE{+9~JtCFh9V2`c(dhHmW~vawNGvgZi{PgX>$hW} zEI)7hCyfxUc|y4moY83A<$a*9WMeWeqBg@)gT#t_0-ES80gxsgS6y%gaPQUo_wUDN zDFOWGHrsb0b8%EoR<<`W*8ef|{m2P&V^xe;dK8A@AEfQhij+|y1IykU7oy#kFt@s5 zQ3`sjC@Bksewtp?$FE*xlays4ME&}@%-$=#FMW7Q^Onr<Ba<%563rYEGR?ElN@Q00dS8;?H>M6z2>vCJ|Sf zO0eU#?mNNAwJBAYvu^L+%t=Nlf$+^+NX$mBV>uzD@0|{3)i49ix~;Oyq{sQbh}OPc z5xBV@8h=(!g>@>!_tdzxFdx?{QgXa^Z@NkP$+bJ@JsI!gdBf>g=JnGkkq33J)6ipr z6Qm^5%b~-kQ(b>|5u_Q*X-byL5!(P+SF4tdg2hVMm*K&?alk!db4#*EYqT<;@Cc;? z-!$3Y5w#mF=de1TQ_sDZhISs%|0x#vV)kP3N{V5|9WyO5RigcVuoq&(boUXv;&xX+ zvh;wyjh6+ZOe!EWQocu&L*I@cLFgW65lp|_=XzQc>{TVS@MycS;=0b#gTQuNGZTpI zohFW?b-V_9&CR)b|A@g9NO;A3dUP#lP`JJ2nSZp{ys1ln=Z{^XID|7a4nDoYSo&PM z_Rq!nbVd+#KpEWBF(FU}KFw9Tt|y*``a>XZAGNVV{NUo3+Y4D&#nyj_p;XV0{$3~4k^9G2%ZDwaP_Vd*tNQ5f^)NiTnC|< z14zhCeDwm`wloFpdpG_>*$TkMN>aBokgLnz+2R6FTa-jYi8g3ku|W-*)~_t$y-PPP zmp>TU?GrJ*e-_0OoKG=vJh2KmSsOs!34u2%iWNV$%{m&?K)7 z4846^S0N?mySy_@9GvRlb>;oiK6F|G?iB$>t2MX3<-7d86x-b;^4AH z0V$P<0G4r}hcKP<%mD+6?_e-;jp{>FLK{K#FdEng%fnpHSRW!7zvO?=7*k z(+U;ygG}_`JW@bewCktgAJUaz7RzcL1xE~oSS0!l>r);Qz-x`_H0BHEaslIu&Q|1> zrlx14NPtVv(f)U24!V-JP_$G${3cAlFDX4Lc-BSB#!PeWhoo|Mhx*pzKo-~a8qctf zJGv$~^xi7N{xpOtIW6Yxgum!SV~+1o>)#;wHEN9X($v1;(#5fYm|W|J`-nfloSta% zA+;#+pL?0FK5bt6#GZ2)9BMe~=-+>&1ghWZtp)`>M|shSx#!-vJ8I7=m0VMeIf+gb zxB9hIq;8R~?{*qVOavVJl8?9OsJRKf`e!i*Z0K zT$r~=pc9vuqoxk?O?XW7xy0?80DGE}cl3sR^h5jAm$h0Z~FQY;f;A$>3%!^%ygYU&2pL!fkp%xr|`Uw zq^J!Oxnh&APth~;%;4m6Z$&6?cWrkL5II@A)~p))=H%jJ_GIzEcL%-d1@d^}YTx!R zQh7-*pDeGiA(afP3lm*c^Q_!-v(%0NYZEb`3bEjXQEgdprvil{4!X@5q|J~VFY$f# zAZveC;wa0 z4=E`}nTc*^{w7kx9RMXi#&tNK9deCOd8p#1ft&* z_4VH&7y$pLV|^~gdSsDlV#?eRArs`-!k|8@qHl@&>aUJLEA=Cr>kaG_ME1#?#J}u? z>h;Q4u8I)1;*+NI;K^%f_cpik4wqYx=Yr~9x}AtixKoft*_YmGPiLhv|bZDz|VD4qX)+n#g%%`kUTQXRv-SI zo@3Y?egxRJ_;=qUSD(&~ZL78Lj}NvbxxOOa|Gi6g8cX`}j7shfOgzK)NT@Seo@kIi z7=m3y*mg)pv!8^i5-gL8-}5$ESbZL4Kz0`9t!=|UFRwdRr+41aAuV#He+eU<*Djxl zT)Y_X&vcV;5)A~Dd>mk&2J{ZfJnn|*vjev%BkXTA3NB{$fPnpuRu zTe_KBWW}GSAd-{kw*Nc83jG>bl=ISC0li-Y1ZxQ6Kq@{^{Mbnh~z+ zf498N%((jj%`k%HzZwepN%6rQx$AqA&-zWe-Mw@2x#IMAX{IrA){ zb{gjKbgR%|$>c^BU37&Zb|P&a{)C7AX1xsreLVUmb`O??j<}(1=U4BiN+qw=&7b3r zk$qty_7&B;n+}tff9LP&VsZY)z{_MyeXI(;I+_Bk@xF8|JH0W2rXOPmSMhWgtz)GA z#*6|QUN~&+|NF-8$d)`ZE2U+4zV9@_2rdeAO=9WG<>_O-S_&LnKQQ{AKgfIcEfuVf zmIB>V9WsG%KQtgjbd@mi?YbDc2OLB3_t>!zTVPbj{8@2Bt)gY*Yhg`>qnZsV`s)k> zqewh#RTVhGsA|Cr5?>6ua)MtLvFDo<3s>CN)N7BC6fK z$D65bhkrNCS4PWQBFF%!Ly>QZ`F|f4r+>JIu>NO=9ICr7?2F5pN5JpuFTF8WajU~- zKXn?_;52@xoeuu0UVMjeDrj`P{q9xb7UO?En|E09GI5#TGHVW zy7uLeq}a0Ezh--Xqt;BnX(s4X<3W05Py5tbLMVVY9IIHRJosN1UUTUC_wC-2EdzvH zbi80hG-hoG+1^F0h(!d9cI~}Z4 zwzbLblt4w29ruZ1GZsPBe~C&I>SOhv&lIQV-44=I@LxFh=gZ!O@cDPR@a1ZwriI%BtRdKXYAqA&Z&;UyOCE}ffkaG$%)w~M&Kzjh`uq{?_|ByFw8 z{qj!1Gae=_SWtQSYWU*m%3Xy!y4=QFIZlc&<2CG)LyXc;&@jWw_*V(3op*xN%S|^o zw;{Y!Yyg54wQu(C8Eu;5Y9m-qjmP}mK?``%Rz@Qv(uoLqrBhZeiyLA8kZT5B0?(%R7eL-=VgZbP2e z^(LaX0`lpK&BkBqz#+o99&1DNl4bU$0{>4*tU=_LI*Q?*E=?OFGJEG!LoI92yr^FT zuU`mQJf44zcN*5j#*2LBw2=0vU!ku#byq23=c!e8c zk2IZM46-t~_h0^Ui`YGWbj|y~y{nQ}=JZlLfu0-dHkdxJ`_}_#ekieC^JtTvDN8-F zi~eVDp#4+V=bdQI$FAfj=%lMIb^(x;Y|+rYPpa*+{=2rzWwwdG^-g2~?|?`=9i4bqHjW%@Ij=rP`gq&8vRl7(`JRbPn=$N>1M%YUbTpsvJSqRrKo>&vx&n!v$@y6b^I#KHrB^<%{IeX8n0nfJ&-R7Y zeq7wCOQ@0Xo~z%hUv>hwHXWx=@UPM5_m%8ZPJ$!$;qD$xgzWtn=KNlHqt{zv*0<`B z_trFZ_9uIX#Dhn5xvScgBqSEu!PKI~LNOg^G&)Oo1bmSopd+*GSJhQ3!EQanF~I=S z5ZltJ`9?+YBqXN&0jsQlmq8fAy-Sb=4tUi{ ziJ_;Wx&A2`qRGMWwlro?R3S8iQQ@F{ZHE>+7&R6iv3pQ@N_bSQM&`RbiM%JJ+5K&7 zNwegWECm!+Q0&Uq2>NcVhi-h|?ZhC=Rrf9yPc_y`&zIkLyGgas;Y#Y^@Uun z@akU?N4lnt?y`TCd3>|Q9QJ;{mvHqs!TzV8AO*E7A7(rGAIy`ZOYItK>{(=6s6jevf+fq=#5K3DZY6w7ld~0~L zYB`J*q2*4Wuk8itwW=+uE=608vGkAcgb*KE1g_ud`-_NR&zlz_9Zy!D=jL@CHNXt6 zAJp-mz4X9BVRM}FxcH#+J9^qrh)}VRv^=0QhGKjq(G67y8d;}|r0ZKoxl)eL(tZ|2 zBXj!aM7Q(yX1e0h7P_~RJhu`~w;=9#3C0|j8}oNPtaxXD>_yB2AreOKr9F?ek{8WX zzA!1t=kaXf#d7nb&Q_iBY(7AoI#bV(4Utc0JM~MzgG-c-h|3xtAnNEOV2S`Tj`)_E zzyQya&uND>jK-h6ZoQuz(OCxK`%~v4Z_RAtu59Y2w;bZ@W4|cJZ1j+E01l+89Hja; z)TjHB9pWyK7IkFaEhGt8SrAhX1to|NnMEW&L3W8sk{Nj#{Xl;Va?*&uiubqXOVhB% zepeJ@NtvwT7F)C7dtB>Kz#JC=ZXZ+UH8y8<6ONu%;Zf6~wZr!#W|5<>hC6uvpBEF( z2WHl?z1}>ta(uj#GwV1h#dloiekauQ%$5Im)b@DpfMQ0V$U+d6M?_N6On6g7hL^ou*z}dZEoIO3Td;*oq892 zBqqRLUT_oj{5}SL%12wv^C7Z1dq0JjTx8q)fTu)E%;8*YTig5d3it`9gl;=@&Cu0D z-7h1|axI$GuG`mwqfx22WE(+Pe#bL86G7ekAMPg0T=uPbpa51)GSysL)7HS_pl@Rg>V*(0 z@4x5YEFH#5tEoYfhY98p!FD_4j4^AMvHXAx4s-Nb(!ZgKuod0A2*IDQ>v*wsmr>_Z zou7k?Or=x&A4jT@k#5q|Pv+5elPDC9#$;0G0bOj+E4;IA>R(5#8W(>3ItNm#j^uDb{jo0ntT&>5^Drlw5-D@0c1246w4u+rv#1s{O{5H`=C3WR%jMH8_mQ(wbF9;B_uw;A`r5{_=h_?CO zy!OgItc8CqY*McBBa@_~QLz{c$RF+YN<8rpieN~>ki?BpYf`AIYeZGTn+&|s7xw(# z1*zfIi!0h`A}IO0kH7RsZv;!eXuZo|9KR_EHwNzEK+7~M9wpytqUvAv1++5$61E{d z{ihcYnwlna&W=NwG*Z8fOf5j9E|6qUl56iRWHJ)9&;un9ffWJSlWMkIn5A4jcUo(Y zpT~acz7U%obWaM2(GQP5-sy>_jM(Dm56)~OjNng^WuJKRyZdQ!WyS|KqDzN*m*+Ax zi6Su=V}2t><0@OH2LyY&?h6$vJU@2ymc%cONO-!6O^EW5IZ)xChU*Z%7>gnsv7`^Z z)(KGc&8AwOsk57M`gAATd1Pi#;(+~c(8C|-7C%6yQZuZZ{Y|;U?PXLpKa2EhAVp@7 z8Cp7wDvDKN0|BS&~@jUUo`F`9$ds!mc z#?H;c;4p%9hP5qn?Unw>gv&SPjn0Kkv;Ci&(np^d49j_u@74W2?v101^ki*ejN=Py z=TY5cbAJS0xvS7#l9O@2zs0?4LV+?d)>I_K1UJ2#$zCD!OwIvK_0M~gx6O1;LOjM^ zlHmMn>T-RFSgd1*Z{9u)?rV|8#<;6jl-uC_8E;J2DX&%aaQe7 zlXMQasy|({-n*lViQX%_M_+H7|G{7hx^2~S@!z48Ud7Uii*M~$KV#nV>xbbVU)#!o zwj4*FE2~H29fCG$7V)*5@Z(=8=Sa)AbVw6vLxuM!!a0PLO_EX_&fSe(D?q=tYo7Pr zQIR>0b4P1^9J_FeD5wt~5KW+OhL*Q*%{*=+M1nB+$tZ~0z_1LL)=0kktVb*7w;$L3 zptR(nwx-?0z~%m!Zl zK;pn>3ORB$ZK%QAHRrKnFP=z~a2C}H8%1Rv{1eoM*=^#>=12g!takk%kCcy0HRjRgu2lsL%LW0cUhIcOu_kJCVMx1&Qk)_+bCiioEOwD)x5PQX+rS zKBkaX&UrGVuh{l`@rx1+o4>~1fjQr_-=^P66k^_XakX5I^NqNLhYF)GSIXG1+lhDI zYdapDPrRLvHn~vUZP|L#FiTJy+UkiK5faajFNy5raLK}HiH!fJcgl(GmW}t4k8nom z`z-$j)bCD!f#wjUSl_Z@Nel<1$oxi6sHCIK)_uitgw*h@%xNCF5Y0; zu0(pj&A_(mE!xv* zy&sBsQ{J-w*uZ}DTCNWpMgIssi@H%v*gYb@)#2HnZ-Vyv0W++mN-?Xxk$Ddr*REx+ zaQppesWkF|>}wKdkLSg2vXGY4cj!r8gi{l9(u?t^ zUUkm0Z-DA(S~!2c$b3iyX#pH!r_o&S@c8*k=TkOc#X$B9XJirgm~=E7=ChurUQX3YGNmS;dOR(Fak2QBm{GzX2g4wvRju6qCZ zsl-8AlF3X#Ynzx+QIb7Oaybf5+b$gWPGr!hB_R=R(`ws-a*W~iW5M0^X+fXmG!{+( zlp)Y)j(nK?1jq>-J~X`Zenf*xT&9-e6lrJGvXPNMaxyqnRZ<2FTVr3(riev!n+KP3NTCm})XiOE*cI;$-z&9TFR zR`Vld&NLr{Q)Q z6;hK42EDe}$sJ0IBF3mb)7>`eSW~Q9ojHuiijPl~Uk7#h7&bHxymQXfsWB^^Ap%U{r-Xk* z_m&1?xC{4I{^;yib3Wg_mnyxDfz6Sp6Z3}e48MD?;>e{nQbp!r%i%k^qxL?ZaalRv zXScP@jmEb>JW~%ww#zpf7_X8TORQiZXxGG#qC};6E&axw>V44IwUX-p(~Jc1KvW;)7#Lgv3FkPW8vGC-Jv5>Ei`B{%;id0EMgFAMkiWWtnMmO*HTK^1{suAqE)J0A5(Oa*NV@^UhAPa_D!_GX8k*lufvNT^IPgTl8oRM2N3c+ zy8>oF{e2Aw8|>B`Zx2G zV%#Do%o~JTF!be9m*Y5voZ+5x2`fc^U6SZk%Lqogn~}71>=kdeC4_@G2>^Rw_7;m$ z!l8uwQt-1AUN{EYNM8da*ip~d0q)Jn9sBL9O3N*RStP#2c)x9vlQJ|HNZ6 zaCV>k`g8jb&v|lfchh$hwOS*)*5!3~B&yX~czZhiZbYMgezOeUj3V0Mndvw1|h#eOhJO>hAuL(3n=f+KO4WcVkboR72bC``?^}Uk?Vpq7qDoKjGk(V=qik zRJrM0Abq-Zu0Nl7_WCE}X=sPQ|NrV4d1X|bOVS$-_a(*X^P{EcU#M|E&=KRHW1gV- zrgWkHnYA(H{*zoC$4es4Bv3PS13`?!5V!g>lw|)Ud%n2 z&&-bP=59NB#q4#I@TpzpEn%?=%Z8p_y+J53&>x;rO>{V~6xV;5gixCPDy8d|j@pmG zz@k4(D3s9^NezW?9Z^mOmzXMleiHbK?$<%7oW3>u#zvBV2c0?)l>B_#!@-4FnYJcN z^eY$^u z?>~V5@0HERW!P!N5;1aiQdmpG(pYs><>!XN2w%j6#t}!yCONFOzN*!GDdL*`{Xr|$ z$8wDvG~dfh(}V>YM2TFDHe{w0Sg|8dgCdN!bWhxgHiz=3GPSN3NR&CI-a#vPU6gvl zW3?-26SqEiWjbGalN;q>8@H};xtQzf*{7%vi9B!=8_dW`HmpTM7NycO+SMldSN_P= zkXL`dPsiifV1FWW4wXQ@^n%)tKP>!Di>P^1y80LP&L~)SjP(OkECFPBkgw=ao%dq> zAGW8yJAPT;4wmY#+-{r7#mBnBvQj$1lkdOcpvEPbvGdXu4a8-!alM`q=$*))=$eMm+^rAYeQE~=ZWJ#TC=jC74Q8m_tVk%@S%0<>ucso7qExlF&$NLEnY%~7In%sgul9P7LOAxfiu5~Y_10(jWU3`7#P0?_RtrL| z=4z9j6`skz10~F(e39N6Yu){L%L0oua62K9ZaHcL(_W?};x;?-9cS3E-#@}Aw12^a zJX|9vSkM<1qdWiSx(2rZ?*tR+-|`^@3WB+$)YL{&W=e_hzXQAXjm zauwx2v#)9=qZi(3L{LH1fBRLAF!`X{RNfuV&SUSD;YTv15;#~-%Ae^X`$*zR)Y%D? zEeI3dryMLYjs#6CQjnD{)+?a;q0JZ1%F9a#L)F-!;4}ov*Q*3HSz_LBg@6(7eEjxz zxsLjX+4Vb#=YLpo+p(CG1s9K^hnv@Yapr`WzTG5{OU8#+dhtcSyU$9&%5hS1)(ft9 zUtW(@IdkPZ!hr&g506vp?i!>K4Mh;NC1o+4Yiu{veF=v%YiPjsnyDckQL;@#pK%iP zp1&zazkc8_ik|ZAbCbW#N~*Z&w==Y{=-AyO)rHFf`KccUM1#dOfzGNB~U?y!?#y_>xBG$D{Fw}Tj z_HbQ62FAWiKwTF*qj|ZW)AFz&o%G`iAS!jCHIgyX`1nseRB3-C6J}@8=FYWmdx58# zSzK}EPO=q)&={H|j+Y~0pYOAhKR4X2DC53}uE+rtisk47HQ7RF%Oz%=C>re7VK@!2 z2y+Io6ZUUqYs)Jy6s_^affrLgFKXuC%;YP?O5`gQ*S`>jM@`GtRx-(7UuH}>HF>~| zd$p5awzHx0#V`4MGZHD}u;9jygq+FITb5GnAVR$R+}Q~|_Q7!xhOZ|nZjYINr?<-v zg!KlgHsdVPN70iIx?6@4T7(;N!Mi&SG2Xm+QTm98tx=mGT!ScC56dqZU;Iw+)5`n7 zN^<;X7Y7WuCeLKO@S2SrdXRLaOMb)KCxe0Ufp%K%=QBBpcStSgsU>stqg|>g{Epw9 zi#0oXbn-J;316^2H96qazAYnnJcHz2S{e$fv#CH_KycKZ z5#v2jLU(c;S0+@x8#t?eR*WIPwSvqIHB}s!Z1~f)>^wYd*y95Y3Qhnkdp~B5_{=X3 zJW~gunzP`@d%Bas@fp|gHKzZed@1gBJ2|3hZ|R;+0>e|UUu;a@^qZDAobfXiVf0~# zymKx|WPzM)uHfRR7xLnovq$tv^stiAOY}uHOP-xkB7@iDS@$^$0gFII%icxG=AQ%mEQw;CQOG3+zz!<8w>^ z?F4vbQGI0CY@K0~~0ygBIm&Qv))Bq$Qd;luGRWPB8IiyoptE8-q z3{*GhK>&~f2F`uCEQtASkinJlp@blZrlxzu_L}b!D+lEkySb`YGM|~ z*y#NMKpN}4V)d(8v-!B{YzoL7c1RgBkjR}eo>GbDLQa5H%-6HuRPh_{Xl4|P<(ny) z>)Npxjrx+x8eJI|V;#J9i8NaJ_j36ZW6kZ7y7%W>+>)&qg>EOuG~Ef_4AkILNV`V( zT%|rhleatXr}fIJbWNl(vqC~8Wtk$*RM1AWfHis4dF=VLs6G|UM$M>#p$hvJkf90P$LpC`hff<+apJlH4GXgO%*AMBB(=%s!`^nr1A}M=?Cd0Z5!gq?3|LRZw)?P$OBf9V zy;{37LCx2Xe@XG?-qh;IMmN__@MpxdX@Md1jqTy!nA0^odMql47Ckg4ry{_yvN%&^ zaG8DGO}R4~I<$){_Z96(B1QxOq>R3d{F~Q++1hk&_dv6SzY!yI<{n!goDg~tCx)06 z9$K=Xe4(bP>{qN}@-K)pgIok34#Oj1=bz#{WVVtk8$mxvwNbowN4kQd-~6sq=Ceyi z)xAM{1_z6>x#U9Ml+M*RX|pj)Hgmb@!K2aW7;`KE&-bBM{Yxs>ovLKoFR4EN!WIrQ z)21LNT9@U=4gHl(Ar#yK_M;-r&CT^D0%@6nXppt=j1D^Fkv6yTf~~q&=B8d8*Tg}qO_GS zPqQ?U2^H`}w2+oDK>w{Gz~q3W{Ej{WhzbN)1yTBc7IEFYcbN!YAZ}p1WxU^>cC3 z{Gm<#5`G9IozAzYH2NbU^xFTj({Tdnd}LgoIdqDN%?-L{l-`ziDf0hi#FW$FlggjK zTTzxAFwcfF6P({ivXDbBw)yeYBhiI}EiK`@Hz$#hSU0Vv^EFYAM#;-d8k9^TK7T%z z)?w%1m;sIYCK#{oJ0WIlYz#x|7+_QYqMjHE5@-0((RKaSt&SUQ!inDj3rIRUJDZ3& zvx{Y{9W*TI{x0)%kNDWluFI&VHudG@?>Z?jUWxl7L1U9wJ$8iS41zkGd_CsAkY_#n za{z|Px{CA$$xS$8eeOhQC4D?@QjZf~Q~ReHr(ghDh0(Bc9`_Y*Z+;~!DJ#bMM49-b zZKwDY;uE^W75q4})_;+);LEkw#Blitm)&pocK6yNfu91y(qG=^N`%5@sv1#egjiXu zY?hZ>7U?;ivN9;ZWoN5esbOzj$qMqE!L49e-^xjX3TLLyOHF9ns$9Ybp zHkO@*28+S(&?W zB@Km1!I<&j5u2uz8AYD`F$PrqUCU-OyO$R!vtN|^>Pq=;F9;6T?4$&rf=rQbuY)}93UTzd{kK#q*-_I2 zjNxsajZb9ivWbD(P@q|Bb7TbFK9kz5rV@boL|SCLP;brbL7V3$2&K6y&!Rq6kf8jv$qs(z={ndPA2KzGxgrOEaT_HF@wEL zYK3gYWIWte`sdpKTwIi_@U?GU6gN|U!u9lm4I3_P6v^uM7R7e+9}>)@=dV3M%u`Lo z5`*Q9L*&1nOsW-H0ZGw%<3LJ)7G5;t_NJjz_fNl(;FzF7=J0a%A|gOh5mrTC=W2Oa z#F;`^#OChJJ}-{8` zv@L&Zqa$58SV(&ERjrg=M}8m^s!}z)fuD+_q(&U^C7vQiD={}oSM2F$=A1BDTcB`J zZ&qU9S_7kE5u9EV>Q|T9x3CUvYo?%>02;BMrerBYaiBAnZNl&5=voUCi?cR_Is&`= zHQ*1Lmb2tl!Zw<~PaE8Mg~2GX0RHB;<84lyeAytT;;@iv@FwV`8f)u~zoo^RWKkvGTev{Z2!tAy{)v#=u1ol^&vi6Q6x`)>uU z%rP1dA6}M)W>w!^PZ&B%eCd*8mPAia4^*FWJ_4;4L)X+uxnpXO4rC;urIpUofe1MF zeF*^s0v=v#msLWxn}mlfi@AY2hz=dLW093K2>!%LTf&^9x9Gahehy*O!tlkW_BTkV zX1Y6bf$b{wr-jwI%hP{q32|OzV!#qf(o}?8P~{7~v#sZ&t2}K) zM3fKk>4O!q3zBi_19=kwKLft_5m=Stx%}?lxY*U8AGY8Dm7KAjh#J*-VmtV7(^@Wd zhv3P{-V09c3{%iJSK~=4sqbWnSNi46#_;~EMouq3gz4gUA{uM^O&%!jDJ2t;Y%65G zG&iylu#CX3A3T(ryI(%NR>LRb-ai0*g88WMm>{4^Kyx!MVl$=+ezIUAM?}OM;XKQm_>Sq0!i}HN#-_E)|za9WVLeV5&JqSlLz*uA5_6I^Qn%P($exsql?8(z- z9Mv+#pRAp@Bvj(Ut6%pKi6X$B6T%XDjr!}ynLXgXl~MQ!FJrH+gxnd6S&TaQ>-d_FyTmq##0u&8b@6nybw%Hxq#Pk}Fq)f=slC!S3d z0@d)p&0JYQmjuOn@qqo+$hirx&hwgAtoC5#vUi;E3swr=-(?|Z7+9Y}+{a*;^c0-G z+856gg?>ga0)Mal@fvO%}Y#+2#m+W zv&|dVn+G1QZ)iwzDX{E!F8p$kDG|JAoSGXi6&I?}VNoT-dbaMP5Ke<)c>e-%baFqw zWZ{%$7YGwS~FK>1B^QP%mBaW8zoYQ8frF;CgPzkm(L zSQjHK@LW2~?2Z6|l2C^sYY{~7fR1Jp223N<+`}d&CI}pg3JY72xXpdl;6*Dt%lvD| zlL17)Y;8AwIO~VrdqVi+y-qoH305`y2(F(A)Uz*uf};At$)^@sC4Ut)HL@hE-e=hu z|FN9Qez_U=h#Gs6s5@sTx(X!@HcJIf_kP5P>@Dt*Cc-;00U0G>F!6L-QfoLyo6}8- z%I%~UofSkAO>QRt;iRR=6T%%mX=(Gs0x@7{xpWL*yg0h)3h48w> zxbouU{hNq~U3NF^y}F`WN24^uVc&HQ`Z@%xhm#|%bJ6N(i_r7NbAwZNjVYCqJ8{0N z;x~VJC`2s)v8`ufxrb63H3eVL03awG)3p;y{}O zCgvzMwJ#CDma@=r{99Bphw$Q@)*r5FPU3snh zNjBpm?D&1NX9VO#6L2oT$3KZ|v1xi^$i6pLVOD84XKtiSjO06REHE#(-VjmRp+ueW z&+EcJQh^swX6s=Y)dVZ!w!Bk`W6S-`ayml5U>gW%B(GDQ+^mAkC$K)&VV8g zvW=qm&WHB;f^TZRY2>&N0RbcThVHpKGwwH)bI&TNLRT>|$$HE;pHzt-|DCkM#Ag3@{C;Z`pWb~Rkl;LWFs}6|(VXD} z@s3ICsRI2l&V&?559(sEl+4i6Hc? zE`Zu^dJmVomp)65aJkt~eGtpXwk^8?2qJvmu^sJOj)gA$(Rc zLCD5#Bjc-Vb4wOuTr$Z<6MSgI=B{Y~u-a2>QCfDUnDc5KED}qXFsCGO2Qw~t|Kkgu z@5^;5s!YAvgjj1oPO(JOzZWCnv>A08_&TYS{6%*tGE&|dg9VTULaC{zztOA)fXLjx zh2WuTi@h&EXuduSTn(S?E1sM;6%6D1_rdGRf5q&g0cAbUg zBFJh4l5whTox;>4Qm^B~zef&TU%x8Y+w)$(em#ja)jI19-O>vP>A8Li8KjUtQ*$H~ zQI>pqVUgr7%MIeQ&kn3fRx?|GDMiWayE8&SJN!~VaK4gUIcfT%bN=X~mQb&$0xdHq zORiS*p2@NPYvrRd|=Ff!4Vy_Nl0*wq-R^#H@_psvI#JItJMngkTYWd%u07wScU6EAErEvwT}mcK$AlWV639 zk5c1dzX`Bvb044Z-mk4)VVfA$4|0&EqHzv_ynv3F7#+mC<|J|?+uWC%{UcYCLLjX6 zew2pow_hq>Y5+mYUR#P#ZDk#HB%f+aNQZjN&+Ev#xeD^YlmEz%jEo#PM23Z-A3Vs? zG;3>aW)cx02mJ%8AM^DAXJC9*u;vVz=ap+HSpDl^G(2C<-2hKwDys*Eo+M5CcJf5= z)JpcV%6QVH2i)ru$N04ycP^*Y`HCps z+*eA5euijGp!udhet$mv(rd#DFHh#N)|D8A3kfvy7hi|P-oqq46rf*`mGYpeOGs@# zNrm?o;Te$@H2#W%tYQ228+%Vo`?{1T^V$Em7QkxeHUC``AJy%sHtyV&`js_?X8vE1 zji2Hz{_>LSLs?v5 zvNOYXp2G44#ihtf6Znr{A^Fsx0Afc%qr(QBdzITvHSb55&5tc?Niq&U6}zfbDYUZE zbi$QK5MSkP+^zd`yUAcSt7O=z;kJX@`KZQ9LiifkW;vtSfSma3%y$FN#Op3Mjd|U@ z74tQak-lZ?8H!p&`PR%Sy<~XqbnVnsRaNW8goTBZY5ZXLfGWFH$Zak1?09sA%6=MI^F4WU9>+mF2@H%VNB$J;;H)$)qE!+%&G<`| zwQ+{`P*(V_){-b*0OxQnJSG+ujA{RbWRgdZ zezq4mv_UMM*C*KqfpJ#Q6Z2oWsIbsKkgUic=^~+D*&!DTbJPl2e7X+j$3lJ!)cM1G(QA+(u3_WJPLgYbRIEpFgh}F4w&WM1yMhUG$vNQ>H0E z$pYe%=W0S}9@V}hT=O0~*?rHgW6xsrL-(n+`>UyA&tQaIx+Ulv)v?zb4%si(5Ei2e zUs8UETM(kZQy2fWzgF3-Q`h*}T#6)_yK|}^i1fa-a$py&@?7&yV;FMMdJG@iS-9?~ z%gNhgeJd?u;L2a+ROHHBEKrUZ;BKA%Rat84HYGd*Pc%_b6+JGqp?Mlc^CJBAoWnOt zTF6&F+DsgY;ZogFY{(X|ovcx4?V^~s@B7v~ zL2(GezmDr6?D}fT4?hJucm-gOXHR{droKKwY)Ai^EQ|(L{mv{S1B>(H#}8;myQ!uY zrMU^=a+XOZuDA-OnUIWSqq*00`HD?F>yoqj!03s4A$RSbo1niL?0!SpkOhn2Fq4}y z*wseBiOXP2YK9oD-%Z`rHmqn{q?i>D`+^6?K2MW5gW!?t&6+kbI=Q}wiaE~zsz(CL zMe7{8Tk25%!s>NlUS<^k$s-lJ|#3Z1RnXot&U^6nMXyFVF2_E;(@>kht^4AD+nRgA7L z|H1}7zU09Nm-+G28?*faVTBmp!bs10AH>bSY03^WHZ=SWN0nxfkCp;sUsrVjNFgBZ zLO8{K-A*PY(*9s}Z0xR(9c6mUl3J)S98%hBt~N$HWF*m>-f`NYIdu{Nf8ILeX-aa- z7d6J-?sKwG%^q=w$Q-gHolLqE?e;Mtnz+8j3SmB#gx;TJV)-M03?pz5rwLcf zA5i^%Eq~y8(NJdD=FG)=xL;y1))GKwQ$yBfqv!M9#+DBG;Nz*IWqk0;CdR?8lP-`v zOl2r+&Uq0q>G-YflMC6SgZC2DqRJi4@WHzJdM#RwD=5wE??3N{y1+sP`k-4SzU}9B z6*Vvc^h}tb^AOlJD2hVrjb6->@*fv`CxKTC!ZZ3_YQ2du1R4rh^mCQiJjO=y$`b@N zbb|w1pD#M6MRh!~P&`-jvbWg0Vt9S(rsUqCPI!NwiAEUXgn=X$ZYL{KhUqt`l6v}q zm`91A0dj$de_}Ja?0-93hea3>?7R}0d8hIi3&Bk+4^Po?lZd$ZZp{yCk!rS!nLWdf zSnKkhq$GqlZ!zN@9xsZZ`~mpWPQIK5UJKF`F~7FKpm}&6+=8+Z)1M!x$Av_3g)SKf z!4WtDm+^i={psC{S{d&K*xaNN;z`3iFJD7W$(&3j3E^$nAhWPk1ubcRgp2+Ee8n`ctXd?aN?7B;NQA!1pOjsqGLPt>@WuON6Gs(vo&)y7n&Vt< zQW(PSX^3K~oUWhk$DeQ{j-E$$jNez5?B?A{7D(d*t989{WHG8_H%{bV*%OA16_b%U zI0&qxd$HwrnsLY_QvFDI^CkqOq;uwxya9ZLIv7Jr78Kc4bLO2cL-TAn3>_U8nwOtXAU5`wtRBYIxk@FUy%e1};5PQ?LqpI-{DUmjpLFh4 z?}(Rp>+iD4x5kwO%P@3_i`?S~#f&R*57N0rZjSs$U2?di*>Ll_3w5;grRBeGKYS08 zv)pa`mBu-c>HT1Do2}d&7v8tB>426-^~4L^^K^|A1HREr;CS}o7kC7$BAnJ4S5XBVI~qg(xi{ZW@SMMk)gHF?wK z2>}V=gp%wedAZI;>xQhzo1mQ=Nvr%#fwO;CgE3i7WA>FGvVB( z(kBc#BT42F5Aiok*M#iO5DZ_7{CuMPrD6et`uMnr%XSL_`kuZ}un^$kr?8rvNkILD z+Y^iBDaDT|IeV7fhD}0}o~a+?cn|i@4eMQ2(5f__h^PE8{AiMhtT3e1)WH87|HapY z9h=|R2ko&`Kj3>*>g+%FW^rYCdv-+Ns?IZ&;o`FRUH7c6v$Zl*2Z zvZhcQVK>n)-)gyMNQp)J<>#;(Q9F~Fw?8JYL9CfJ8_CaR^_t_ntM(5J7h2AbT{Za0 zP8B`PIrBw{*1IY}D7sCbnz>Qmq9w@rlFDHE9h9gp-Ai%+8a>3ib_z9xuW8t>v-*5T z!QVtH0G;%{4pVY`pS<$C2m7QTl@v$5f8^J>y_pY~{0zGUN*^+RfgD{Hh6>L>E{9%L3KH4TIi9w#G63a_3pJE=-3vhl5Qjv>p zL7ZuB*~Q#t()H2v3!}<+&X<~gNX4)@k~r^5P>@EW!>*VpN1c;z-Y$_3JnwO(?Q`3( zWg;q{@K6@vOFMLNb=_m8ZJP+4#BxWD;^DPqhIxa<4v(Js#}KuB_CL&0iI51ynU;D% zbla6E@thr3ys1^Vm&`MRIGYSXd z$9bF+Ut-{Vt)Z)Bg=z79^arEnmrS%X;W2L&(P#yr=c75WjJ3X~na8XekQGolX+EX6 zrq`jt#3D|Wi}UJ+e#z(Y&x`TDCWPA%&~fXb08ahajDiIEFAj#VlXHLj{|Mg*og5_C z%lcNrohsw560p!9#uHZDp#QTw{oym)Rh-WSvD5ii7P##{k+WDn9~R)e_bf;l3Tt3Y z1CC76!za$w}TtBrr* z0@}vrUEl1>moL*QD|c(VEQBsyzzyu1jr9Vl#cGpzhu12&$q~0nBkyTmsDGI&T(`DJ zwxN5AvEqK!&G{{dLW;_*AP_!O({ zYEBX4Bp;Jhex>XR!#+rz5*h+$+y+Gxzw>pNgIL`pXn!MO&`AuOP;3WN=I4D1`xXR% zqRnaJ-2LEl@YvPWHECD!#ISpp7fVfNEWqvNm5p7)Y+&#PI|haMXDqOZsdC#2G&4)g zoJHn%ikY0HWhRMH_n@M1AenQcA)qg&S^Eo)jFX!bq{U*`WJx4b%R0q>&6ayeuSNZ6 zv*#+AdZ`-;ybN}EV~ODdfNxT@b?MVt)ABfvWQGdOEx#uOoipa=v_Q(b=OINm1bJlr zrQKP8nJ*%2OHuieXA*s739sRXE3`d6o8maG4?&rus#r#D#TkU-S#(X)>~QMqw;mVf z#8M>GS0nAop8fmF`&XKtw~@_cO%Cg}*!ZUcJV*vvg0LeIIf+Lz!$ z;U?p$Q4BLGT5~^m&M+sT;N|62H--l&64Mz+ZdUI|nLQ;QsvUg+0Ys#xpFVRb6i)VdBdwS61_1W0TOW9iB6HfNa)f7zS2N>a zg$NxdMjP&0NYY`dJfWq0i(}q0XZ=n2f=N0Nq4mvcSC7{{WtHg<*LsY0yKY1L$N-hDO6Pi; zZns>nL!%?6W<~eh?=HE#E0N8iK|S(xCQhm5piiIhzKF0W=+34bEHHenU0p?!D}`53 z3|yTEeC%nt6TaK_>%hu%EcnTsR;8(*t}ql@DJ2i;P8Rsu^>eN7#fYdxY%3J2pNV@K zO9gOay{Dni!=~^2Ewf1hS?n%@_>R?evZmz@xN4R6VyMwHxeY$iyNO7Y!`+IF;MG7_ClhF?K_00 zdNlh?sTr^IBQ{BN*@bM>-T_jnGL~9lZfS<1%z8fcrewN1UpECfN?3yyZWS;lvukTW zC=3qXkDu!q92{KR3HZatl5za-r87_Gg_fCbYS2%WN>Q}J)1dG5wY$eWTB1gH)QiXC z_iQE#m2Dt@Jqin9wHZ}I%$TW3q6xP2-Xpa;FXSYD{TVL7k~*|g#fEUE(*ZvA1BC_X zM#(rwCo>SXE;vo}1u<&BdlA46)SWCOqmDi9;I1Yo`sewLuD+y(%#zb?-Nor}eGYl% z`Esh{rF-U7t9o8KF~gUpC-yc8Ga;`*Y)fM4y z>9YvE)YIO2>LtjCiM!W!CMJwNR8%y!wY5Ez6cH6|uoK&@xrm&2y4#sAXCbrj2r?&0 z@7J0$>Q(}7ykigMPwToegT5o}TXQUde6QB>5XG7wAysHJ?Ak*d5M3LEQmidYKNqc0 z?in9Aar?;Hvgb7orIk>16KRr3^R&Lvn8i6P9TE!lC11pNEKUpNKMtqi`|CbK*jFH* zc|Sifp>)vM|q@)}HUj zo&pI>tlf__3x3H65!Ew|B6r0i6cdT~qZ;Q1z4UaWiW*%2+5UA8mwO z**TG1lK&y=J>a?izCZ9cX%Y<)LWzv5vbQ38?>!=WW@c+3vPrh=P4*rMMfTnyJ1cwt z&r9|BegFUeeN>OsYu$72J@a|aSy*bMrvy<6SmQ=bQyg7G-B+zorQWSKzS;<7WQp@T zyb^3P-*;)(iMp$sXZKs&veXAEa485f2k~aPo~?U{`uZ$p4GBPDppsr*cAP5_-E9=+ zpfa9+zProg%6d5Oe+0k_A7!O?ue91S!tN?+*%7(zI^n_2qxUnGxxdzI%9O9q%q4j3 zs_3Jnum*_Px4axqyfAuFfA!byj2Q+2Gd3yWk?|2C;Vp(-3r44ElH=oJBNLN~d0r@~ z5BT%vYS{3XBMY2MmtIPx*{Hbyz8Jk;GXtneiK_$<4WrxX`0N#90*Hx5<-IcuB9?iv zZ!VWD$DdzYF%R9PgKd>zl8DQF+NQ^~{n9*4!p zM?*AC={D1p#M};e3Ca!%9DmVU)U}l2h{O!NQ7n#Hn|BX5gVIO0dLhP0QcH6q*iGx2 zp^)IuIK+LEH$W`ljj5Cx2%#ZBGg@!-8iD`p!V|&VLMk3xk+XGw@T9>QzpBs4QtL~# zyaqZL?aF<9Rt7i=1Z`$mLt6(v@|q}4$f+7QS!heWKZ-Tq5|eZkVW&$BfW^VK0m{XbB2O?8-y%e$(wgO|^>=^QMEcAnQ<8;z zg&QCg>(>!@*@DcgQfn0nuo@Qb5DFsBC|Gnio+`$RfXjEWFB+zvc6VH3?w?bb{CHNh z%vC8y{%Oz>lDEW~b&Hgg+dssMKBBP=_FLdRVI(||p(_;8NCDuTLR*QOkTBw(C*8|M z*M#`h{j~9?BbOcmcd9eCMyCI@@Dwa?#-E4{dlh=JJt-ySc>X109fy>6banfaUNa{P zFGMd0iysG^p9}oVV>5-s^O1-RWHM}xf$C!~Yj}y*WNjd?gO=5LYn~AaV)3zDxcKOt zap+yL=bpZ)7ThJ1?DjWU%E;p)!~&wz1g8U3t=9&!G_QsF%s&QrG-+O&$I#OTZb?W)$Wr5@K` zoEQ9g4}gJMwa?I5N%IiSI%Jn!-N=TV-T<9d79U??IKi-?$wM!yJmka@7xJE5DfV8Q zSyxN@vez)Tw+p{jc<)@R)e6JXj)g`(Uq1=Tewk}F$*0J}n|ROsF{AZY!5~Cv5Y^DH zTVU7X4aBwA`ZCt)m*v;iKlV8C9WXzaD&=GuuPtan0@w%|r)MDfZm;@MuOspuKM5cV zZ;J-qY)DHi#+>TSrTLDS0UNw5`GFCQ(El6{4-fw6_|VW>0dH*G?qpHyz}VPW|CN=M zQ=G(2KDVld>1$Vm^-|uvxJ&n)h%XBF4HCN0uA#AAXzi+}f)E|JhaI=)BHyBwxsOvN zzajW2TX6G(j~AsZ?xz*28%W3rz{F|I;s9F;Zlo?VQ%LC1gJ4Pj4G2KN51M1007!yQ zmCLV0eRzV7e6{_H$)*QJzeWQgp&|xvy5UvY`ec1inV!ze|6YsfLX18BD zNgVaqCwmh;VB@$65$owK1hsNi6E_d{Eqy|AGDad*+)nx9k9DyQ14n4u3k zXNmcUeU~ecaWM@2M_%o5#l$kS)O#(IWbLQ{5eDo?i8_eS?oK9)KnyM+zl4~(?8bq={&ff;DM*CzBn6cgB(-MO+UY zs5X#|$6d}$Tq@;PUkl&@~YaS02mfh8+4Tl z5AeTT_`G*LE=?j59k99=ACeVJK=IB4I+Rwa1u=>1rmT1K5p;dnAFI)+NB3@q6Fqkw z0}UXU5V=PdVn$L^r7#Oam_|)jX6Y~>EFeg6_+57Q2~XIL+_z6uJh(V?x8BHD=Dd!) zdNsBSGFTzDKh@I^E)|<>dxz;7`WmC3`&*-%pGr|5PLG|)B?AbKE>|}po(;0PblE9D zbSzoCMyPa%eHCW>4iUF1wwmk`QvWNxdByG;TuT)M*aV)99y|KwA>v zk(&I<$^#sHeu)TkLaHh%vOijE#x z<%OJw*oG+(J+_HQcDp^rk*IdthkFi699pAF@A_AG-!fI&LPi-ckH%YR9A$JAp5g1K zS|(S(!;j5@`NQYy8^HTOvg7;OI116juB+pY%c<6fD|ZuhpR}E3(lBEUI$u7`_ajTJ z$K2>5`!4L4v3^`;-Bt>yCBof=JAm*iTWC81*v^mCjIJ_sCt7B)a(TS~K{`zXV49D# z?6{&hovkx7h{EZ{7$bAiEtZ1G)1CpEs}sGstrTdzbMFE=g4EjFMZG&}P)ciDnE&)c zIi94!T}jeG4GUQg!njkmq?WT?MW%!D2?%(9n<%mVZD3%tRd@5kKP&+B)(Hx?TPJ%7 z2yg=EZt2_bv}Utg{Kz66PUBNOJz_j4r!)$A6%CMks`7w?5Xq;?U9AJ`6@vKh%@}$H z>x8VaCr;o~jW8U!hIc;e1G=DzfEE}mzqzTpzSw^4(8iJgQB?y;@zWcm4Zln_UA!vu zmE&8Cj~71R+Lo7V00<}e^TPk^r^F3N2;JRT4qg9ZxHlN1ytL`qXU>Bp76Ss+$F$i? zuRon1L0I4?Ocy$E5rYZ!2LLRr>C7P2TO=Oa%`t^;>u6O^McaPi&21}LMSv(ZDW`pg zkRH%#dxG4MDnOx#>^PVq|EU}<$p^kmkcrmw6ghESYxU?liI|;BTllmnNGrdlFTm_r zI%cm9dZK0R5i4@oUVC|Ab0|G~Mu8+Nx$UTyKc5MjzH&AAK#p1;^1^Nd)&$ZgkVJ4c zi1vPJQGz5tayut`4vj9~h8sBm%wmNSlM=q`0&+fRHu5hSofU3tFJ22CgZ%|N;CI$Y zuwwsfJMS#=Z%D=`0;IPmgSe06v$>z&#(A?sA0o%DqKuad|Bh?{KcYN-z4N%bSjA?; z@fM_a`MT?un_X?U6VA+E`5I|>a?(5=E8MI(a6szrYS=*@`Aamk$awhPn8W*(vzMr- zE>Z1QCY+_$$m~@QZoNlCPc=?Tmf#~YH=9GfmbY9k5% z_=d^bR3lgTP2^iy_3Kc&!IkK&P68&Nax&A?*^_#&UijihcD?gDwDIYM7IVbVklAkU z;Qf0%SEw`Bi^)*cIbBTR_yeuDq{RNe=^sPQr+`CYop8%Hz4U9&_s z&ob}b!Z7lT)>>6cQ8jj(vRT|`^P$(h^1rP$FRCBzw^bf&mYUxf*6hPwWgmM!OzZUf zM4~V4-j+)lIx68rTr__vf=zOOu2wTo=j*$Dr`2Vi+@0;XvgRMY)3 znu-)bPo6^FIiiVOuNW!AFQ!1PT5%!6g^(^)6SFN-X~od0Xrjao{jzBS9DY)(A1a0KbNG^HNQo7n38-rn9v;lyTVRs^ z9rp8Q)@{@ofwGwoR;_GES&riBY~EjFuNt7W5Y%HT9m>Juv72V*IS6!hve@EfDQ)emO%t;4A+InT zT+uZ_J9CL>-dPzVnkMJ(aD@(iozNG=4jM*V#M?mOAu2vTZG3GP>%qKQ`(?E;`w??P zSE)yjJfT2vZoW1Vijk3`@>i5n&^^&89vb*(I-jR{YCR>c@df8OM#{&4M8Ak; zzCC!gB1DEdqYb1BqCWfb&d`TUsHXVzhr<%~qH}Ahw`*K%2MtU_cCtv-Zs0~^#j|ZI zb54yk;S;6A5Z|T`bAwv_38rrAx!HIEJ(zMVcUjWO2Hvi2oG;iqFx?!R8JYS$ap*FX zV``5u1JjcwtjHZe7cG`MHdYI7jpoh8GVyuFl0-bEmzH)1KI&cY7d-ri^ zhq0MiFD38#Md+C#UI96s?FYpX4BEL+UR+gD(r}{w7f#cr?c zmg{cp{UQ_P;{Me2N8 zU>Ub|Iq{SvDy*(@k*u>Ex z3-`hs_W{c59x$iG`+duu&-4oH7UpSP=cGqAEA7TCQ%NQ3gEDZidl%1$hDg2T@az#(eJYT+1by1{^rBalcl&?iF$kSezC{>ETUmxd8Fj`F`Pn?Q*Nox z>s7I}gp=F*u?GV3Ua4|%=&08e^}2nMOqa+-12y$9%BFcA%9wsPFVlpMldZOCcR zw2StyVU^;&YwM>7d+Eu`aP#5T!Da8Q?%`L!bFZwj6MLmn%-61d$k1I_aTEsn+X%@7 zte<@>W-D|D>h;u7!;!6Ysh1I)6Z%bnR1KYE!V*Bp5fRwhk8@Hb5A3v=rNi@{K=<3F zSF4Jua>0Y^6NXfH$6#kZut|{3OBWyYqz>;gK!d@S=xA!6D-z3RFsqbh^zHLYC)Ov!JWla zKg^=t0@)TR12%2cD*-cT~Na3@c?<`NF zv=}Y|-NxM4vHImp^y=gNB|wJw?y^7;y_VNixOA0zsV<&D+e&O1xs7=d{lvZ6`#;X^ zi4dFqUdU6wzd4X|W555tI)x|)Nt#zOxzXb|;nFs01))TF)zo*V1XDt;nid{2>##qLlJsF`le0Zm?bhkLILUv{=hnP)$FvrW+ zCWM9Tt}LFP^)^1THh#;`ws?l~+bw1ap~C||cQPgC=B8wi-A=gV{$#v^(a|ws@$Sp@ zfIhlBzVrw-l4Zxk%@%gAh4WYf73S?1#&*6vco3O@h4QeSs@Ygdomskm{kiQoy%QNb zJ#~rx%U%*=TPM8TQI_;U;Y(U@_|Bj^c%zR|(bM;X{homoiik}`vB940N_^r3Ejy<^ zVEagb7(71Ssa?v<%IzMnc1|jhl9dfs%2xRZ=$mxtE#%Q)&{d`pNN(Jpj>U8QCP9pb zu(&i+)N(nyccMh`3y1D%rkRoaGl6JU(%hZ`yI8gjm4XD3>%ZlG7N|3GQmU3y=Ss!v zqQz+1=|$VWXPXzvQFhLX-i&tGY37nEEeMH?`Y_j(xR=Ciip#Z)ezPj(>S(&dOlVdw z-n`o-tHg#(E(YS1JdKB9+ZQf1!K7H)j!9zUqeD8yMd7C_Z)H_Q_dDEcRDh?CDf(B; z>}_S5`ADjs?^@q*kIGy)YfSilCBOj}j^m8|;O5dB{CPj|i3q-%(Xw?nF6Rt8rYqs! zNNv{Vfrkm=pVj$6OY-99)oLh9&H4PNPjaZdhqmjMBF|dg87F9(FdcK{f;P~HclXDc zF~@0tC&*=RKHAEwSfqiz7!tNTxeP6_+@lCX4Xp5ujXXY{-`>c zW?Z)2SkNF*t7`eFg$$ZU;1g!FUD_FKQIqYnTRm*{3zj1^n-hKpEzn3_G^m{>Vo&~A(Nq}2zqYnM(`Ha?4bLBzrAfb-~Z46~)U#DgSeqk3Wlu-Ym z6qFi2%Bbpa(lPrXr@SB;nhXF-M?FHj$&MM=oCIwdBq8Hd(Praqfr#_PU8oP90gZw; zp(BC>V0^8mF1?1>wB&uI>`u_;6Ao5uwG|b47`XKf4VOMOlk~K)O^jk*gmT@)L*MA1 zQC5d5EHL%bj96M*sS%blnlW@+qt8b97(>;gBv1uK+1L6DG{_nvA``zEspWWk_ z4#M_{RdSbc&Wut}nhPg4=TgfHPwAt{F$&A`W;1Ah9MGJ>HS6CSVSuIl^3^pyRFTba zqQms~cELH<6EJC}{N$5LKCO*#zEz+0H{y9#sAdZa*#2DkoBcJN zoa6k-{NsvZvhh#1sp~Big+c@(MWy`PMMD}4WW`=;g8s*BrxN9rTsB2~73$UH#Pk&EjA;535ggLKzU1W@dn%$Ri{o4=cq_S5_>*{)x(7XooV$8g2hEQz`yC~kL3 zL3NJ=NSz@4yX;qmnM4UaQD{zTiAS7jxp0=fqN(AFS5Eoou|BWuEeNpO=|~!SLIC39 z`YJmd!=F=E7xsImI5-u05Q=4U+v z3=I8rg_zGug-Z3$#00{oA9l}HZ8Jw(&M@f~_FmGz=>?jnT5avU@pY$PiJzGzzlwJ) z+Xx$}a7HhIUCN%QfqI|J;v680n5??%=kJ=jAFd6*tw;~*AO<2FJqqbbJ;)=>LVoiz zCbu-P@*E3gXpK8Ek9VDmQ7F~KadoQVW#ftOzJ}7N%U8j=VQ?>#5n30=Fbd*mGC>}w zL+$vuYRcvFrp|UbNp@PUN40DVODEN$cbTrU02|kig}kN%2nPRl~0LD7__3P#wO6j092*Wm6`(!@UK6@*Rb+L$OkeyB{}))^g8nE z>D!gIw`b3um34K+GJ_aJ|9n@{G%;k^l@Z3zb?sJ#Rtn{fIB2-<&!=xIv6vb@c}1vx z###bj{c;W(a?ZArK$)tVlF(%2mP9@;QncMsxB=C>h+}f{$)L~qXutLS^J+~w3gB|< z2Js-E_g)4|$}TS5n@O9W;A0cLz9BzFd=|AIu7c~qMx5)nPl!V4=v)+HJT@O9W@2{6 zWzz(`WK)&afmMTC3U%~2#3*-u#W6uCH8>1{br9DH|_yf4x-c;_4Ftm_bDDOV^Z(bF~mn5mTpvk0rZl?gewHkDoCJRv?OLw5zN(sF7H-o)=j2 zXj-Ivp_dE_^+nBEssNOmVk@PO{VQC#meo~?2LUY2TuQY%4-hMjE{acXK%#xR;v!0? zvp@yQzjbRq_JE;>l$Se^twh=AnX#QhztiGsC70VVA3nA`s8Ya@XxgRv%SL||jthVk z^B9D-G%-({zwNlh*(~ze4!739n{PUT85|!OlGY*dE!1|ZsU7s$fmOC!{c)N16j@3d zIdpA7gL0ae9BYv`$0nCCwr01*=v)o+um>Dxw$4uz-#0*%kB7`p zCd!^N_qd@Y;Io@|onTF2VtrqLP6D@`4(r$QaE9r+CI*q-3!hkQ^u5OSOT}%=N}i0g z5^knR3U4(9v^X{|+R&3m=N#k`CV?(epuVSph2rOm?n@+Mpzrj@#}^4vTF&gJ>&Ocn zb~-7XTq9_;yCHkb-F>#%dSsDBO`=DQpg9V zp_9tFFck^Z_7lc>M3Jzlm)RXyGE+)LD(Yeh;`x1?BzQ|07o09F*%HohrTceafXPUg z(=u0oc9cPUNd(ImE&~b4uNy`#xx&-Wd7_kKGN!;z7Y1jTcA38Ido5LN^#Q&Ot?&IV zZf$NnwFb4x*Bh=KFSm3>aWg+Lw(!2hbUpm%&zjrF#-0qtx5A#pGo6P04F$5HI5OFTKpLH1#6M#6jFh;ScXBUW=!4Yr7u z|7zHWX3-kVY0jgT*TA9$rnqI*^yWpj4#Hg1wAl=HN>vj46m66bo+0g}x>Jv!?r-nU zCx<$Er|M6_k9^h5H<;cFnE2RB?AuTQXUS1BDN{Y=Qr<_l02PJF<%5C#kXTkplJ|*s z;xLfe*AJS_q*0_N)+lPZ=l9siU;ou2@x0~f!oeygG~+hYH;^0chttZl?PQ#$hn@Ar zK~pw6qd`vbLuC44?`!rHIB++2!4`rk^JD!?yEmVE-Pj_G(|sM1d3Cj{Q+*3VSzH}6 zbK^eTzt5JB;+IISBo?zD>b==WyxLcr3XJU3az2Kvwr_5$9HD@*+_~bIfFe+c(SpfNUxx?x{ zPglmD9d7Tul5gwK`y36$IG9qljGVdXz}{vqU-EDGSh2E~YRn|w8@&52qZA^4{WlL` zcsO}wc-v}wBeNunaScS<0qk+L?gE8sZU_u?`&GWR#&a3gAh~*VYbn)@GS^sW^T**BoM-qMit7icaUGg zFLOeb)8GF495Ls3A`W){yp=!O_@{jg@4m!~dn89A;Yloc?Dxm5|FAKH({oj3CY5;c zi6DN@*OVb-UjF{c@I6+SycG$9&AMJvzaVbL(^l(U;7B!ItXszmA8@{LA?hJTA9HC& zIbHfjp;#TfD^VY}=nKqdo&(mI(6c1{(@Ru*BZ(vUGc=3BqsMeMi zw|ln1&dGAs`pDHV1@xF<#Ub2@1Xmew?c%kOW?*`y8LL!8|K>z(UX71_Puho`A9%42 zIIM&xBiofvYVRI7B;5rXI<+%m`G1w@_4)nq%9vnaxhtRvu-vMFo{2^hB_C^-gsk3;7CX?SMLy~7p zJh1zUzA_^^(Pk|viLCnVw184;%!Jy&xEXCYV>&gQr;*=XKf!D9VwC<3wbCQT_#G%O0_uKgN)cNyi{ zTP(j(^i&=3%=)w}9ehBlUw_73X>*b|L7L8h9kvGwhFZlMI^AJgg&PO=4+Y@nqTQfP z?00F~$E_c{6Z8g4lECXDIFbzBeU(uvkmn$Y0Dm1-*Nen+q4W7P_lF3!4mi>4gTPar zUX`oZR^!1tsGZc$FVklJsCXCM$+E+mrQ~d46wn?^3n35E31<-$zd*L ztM;r=C2ZNco8-VY@Ur+1b+pk5uQ7>m2jJ3kmd;)50h5*vBR zO^;FRXvF*r*=);dZef;mwJk&Z#)`75eWZNci3R)p>}lMk;GG^;9q(M<^*kA)5rtq8 zsk8yl-Y9da04$^?6Nj?ASBhB3u>06?RknVbS4ugTJvz@GMa_%h>Cn9B`TQ1x;@9Do zxs7SS*)uox6_w@`^-TGEEQhB#t*N$m^&3l@aTWguJ(@8W2&^GbqD%Ux}V< zGepo^@or%V^TYeH;4}qoAsieO`I{IV=KYS%XHc8`z9YG57BQ(H5f_Tvo((JYCkU`m zTH5BTBZh*B+M`Sf`Tem90p02vhAVO}U)A16cI3s^k9B$YMpqHt6&Vp@nR(h;*~o7= zJS|Jr`y>6Ac#dat9fkd(!S;*djjMAmYA2dwhKsBH5cvu_4c$xENbOM+a6{3MYaE>y<)xMNUyqJxwqCG9?LvtD$yYE;tu|S`YoS9}J70k~6)X z?CX?QRg)kge617TSsx_xW!1YMs#4lwZ7k77V!odbt-*Ua?u z_WhU>72;zirD_ zaw(%9Ux!ONG5-kay4&x6}_nr0#xLBuz`EPq~Vgt>Gofc3K4d{$)51D^#HKRJuaNu zj3|@{r}dp55XnVCTx`cqIb!#Trim}U8q6ug+$vw#1MS=3HyJ8Hc`#=Z-^0~&O$>_E z>sVo8G(@A!3SXb>AzTs$JE>H(BBtRDlgaGIM~CsL85N%-!I4$UdMmvzw?*je<4M;D zU|Al!2?!4ZKP)*<*T)I>XYb=wi-j4g9QbqGd>MRlRqrw(fxMK8WiTtcL3dUC@DlnJ zJ`1>T4|UK$3$*p9ryGsFx2$x$jJQwW=fSUH_KUzb#W+7*w1Al+0kDnQ)&BQ)x2%yC zWgaUKL`ANQxzlJq@JczbX8<1;iGc#Yqr!ctsI=NQ!j)AtsbgMsH!+?dGLp)jDj7CN z8)x|8iksw(=Gf8OZVHF zqryca;1JkpU(x*7So3D@gu{|!A;b7p;Gb&`kPQXjWI@4c9`%q`5l*-LEp->;VDbfg z_lcb5iP0N*M)M61LvImAh9`GOwD;lD-x8|FM|D!NXP;_gwtKH8rBK)>8yArW!B!jj zrQ|2{jKWw!Da0aDlPZrP{Y-N-c;P!C7Ug6xLvpIrL*!jY223a94xg_ft$r+I_hqH4 z%Ef`Nf`V@iA?IXj0eQRT!>j-NEw0#$5&!t+2MIR99vlp2F1^aQ^H}{x7+aF=<(pvzf_> zkHFolI55@I5<;__X%^D=bY4bM9995d6$^1|dZkn%meuh>qOO=7*Ay}6$Q##0(aQW! zRRpYK9mja$Y&>Kskdfe?uTDqvT|z|8 z3y1j$bMCBQ1_9qY z!3j&;j6|`>zb#>AX3!-#^E%-FWFgi|uhtU$3hO zX9I+_Z-HNhOMr0{@xUUX`VmcznL=Ol&b8vRFEcI70h4zZ+9hKDs(<5}jyL{bvi$BxRWwct-K|_cno3^%kL{Z5tyNhZ$uJ zU#rM-6Z;UR_P6klQ_zg|%E!!1nxli-lgc>f6^<9xO zlnT7sMKza96Epd&6T#p#y`Atqm zc>5N?)37>ps#%@8S=pEP8H}Q4c#`W)gu`Aj_eA)j+50uVc;xwi#!c?B#0#%Ke*E|d z0Z-yFXk}Maa7LyM$&RvMB_-uMFUD{5^_8d9+Dl6MF zky-<c&6ji(EBN0)8s)@Q4UgXx;0yTs*)TZbMLEr-tDM!9`~0Z8JqBC7~V3Kb#wNMi92aNmYtQ>GAd%;+zekJ6D0f7#)7JqWr^9 z|9k|hlLxHS7ZC960n{u&A-ZLc!z<{I?G@*jO)4yvk!2Bymtl50i7{o3HIRMVcUVXisIKE=(rWWK8uSrloV$?K7}OZ_cyjAGIpTjC+wgAN zcX#+6_D0kdq#2PXBcIV=j!W*JtC2rXr_X^@Lm1B2ZQy9FU2dk7ib-d1-)oIxvy20V zNLD)Hs4^A#GjajyQ(Bc~uIM;ba;K%Q!manC*Tu?j`) zy%uHtPb!@K?3xGr(6ZniQU^7zR`<_*bx<}c&fDR;sRDM@(5)JLjIgb*dzjJjk(^Vf-=9lPsn5?g z?sj0Fqgh#^*J4q*-3*Q#IJLd-tTasevfCych){yIqDz&~%s7JL$9A*nKyDwDaZh^x z_p9eueG5XIY~B1A29YRr9Y0`_K0DQfBPz|m(f;zjFFzY_w{oU{;t2Q44V`*{JgLGY zFOuc&utn9J9IY->4i&gqz$FJz;!MVc_3m z!Lag1XY70f(W~n1VbfUOlC<~kt7X&JV?eD39mV?Ju8qBzi!}`M7%8OFuF;^QqkGWt z$Hjo!JU<{!M3YAMJFl^UZVR-*`g&$b2r4`ooE!R&Wy6bp&;p;a)oqJnA$~I4(^>-Q z$WFh%QBL2Ggp#ghUYCjPE$FY8#ttm?Rj$?$D*M3w=>vz^l@?~%jGX!-NXF>5iqkdftnK(Dla zKsSq;B^dhq^)VSpFfKL(zn{bN3POlF(L6Iw*saS-|G%?9ub`k1^FUQOBvmSw(3@G4 zi$~mf{P*wQjtBq<8T-W1EL9oKf4m@8k5yxpAv&`&&+_?*_U}~SA{{Ge3u*hYynM-T z3l{K!RCo1Cfo%j5-h;t!XfN)l9enWWBNYWa^{CC0X<#XCl3WNLNYRO0*2=4lw|?^Dj) zK$dze+*Dmn?P*N1^Vl{hq8P_J90A=Qfx-ws#&p z_|!V>jYAq>9kN2q@jSV8dhFR>Cfpg>c5N2p$L&+PUbN$hLAgv&Hh;Y~YX}nP-*^Q^ zbpmF2dHKUOCd=6a5W!PH;14l0?ud?#CJJQ#a~*%J9;OYt)$K3HiL-iK&Gs98?d7MT z{qA=!wIu$(-=zEVYj7+H5d!Heh6*<Y;kVDI0@!oIUb0BjO5?4PFR@vEZUG@&WC+REvcfk@SKB;~_@#VgWSci2wrFj*iwG&q4zc!R6 z+#|tdO&%TIy7_-EX!pPG$B#eT9_!rnX`8x^?|40MX3J?hXz_JP3G2~rGvA86@*0QD z>=*XGMC{}n`W%Cz6-7f18I}nWq)c=ZH{J;T-^2fG9FP@vOGoGsW}&I7 z8VSMT6~`w%M>`XFkb@=4`QT`$m&^)^VMWY5`+KWlfv^l}`@Ddx2yCzYR|w*B`~JvJ z%-1I`ZnM;r{J&oD5ZRlf7Nxo6vr$rw6Wawj#!*h7H*P}iO%wM30ED;vv=67=$vt;2 zK>(G+jsLyH5d0lCUfe!qtLL&Ts|yrsF0h>uwc~Q)_^W2X_jq^)zzO$%;)fS&{j2xd z8WiKtLR!f`Xx#{nKNQqH7#`r1JmeW8b{M@{c-rs}j+Hxp7sij%1Ag-z0wJHb()==) z#`w?LhR5=M03Ck}NpYpG*?lUys8GREjB%JmdL#nio4(n$=%n|000ya;^1Z+L;}s6g z=6c(k_>?0&H|MBvsuKLU74~aA z2E<2U`e{ILJC5R{>Y)3g^*S=O$6I+Uc8dy`#iqVBeSY204yNO@J&x=|?tuQIwk zpHaFq-y>a}mFd+V_XUo(t4J2#VA6(R!1sAXh4?qlVS==oTZ4^d0yXmY*BWrRB!7f+ zMtF<_S`HOFQ7^R!w|)B15`bgSRxB(egeQ~)q9l9ucH zWDF>r4y!E2hB1iX|2MGC0jsdFD%VhhHcd1gnE*<6V z#ttTX4gg_RD>e!D!Xmh~aq`!jQpc|o_#90oL}@iQ00Cy)-Y26*sndDY9A#KXvC!PT zgqVtd2NuE%H<)ebWpcD@wc?LA)40US)9^jPFd5|;i7$+G-sc1@ZrC)hZ@Abr9Qb)o z>0gRsIkJjx){;$F<+CoD!l9lw-Fl;qa@*3Lo7bN8fA<*P{BOKMJF9aW3y|7~*|XWI zeJn>3IG6oIM|3Xc(0M<;CsykaD%tfRjHTs%9w1x_Jpu44!5*p5a8XX%mM^=sE` zA%Qh3Ia$zQ)LIyKg5b~1jE;jjT_?U(eWbpBNL8hK92@r|Ux@nRe^2+Q2ZiLy$6vq9 zjt=Me2I^m(N6btU$aK||+FZ^Y9MP2B-P}l%ip^{$b=QD=^WNz|zTE8WY{#0vd{Kx0 zlWHO#+8{m_^_64{06DnNZM|VbW3QL`U-s28I7N(_Uwz2LWCvyb7l5bt93LHQffvFA z+8Pam?Jg!RKC^Ssv1IqlzOpHRI15yGBdBs*@w??d3v@Z7O8YCe&*cFY;e9fmyG-28 z98ggclln-t&;|iV_ur)WalldL)a7&aZjn(J8J${@NC+<0IYlk4+=7CK#9a0gzyuIk zNDf-#>(?013=C)(7^FeS7pRs0ll?w7qFMH@d!$^yeujtMS)w17tZVXeA?iCK;{OdE zc&iUtR$t~v0dEt)gRKYrUD+SZtm0;=znxqsZ+HRop18g;F?SLBfAvhKd#ny@e>F4c zH$JGxj8^sriG3VtooY7!Uh(DBvOoQ)Ed*k1wsQEkp zy}{$rHw#_laqN7PcplepX+YiSf1{JB#PK|8Ke4-84oq?TJuZN8LL-l+eOcUoLVyr157TIm0)i*H^*G$Ux176CBDHhTA+uXh9gdfLILLPfK%UiWB- zy$N>Xz84No|004K6JDy)jTislm6C>)s>pX()rw4g(PSOnmYU}>bKhD7 zNYv47AvzvjDOolX|P+|XL2Ad@+ zlBiTraQII)UJaB8YaECFujP_3_mpWIHE$Rd9nHmK5r2-`Zn5`2wfV|fSjtOv?!&eU zIc{Qgh${(j1(wU{zq(BSn=gDwr#zy1k&~0#zJTpI`JbwKTMethNA#lOQkRqKVn!c; zNF{p*V4LtL%XOt2Xm_x#idg->p2Kwd9104%7u*~i98IEsCn*?uU#MqqTaj(a%Wz^K zil_N$0q{hh(JoHQK<&E}_2ZcTu7n$~43LKa#2xGv^y@?zBi}sd z%6_0}voTrmAs2S&=bq4ub$9~%$A*-fPyd(6o>~Kt=DJ7FEYZ_jVYf6D^w)mpFT&L? z0}Icg`i@S~FIvlY3r?rs;!ZVXvkFizO>VMk{GLBwjr@5t8;*?T2Nu)!;J@KS^l(uc zP*Xh5oSzBZeG<_B1vZKLXb{-5$^!Rpw2arXmCBWR_+ zfXiUsG~&h+#A)?+c+`JA^&sgNs});KKIVaDC&V)o_6VMr#BFzyo#O9#?Hs{s=rm0I zX}q0|RsAVRPCc;S)ZMP|aVoWFf$C-d7P0OxRk)f=6v~jg{?Yj)pJQt4<(L*#R^wM7QCz2<0=+o%TqAM7c}KB;weo8xw8j>+6`uAM_9Y*EkR%&YYP@%|>R0IN}=c3%1bQX=12 z=d_2Kl))!wJsyjXptxBTZX5%DN5*h&%nnLMAuZm`NyDa%<@}kt^Y0)R8eq|}JqpML z{NqZrS&gelzg|QRn4->kJdKVK#Yd5lq}v+(-LVPr7f}u9xwXgp(9N-}J|3qC1xgqN z@8(CG8TM0w8I(2hYw$^A0uCMn<0JiyO5>yY{{-^Df&3E1Nc$NYfRU6=xH&_QMfwm@H;z^Q3yufd%j>gjwH&PG!?oU1{=HfAfY z0Sw+6;st^k3clSqwSy7lqKFgHx`Suu3p5`iLO$1zzJiLrYVEU1rM-E!$|tg>rlzN6 zX0$Cc?QUo~%frRQJbcJhtkR3nexw2gaEJ9{ zC&9Ch;8|$rAJ_PC%%8|t0_qK`re!LpTRP1@8WzO^4RvbH z{V4xj&0vYK!s@Aq-1AkKVrHW*^^y*XDm#a3yGg#1Qa*>E``=x*9w^3JkA`*3Ngj=I zqcC} zF*$JoUU@n!w1!^8t~n6LwRgFo9yVDjj#m2I12jT zt;iTiWLfoK^^}QukjS(Lp)8#CZliFUGz0ktx}E-`?sa6Ppr`M%@w=xl9#oLS3;C8v6qv2P~6#FnGpm-nQTmXJUhvsRH`-3{5v&n=znJ0`BLI?9sFJ9W+(xXhiSOnVfzSc z$&0@N!{aFP#b1M?Iy>eLiWcmo#$XB*w+vmgyJM>t`%dx=;tzirC;#6SQVY3rLewUR zeiP;UltuuxyHUH}F;%1&;h^*1Q(^MhNG2fn#&;&0V++{g?R+PP^wOv6g{znn#*4DXt&;5qv!iJ|W53?LDQ(e)HxC0ftoQt$ zCdx5A^`G7`UxhHUtFbR;Bdt%4c1XAPHahs?|2^iJG0LKbw)0>x7k_G}_At zzX=r$q7J`}kopB4E;l@2;&R`eAHq+aF7b9~G{;%>Wi#i#10jUGcb`70rM^J(z;9y> zJ-b?OgE02fVJpC~ik9G`1@%uzw^c*P*V`=Jn7oaV|MMWb4~Lr62vsvv$u+g#VJUfo zyJGK{cs*L3M8Z`P^+Tq|f2izuHYa1?KT$OX3t;2em!)+Bvai^8Z8C~ZFkNtXHf6Yv zcc(cd&mzyol}!nwK;2sZYnot5+M@pNfPe~$hzN*+ z3W_MDC|&OvC@G+TfPkQY(jg5qHX)!=5&}L#5h>{&rIZGxQyR%3hno4HJ2Q9iTi^G; zYrVDR$-O7`+40-^?6XfKaCun70?jvjiJMof3F`_;Mly!k4U`y?bL_ioZ!ack`Na{} z;(|wB2pty5bzdAie3Axk)&KNGlzqK;NWpN6g_+l<*K0*_#db<#xlr>QVQN5b|EheU z%+K!MC`5TFjsxQ?+rQDjdZlo42z@+BOW+NkUof}^E(>g;9OftSg@0nqF;uVhNnEZ{ zoXup>szUCEq-Cf%BR1}>9}(AP6WPJsMrG+nAad?8KI@YX4Hr5Nx6{bV%X5Po;Sbfd zNj!g9`^P>gR_%@3LZP?NZCB5LDO9|1-*V+5?u!ui2DKI2eb93{L-f{imU%{Y(t9&7`j-|gWvdW->x)_Gga-7QU8 z{=hBgIPwI313dabS1M&X3|Du8k-Q8F;@+GF<{lWxtUDFY@!#0XUJXBm-&2e|&3Onz z{4@JuD6%w-4imi}3%&Yr*IRtCd$^i@c;sevjIA=Fs=Bqe>{hcYl)B{9dQ8BiyFDr zURH3J&<0$NbxgQu;=clr%U}l3LzZckKa97sva(KDtcjcK1{^Unu?8G47@b`Wk7e=Jpcxi^eC?0ho18`r!&I;CzzJ^t+~$)GASe;0##Lji`r z@hAIQeR9bo;nZz~1hDgB0SM?Ua>EmcCQxCHL3^-%J3!}Wr9#rTB>qKA{i|Tdelpn< zMN%z+eT>b@=)YQe1?d+a9^3?!6CX1i;sO-OEA?dh!6+)K@utkS`LVK8IlT!$idQX+ zpF{KKs5)maMa<*rMzwqZGKEKR?xqG0#7#wcBUE(o$^z2cWQSURv_pn7SUytM5X8tz zw&IwBH);<7JEp5@ZV7Qy;rU;mn-L^N(5R#DelYF9R?u#*1cf$=jLJz`w#Q5W(z?p8 zz3nHwqD5e%=7|qG?6m>9(CUhKk8-<3MV1p_1xUlO)GQ3uAdfPVI)f!&U(0KE`6lhVGYo}w>~1F zBk*pJD)hE&zBSXjc%a!ETtwUC-l*ZT5Q0m0Elo}9@F-Y~ z3rBM^(qLJ<|5ydz+fBT3iD}!Oc!dHeTlD_M>0CMdhU2w2hc`b&?;zp3qiCS5Bbap( zVt#Wbk3WGjGXcQ$S_%lhYm`A1rT|FP`#qQOPn?*LZtiFykedw3G4tBp1K3`UhO=54h#gY9^|6j?q18_G3ynIERYKoe{3TJbExLFPQ0u*fZZ~SONv_ zI-2JtEwg7Rd{PS`wFE(lya+J=1fWfcSLUHnrVp=xa6ePK@Pz?W^Zb)T7iUe50|Jq& zsPYh&o#<+8dN=bB3oI9XCoQ5PI|%JPMx3yNu>F4Om>jvQrJ}D7PAqmmdLTvr=^hZ# zW|a2w(jM%^Tt}~Y{ziWZJJ~E+WKUl(2$B7X>0u?asi4xx_E@KH;I7zE`)LkC>9ukR^~`;dAm4YaP(O+Wbik@Aa^B&7yY zs+AC*;=K5cfPt;aMXijDc?}z1?I7+h;uCDPg!N zz3hB@nvqMTS+J4(zBspWI-FRvx;*|?GD(%`T?btrqiV8$ZXkYExId57!-u^KWpzU; z26282vE8h}vSQqUV}wxK!W;fz0DeyDhXc?)jSg9kUD#t*Vh13lH0^O(^IbJapjNEv^&rH~w6p>QqfCHGEG+h@FQRK|^<<8u$o!E{#e%Yxkqe-FK+X z9Yux)eK`+F0AFNq-?cZDo`ktR+}hl9eU8sZ9oxlARJWEJ3Axa`L8D9-Rb_xq-j==IoR78#bOgA7 zL!#f!OsTOi#Y)imHvDz`D)7EmUhad8&fm5(H}V96=+H2lVL43EdQch*lq~XaSjC|X z>{5Uy@pTHSfYu38%&6^#Ha}_W*1&N-&D78ySqd6cbfLj6C25794s@?)U$Pm$&}vAM z;0d)`+ydfqz*0O(K6f5Mk9?4*)-ZNR<%f2;nJl<4G4}iva7XOXdh9ykxGp-V%qP6CPS4uKZ%ig zD7p&7Am^kFzokz2mcRMs2|;j%&!>~yQHlc z!(YYo-*pe|QjKt;!JM#>zDGMx4d7fip}`8?2RT-5l&FlLavsnzgP0VLTKd5Ug%_#o z-xx#!xX{u^^W!v35QD13d4$bWUQk5-fMQ|Hdz2pFl)cIz2%CtQuv4NkQKZpdhd39? zj{&(8iBj%@Wc9LdQ(VFW5l7TWZ=Awt0rE(|;t@ajYY#STuNn>M4^Xo-Met5xKmg|$ z&^zG1kvEC95chU~wd!VrCj>2YSc{v1jd}-=vswk})Nq10q;4-rwmScRo2`6LsiH%5D zvpu=F{fT?hSyI;r6vIhce!c64x41k$V%5S(;p6{ahaH@!F&7}(<|b}84~^+Vag8ND z+wqT6!cw`3HS{^wPptaq0^C0L=h20PxToC5KQuKpJw z?BAkkYzr^KsmG4b=}qY1f#}d+BVs*n{5m}RJIm3)Re( zc$15AkdHNw}6=r zfLyx{>a1^gUPl)6Z356k^h28fD3@}F@a{W}!z+W8w%4L~npZkU?`Tbr6!L*dH) zJ1^XLWcU*aLM`o+i6J#{eV@Q$In1qA_qi|(fYZob$W`v;C;d8bN#Gt$K_sx#&E;_X z4tQzgH$1Lhn4=7Lt5$#ulW=iupv!!JT;}NG3#}% zzu-3>uVE)A5o9FaxpE6KIhI0;WupkeUu1oJwFl~*-JD}KdK+Y1f@`F!C>L?9qm>!f zC5+6zwQ>0v!~u<+6-!0rO|NL$9u^Bo@t;s-K!_gCE#rX&McG`>bIV0`aslO46e!l2x&b^o#EGIS^VF*MWjH+J;q_@!t=3bb(ydm^ckp)ylN|{%+iqwkj(t>!Q!>91X_B zp&S*@)oa(C&}Eq@P53b<$C=+BC6}|IAYXSCCs+O8XO13EbEN^$q&aDoPX#KudXR1ckkd#C?FX=0No247b<(*WUC2 zppCt}Wb;Aq1Yu}`ew7O<`nq-U9p7n|EIc$*?<`kc^TD8O_9rWgL@&t7{c2Wh&`EOH6GsOj#mI(HSd{~fSjLf>`}C{6wfZla$=JHK>*5e z8&}))*@}w3b!P!vkN{sJoccJOcR4f|*#=7;}jGt+nSZP*rFyvnvg zd`E9$^1}_T?$xRy(%|_r&ts*_f*iQO2rKtNz5fonY%sETPR*$O3zU7cP)OjC74`Gd zOAv?NIZ%RsbC5ydyC;)J^Vyoitm83G>NOeJHa&T7V`Jr~7aa=^CnO{sDVMK0fA%a( zgZW}+Q{AZJ%a<=)VPsw^tLXRw4=7GZh!32w6=%JF`Bw2%Y{};M|H-EFGKQK^?kH?ud)N}U(V=}X# zMDfZU8JxYG;x9=u_S%>I#CrGSm--~dtbh(J{|e_Lvi!*3+4tN`RFlp zy{jX!Z$CHXIq#*al?Vjv{}ZZx5);=i#woL^dO78Q1F)GNL&uGY^Nl#S0iduZuZ-(^ zz}8w|)f!zk>cn(|;&_0Hh{r&(C8x!^hdO_%NxJ>i8@h#Jr}b*HrmCd!tx;cJj`W*D zpINUA&#=cHo-4U)6Kd@8g?ZE6q5=R2F)(`P?~5DyRv8)LDh@-nzr~TGHO=lu4&Qy9z8eX7Q`&t-gXGv^Q^=g8ajIR}J}m5r84=WUd%qFa1sD4LMg=IwvG8 zkH<(JyqK#TolI8d(1a{y-lu#IE|kB(w+}Z}fj|$zQhb%ck@!1{Cuh7;so4^2-^Gg= zS)PS9lXYX8shfO72*r2*r?xiW>szq(`Zli1PJxq!MMF-Zt6Hqd&Rho^n{Tu{0eQ6) z-Na>}mqNF#y*qW4MqO?~#AbFLH*i7fifVh0NB`O{u4}sKw2H(?5M3!72~8L(FCBjT zQO7!vVzbC<6;=UQpP9YTz#87E#rkAcz6xsaiZ;NF?_PsAZ+`!JZNbpc1x?}nRRSdw zq$*lqG9=CU+KSdcgC=J>-r7`G)?0tN z!21Nia0CDyq0VYlYeNP@tc&3G!-b~#aj6@!0A%+d%(-W$SRh{;4zlM9p7A)=zu=eg z!6@G=vmJOPk<8+VDgO$HpC~Kwn)#lRTWxBD0dD<+>N!B5U5k8qeGd^4`FG zGeI}3W`TE1hb{-d@xMOEhk1lcluoKSeA~sJXv6@9-puUZ3YCm~yvM?#nVM(~+48;P zV8F=d*d@Pqx5+j1{~2_X#*=daGQ3BBoH6afq}h{c7@wcCF-BIK z&1Wy~gvuQ%a16v!9d(K8q6I*@==K+hQSdeuUoBl67>%p8C?;*Hg_s zgD1Q-W`i_(*DVbVJ8ITj4{Y;7M)Kd8K7^R#c{PnJywV`K+F z-5{=1e?BUuorw~`fS_;=D$56GNS%(D3aV#?xNWo4aPQv@3#Bo{D7K*vH8Y3J&g(HNb7jp7%U9^f2ZZs>TuuJv#G2cHdYAqzssoZ8 zeFmZeV{_BKtDBQ@DILOG0Q8a<+6rKc@) zW)EEjZ5V!9q+Hr(F_~e=Zq{46&Hck6Kp#PMuzPPu*et`RddAk~7$Kq1%wO<60_pia z+u8CyyvZT4y)xkn{m^Pg!O>;+4}ThXd3Hc7ICNQ|oD*Kcl*o97{5llApE9P2J2e@W zLXhF<%byQ%>ix<}4R6zW=lLlemi$f3LU@&@&vedZ9tAzM{4~)%(`a63 z>vy4FWOzHXPF%E?K7-nyL zF>{G{qjC1RwhPZ6Oy;ra?{P*o^CWYnm5L74G|A^t1DOX%k`FhASt*!)X*LvKQ6j!F zom$iW&eLo_b@-e zJUvr5Q8DR5y6uMhi%$Zy*yZ*^M^F>Yw`j2zaiRx#%7-4;i{w#ebLt%BD-%sHRvMkO z^U^fU3LqwK%;C_d5yPo#?DF6jHOuIPGDX7lLf=QhHcn)Qk=Mwn`;Xgd@VoZ+h<)+@ zI`xV)D$M0;T#(Povq=!1!)m=*dB*aj&3ToV+&9Ju!5f0LCPG_z-?$W9JOKcn1-mI& zt+RbsJ0RK6-#$CYZ#P>_zoa4k3^*71-T_uNxOT2GZnSgF@C?sR%!y+*wD#c}NVqnG z;V62&IZKV1?hmBoqfKQ0#=p|$s~}P#{S2YyRYC=(@7kc zL0J#5mwKm@wL#ng;7#%<)tJ=aCo*b zvmBwmKGu8J)2E6DcCgUU9Z=hGDJj>KrAd?JzJPvC>H|BS(F3V@x6^94!(X&(8QhP! z8LSkfqsi`3awE}5|H5gb>xw&$U469U+lli}U)44CXRp@BuF9d^5|v$CRyLx0Vk4U@ zgovW<=tcRWFDswJBnDRRuZg*+cJzquf}WV>4XzCAWVZ?AQ>~hSrytB>p|<&zA8B(& z1igGe%k;k}FZnZN6D$~%xQqoN^;j=zgEN`ns?xFn*%LY|O4n^4x+b0h1wmJ2}myzrj863eiN6v49!0?k4BE9+p&&EGH&5xXfKvN% zuVgnbv&XDl!cm})sPhgi>21X~j{l-Qg9xyW$U%rlQoQy3HA*Yt!jyS7Ux;MGLKlUa z7Qb;}_^+Hff^0>ZOzx+w!nOSeAp;bX=!p5DTffDIZ&JR5M7{p*CguzvmVV0&aE)2P zWJ!<7PAUyRI8qFd{kqC7Ohn*rs_^hqm*w~!kbS{n^0DpDE-nlmmfQe#A9WD5;GY+- z1CGj$e7Xnwe~lvQDJ1!mNW+vn31>{2kXta>8Mx#@{u!?jrnP&}5X|J|f^2ZpK*@=I zykGS0xOW_E2)|V*QCIfEQuz!IE#`!9-2%Si44MO68S^!9k;<7BAA2dqD=>r`r`bd> z*{U>5qSo^Gnc|S)ztsaDGDAK=C=bP9@?EyXLY%N-Oe{@m%0z;l99JmgJ$g;*4y}DU zSpU-<16x;rMc-11J4R^%dj6VXXs(82(nx9pT7>af_qQxqsJ{F^C<^+c2fdxUX*ao9 zd#{ay3#Ug(G2xJp4JBKRYqh)RG6AtGlG-ivoC%y7(vr&kk|;90n2sT`z;~ji_5k3L zq&5hztL|kOjqJEjh)~B}`|p)C5v+aW{bP{4cf&CpaIPLuw-&c9Qt8Tn0DBOOJVKvW zMSArY?_Ph`Qm@;gbpjh>ly27tu4cf_8+e{8!IE$~8!SC>`Z9m@oZR?Zjuf}J3*V?Re*4{etSs@EAps0TrJB=)4e!&&7MmCXlTB5Q{juA;qT% zVMD)=c_>W3R1cCpt3TPyM}7s`x=fwI2^(k@dlVA9CFXSN{ZvgVg$AIu8$z&;F<^m6 zy2#Sp{TIT`&^79K0f$Bs*i9_!8!s@%MealR?-DYQiDZ~h1s^OAq2}G%c&*8Upmxyw z*zxNL?1C}ox29DmWn9oJWn_eB!u;8=k?=&#l3%mQiwPqf`l@sVj$sOh8y{5{U!zoGGA@%%ca zZF*SejL;SfYkr!D#-Xm0@pRa3TWBw^ zfJdXRfrRKVi8z)sCqEq_-KPKs5s&WLUR^^}%oG|$uM<12d4>Zj|LtDmPs*wS?~Ne} zNB{a~s1dL%ZE8z>!mW9RtxLJBR5-gHjmV77=>nAGzko6y{cS<&!`p3jT2ED{XV{rA zPC)--qpt15)Yu^0@iv0mh`%Wv$?oapdVHfdK~@|~74a``06%Y{bAj?_O`uBL8Ui@( zjy|T#1QKO`f@BoQG_OYtwX>QzAPe?WTL1%gnEJ8%_L8xaEF4ygW^kL^uvGi@#qlc* z%#?4-yr!N|FcKICxf5vd?lr`YsK{pc%A>obM^86)Estu|~&`}}~Lp=hc zsAPIyf!v{ncAqc7RFNK|A|KErF!i(}4ADIIC%tmD{2x^PUp+?npTORNEzp6UlNJWj zMpdX8=}F!Jl?XK01Tv*)?z)mnWB{O;3uLfpKP!C><&B6XW@gTn#h*}QG9NrnVZ%3Jj4KAP zIyO=52%y7e$ZuW4RcHIWzlcaA)4`0JWPSD~Z1*hG=meN4{;fa(%FXoGMhem#!fbqJ z*rw1I!E$gMY7jisV5-o@|7kl0{1*wezLKr@Q~j?b*p$GH?34?J^M57{Qt=DW)4WY! z-JX~v$L@!MolW*rnB*%JS+D^`ip9KD--SsH+p9`L{=4W~>QVvjmCOdvkhzXk&U28`D9XI{!Ti)yOq>Yb;mvm2REBY+3qb7liQ zhtZoU(Ts7?RA^(;@^?#sEX@PyW$r2^Gfw#@-`zfmXoA0*8>BIz6IJBtDe^qozuuJ3 z7Z>*tfj7{>Z6dP^VzPmeY|bci>}h`+6R9GvaEIy|{YMq;%Mwr>8nxb$8=aTG?KfaR z#w0C?P(PG4ftCZ)nlNy+i&mC55Qx||OqrIvrIfJIgfVEzVsWXwqc=;aY<)N_>rUNl zXOZXFxQ|`cr3P4)=Gq?IT6F&O;`)Z`FVl+fKHLwk*?=<{#UlM{Q&z(h7n!fd9K`6THrAhr zlbe~iX%n-9yvQc=VV;yk&gSynbB^`sH;~0GZsJTW7yC;z&s0${kKe$i!a(qk$fZ4@ zP~wk8*%dx|EU*f=;&Lz5XnqQ_a9C4^RcL~W*&?!GiA#N+Lo%*5B3|VTF6~2a(1mI9 zQjosb&+n$fb*t##vi&$KjerVW)g1TZ2uC8T`6f)cYWJY5&;DTVg>}!6xwS|x9^Xli z?t{uuYoe_&@z<1kaCQfG{}>V*p^u}=xIM~##Jv(wr8n!L#)4e*EpD#7X?1yKMTd~= zD&vy*AY)Jc7?-6_)a+7GJe9%z1Mv%4)1MWSxH*l!tcPDln;;Y1Neh1l?2E&a-H#CG z=lK(AZ<)kE*(S3Gd0h+M<5BK)aVYGNTI2cMaku2$ z?4iRfKeN*quueevrGtoyS3Dx8MA3T5u>D3dsbX)vKjFm zx83P81(4+N;J3C129B@kH30q5tQH~`_-_Z#-3^Kpsi;C7At39b??(V0nq6H~*%>j+ zhY{g{a=vNnl2-rdtwMm01Yue(L!I;{m|4s7*?8=Q=%F+DHbTy}Yi_w0St**5iGeyb z6C#&8x29EnuGfGR2!BZ1K5!8h#$#89!WmrHB>o_yX?8$RXYp@ zNKpalS-_q`0)#+cNqbcUR5tJayO&!BZFXUzZ`JXjurxl-#72DO^6H5=V|gPRs*_St zV--OfA?9wgE-U)8w+9Yzpm2 zT+tc`$0&@b135$;h@mKC8zF@fRaBaZvCVNN%(JoDAi2CIl2o0QG@*uqqaD%@idwp> zS1dAaZJ*hE9ztF5KP~iw<^bDIBJ>yaOM6`<#Jf7#cJ6`4ku zD>QRGa1ef=f2mh;VelRmZ<^o{*M#rPswJI0&<+!CWt$l7AVP&$Fe{OU+-45dt8Gsp zNJIe^4~l$O2Zycz%-uzP2RlzSS03OzE<0F{TIbTv6|kMXi$YvT(Ey=enHY$XDc1Zt zR7E>@ZyPJRY`2jENs>BBNwNkxPZTQTgi$FwtBHyk1tU?91VCEWh#DWrp%TA6frK-i zuL~W6ViD>=+fBfKe|@jCPy{Rbv5l2xaNCEGL56vEl$#Cfv>Tpp)VniY)ksVWvw{qC z(jx~|5V<;520fW=ObfxS2M_4sW2ic0h6?S%JZ?Z1ku)6feK2oJZuAYPO9RJ;Ogu%; z?H-Nb9533OHfL{P!UU_t<uy$5cj+y!mN_Mw1W6hix{O_8TZ|cq@Q5=}qDCOiYnWlp3WQ$`ugBdplu#3lKPj|=Fej)kfPpC^hG+RngN$iidZbY>s+ryV5WwS9 zp!rvm3tB=L-l4G#mlcm4m@+t0NCle{rzlb``f9dIzHN#HTK_lA7GZF#7B!3*7CsMj zqS)N>PRRQ!RiKin!#R`xp11|-O&mlo7;9K=J>gD>1fJ5$IN``o9J_9xK0byz*KF!s zbv6bCHGAiPEk#QJU$UA3z9Lriwugda(DU9i+N&p{nZY~mLtfo2sohBM9@;q93SzAjfuN`~DdQL%RJAQ#Zij!% z;s>8(fl7Rxg-#Z5sf|x<55T$J%407M@7Hkq#ySM@LjpiWwd(BH<Z|7u1r~to%7?6sH}pRnm&>Pv>aO5)D`V_^@#wQ+VyrSQ)4s*CMQ7k@he~L>Dt|VI zMyc`2RO78bZiK}+o+Paei5!>+%{=|?gl@MV#pOqq&GRP25_m`P(Tg4O>jP&-SJ>hB ze!X2$>_I44w+_e5E-P1^YP1i@k-C4xElwU%sj9D6^;*e}3xvzzf>dlaaOBQu2;5E| zWaqOOy%C6BwdhE{jmrx57BrfF%w7o>@zIW3zY(1b(;aV&#sM55VV*;cCglpf=9SI+1eO_RqI|;yhu6otYD}vBW#Xsg&XG>h-$@ zw^f{9Q{lPdgX;TQ_X!tJ!+i)%7-Aj%{v=|nckZV2d~GX?cHBPeC*W5Gvg2IbO2)(Z zl~QO$tYAul$HWKNY}C^0U@yM(l7-sz0oSedWrtdU50y&t3$Gb@L17j+PR+$ zCU4;+-A0+Y68MgGPdU<>$Z4Gp8v>XPH&Vguv814(CzWL)3jnwx1jlfU;OJ6|G6NDk zH#r7YcOS?@g-?DiA$8*zCFht08&L7_Df zt#C6GG-W4%nm>nZQ$j`Q@E*uSY{gy~!Ty!J{HmG!0dBbHO$n%)9t^5GdTZkBE>%Wd zuo{BPV1nwyGDhpI5wol7U0q#n4OT|1psq|?3#@ZE?D@I#WUtiD^w9t%(Anecoj%XG z-4O_MiSB^M1Rr7^?)RJv1h)|IsZ0KT8ZJKvZe0&dO)ol4_>)0+P~HI_@b_o-p13H~ z2h#@gRl+E(@`qBI^^^q&BdmyrWTMD!*391GK44)8jzosNl zOtbU0ng%P}zt-p~?AB*YTsE$mBNFD63a3k1;V-9qs>Wjul&|;CRT@Tr>jQz@pLudP zzp1$Z9)$uKal5!6S;C@I^_9~wGx$GLO7~@qb-!^~a!ix4**JNMYASsOjgugz_zPC; zm0`L@oaH#Ka*zs`lCWB|)T%OEG?gA;=QYf=QDP348t~a#mz?^XEiFv~R$DVEN}qid z(72Fck#c*35gSWPG@Sw;*syw$(a$nR983Nvk?n2d+Huiy=udQhrGoc(tlKyc?T8?m zoHk8V(b(%0kKbaf)Ezy={99E!MKOdW4dQuWaI7S#2JGg6yu|+Hbk~_xqqvRUacOyS z*K@9MPO4t(4?omor7~NtW&7Li_nGUM^LNcCxB7}-wUEoqKA5rI3~Cr{6>C+~P88Yo z6$%k*ZgTC81NI3fAW%IUz}tww_aVknIR?}V!GWuEZQ?ovbB>Yz?$e&4q0eUQy~v5f zHtP4TW79jurMOsF(3+z9b-Q<96-r!{3|HD@c6<9=x+GRNEEHEHkWQ!=uk7?y+^bha zu&F>-S}CkQNz4XfM()r#ZVwj9sZudocteLKf|CBhR}xy1NI{4RS1`{YS+`py^C>TC z?B4k}Z?;b=)iA~`;Qx)&yh}TOQ^Lltr1RUL5(q44c%gst-hY8A8hrmF5})1F|Hf!}NS|a&pT^OkTeK87Y*) zaf5es#TN3p`-z+V_F4sg9Su}2?_(+{4>D3>U6ugTL<^7!QwzK3?He%f%I z8QjftWvKVVUtwiEK>#UjaL+`%?tC3k`2CdiKm9b9`-k9O=rut^y1{zDz`fk9?nzqE zq7&fL@J~8;+Gtp&s zD>kb)vf|#cumnb?yq&HOR>72wZO~(E=e@!4A%1F|1jA*_}w$gj5q z3%fORcIp{ARIzEM9N1903@=@#NZ3;jp(fswOd~`5?fFt7gr_Xb54wHG{cj;YE(+L3eu=s6@CX?wh49dLRy(U$R{XwnZGL?|rCLnMe z>_%?jMlC0>dR5@k^}LP@9(ydxVJyBv)Q2P_KM)~t8|?NxZaZ*& zqTbI+!w=t>dn9t);z*9;Jz%IOkCZbr$qYzrbkr}njgAfk99b-R<#;w+H2Ba z9~8DG!O2*$qVuFTD?YuMzhS1ECWC@^_rrbXYyp(xqbH4u_oJNpFE$ad4gW!#ch@D#n z7pMTAt~Vd0m2!XwoIM-9C*pZ4BAEs>VA2VqjQx?BDE!ie7nQhRh0NwiSzVyNE5I&? z%6PDzR6q5wj^#6mgM$OyJY+iJE`Oak`7FO=R0s#e8C~8{IxaWor(3>G%yRwE5*{}C z4jU)d>oj}g=CAL3H<`}u`X0a2RQnKDXtSg+!@-k>e!l%GDAv_#_3--}!GBx3cln(> zV%GZHa{o(VkNf<4cd)UsJyVQPG=KIl?S+4Dxyr8gJFP!?Q+ZKsL(Vg9lHe1k_hPGL zW6g1|Rn{DuIPmLPAeag?sHAlWHlLdp;6$m@mlz1M}XiwFwbrV@LjyJ9s z7Ch0^etHz2!YVORfLOE?aQ4F2*Vih&@FeU|(;B(9-PEm;>Bj{LTaz|k6jHPrxgo-@ ze4aXI@4^FTjZ!a-8RTBVJnA>ldrmQbzQ52VQs{;L*D2Sqct*x`OKA z)c|?BW2e#!z>(N-nSn0KTqm_?u(zJrYvdBmOSQEL>=U$NfjKJ!S^`7kjWW_c1iG4$ z5=tHh1P?L1aJ6*K8wW12-NJN~&e+%mxRy@czTHX6eqBkA+6Og0sG7J6%B84u&9?2{ zWfH$?&Pt1w*lb-KmWpm4DM9A@?$oLW3i23-(ZBIpn6cF0L%2#<31EQ9Z&%>KXWEUX z@4%p!W`Dh08?Y2-)T2L|(De+|0aNgr0hK%8SHR+>%Z4#VH)=x^Aabg$s* z-v?H7BO!EIgc}9kI%?5(A4(_S8_ z6-jW%=)dVG8M}b{%IqUrdyiNMzZbt+d)w_=-`&#nVb6QfGR*-iP|=;d*QF>oRcb^{ z~ZAjxg5&Y0WD$!Vk17C2crTrgVp&$35^IP5iG zo@6`b;9qqY)}#mePVd300WM_*TxuT6nMytVF`-0*h3c?yxde7&F9%f(jk(n#aKVp+ z{MrwVYCPTzY0Gtb{RfAL=tq~YKe&cMd3CN_x+HK;9LnbdoT_34Li4b~0S~Fci?g%E zb3rf=gv-ByIkw-jsDdkdgoK1p=J+KgRK=may6stv_e8Bn$;O2bN|QBhplR}x0ngy3kgY0tAN^ZBoN2IC&z@ykGoz3~FPO7R4Vn=OB4e*;s8;Aw? z5ss9*s^i?)A1^XqYLv`u>WOJ?}Fr0yB6+_b)BVlQ3iLB z2ri@A&u(b{4_xvPbdeaM?hjk>EKnd**oHLA$=HXLwfH&qccD{}#BsHzz~wW46mYks zoMQBP%woZ zc27;gg%1?kNV~4B)l@G>#D(;@oAGMcmDhKlh07s$j3gKH1P6O>FS9i zDYt_WdQ}dtc@Tvuv}L3X!Z~o{Lc{xy_U-P|Lr+=Nec_wEW_;kWFl8*p777bXk7gF& zW@}{Rt?W>Pj@62WXW-Q=z@;w@e9h|qi6)ZA4NWiuCb>9~UOX#3cp**aOnTY+A7Sgo zx&EbO334^ESJ7c+YqDb>b?Y>UqGrd;vm@(HLy>)i`Sg)4hi&@iMwDB^atqi5J)GM} ziv=;mQxS2oD?<0wfB-9|w)ykON=3_-KPU+wrerumBiATm$Z<7+_nn09?9|KByN_2> zyB<6&VN}#v3}~1b86U4t*!#ndVrU`96O+<9rm)3k7R7asxB66S1YtIF^$Fc@$Q$!JLWOo-zUg}> zG>!g&l6$ouGLpCz5bZPkEbD=FB8FtGzYivoC zksh8-=$Kw!bgZTyOx|r0&tQJ=3mv8|$=9Qe*Oc53=AXeyVbV|0OrwpMgf|v(#rGc` zE_LzBAf|_&g$n>X_pG|8)@+o`Ur&zAdaWG#g@7gVF4T-vY`|jIMVjPgjUJA@jvPNZ z)rL>#h|6j^YA9uo!dWvfDfo2RYxCG6sqV5QO94U< zr%Hy%Y|mlIy8K|XKUFDDu#(Kw&GW zJ5=l>#^4aRcEHWP=Z4ZE7{7Wn`D^I916nwZMm7~3yn8w8+<7T4``?&Zrf8h4+Bt4FMfTH%GmFcwdq{YX4m%mXIlzq~dZ6@2*R z(Z+d@eaeBe(nH?OlpdcT=hEWUz+o$(uB4)E1goZqLsq!Kyp(#__?=4H3`fL~y<~wb z0^oJ?^sYA${lfA_Tp2&4`DBuq_9pxHpG%vjn|(G0Z^mn^!Vc$C z+KcbmX3)AWUMyfxS#R&UkgQ*-#M_)1RP4lYmrDLOhhW%pxNotOStcs38Ofg!ZQgE4 z8MFkWxdpKc<-p;%_9Eju)#30!s+h#9{Y%iL6@8W3^(-l9EY7vQJ4PHC75jEu$KS){ zw!XKh@|L3ToT)WKAJh%ws0I^kosjjiVzlGGv~UGb_{}s_fuX-!6L5X}TVBUVP&hF@ zdb`#AG}xhX#aQ#PYzB-(I%jbCR>pXxlX#kd3BtlfDcw_au% z5I)Yw+v#Q7X*z2PXDQ|*bg~S&4jl$MEY_SWATk}@f7S{)e+WJI-5#kHtvxCLs%ux} zHK3g@n5X1&VXq?x|13jZ5d#5(zDl@7VMho9Py;z24;CISWBOgY9h^pc{otQy3L`ax z;+*84HnqD*HZC?99!1PNG2ac1-D^j3L<-+;sTvP$VCy=Nrl{~=PQ@RS#uD!i4 zSZylSV^@p6nj3FJ>1TqDDk1`F121pMVM^CmR$XhJb@ab+x20C2$6m)BA~PdKJn4HZ zWDAti5fA4MRl}7C;{dtEfJloPq(kUATzDORFyf<$^d`GZj^57h^3O*vMPK`?cpy}P z6u1Q{kW{$ddFbnmw!=n6G0fF%+g#m&wA>vEsz|}C*xE-ZU7ELhN)_WfNb%0*lkZ{c z-u(LT(f@dmTmXi=*-1;E|G=qX(y$;CP$8bY+BpJ1T>+(X1Q6#$lTK}tKy2hNqV1QE(zbwlPj`SC z^YN@=eyBl}Ci&CC(#x4KQ~~aQ5f|x+AK*Ixz1S3K_9OY214Z}|w?)RFMl=EyJ&+2A z@oG}mfGqMpm4Ab4fm`e?js1NLmcJ^EoOjB0@3-T zlgb8AoT?a74g-4rmy8Q|(iFgGBdS_UEQ%BTZ#7~%ASR>;CPsW09jwRhW(OwKij z8Aut<_-N`z{;b~_TfC0fa0|a!Q&6DWFAD8M>t)%Wh3M=!C9%G_#3h-%8)@BXMV`mjIZ2r1Gl3Wo5AS{k0H16&uv__Tx>b z&K>0C$M{gK-APbq@&paj;h4#_s-UqBwf3Rru;rLML}l|(8v~fNj!45`^}r`3VQt)2 zpEW6z=QO!Fh#o2N1{OgpQ=NuGQc`=7@kchu{qp(!tY(ZFOoGD)q;G(_Bjf`sdN^@% z?;#9&xeDx(aOsY3zxeSlJq;|V3dA9KRU1|>Izc+a`6BK*C1X-er>J^;9Xar?82yxH z&=OR(Ww;N5U|x%8PtDKKpV>3_P=>k%&JI!yz`rPaUofXLRuKNC#s6dPy`!qgwtmq< zTWNDEASe<{pdd*kN0lG~B7y<}f}kKEAUVTUTa+M(i3|!Nl0|aHmK;SSN7>}O$(c86 zvuk6Yd)|9v+`sO4@2fFR%Ymv@tJa!%&EK4ir&mZj{JCmVESx++wC^6Dd&7f>Dko8I zGRmfghhfTKn8*g>Vr%`=^;J@NH#eD%oh(=TUT^OPnYH)6Yw{ua>iY$>uQ1|9aDAIH z@B$=aR?zIxG(>lKyAnLBCoz zKpf7+NiTbU!Q6b;rJ&FwH01lt$oGBt19u(Sx;!1|lwL9?HZ7L|R7fI#w+x%p|ND;z z@>}SdeKp6s!bC+hl6o^Sq49WAXuw{9Txs?N_K^z#>nG`MQ>-d3WYYV zIkgDU<4;B(c}t$w?k&Ghi|~-kjZ1u{LAK}pn2M6gQapr$R@}=MifI|?lSJ`lr%wLi z{qSp=zOndpl?He$akp$QQ?!w0&HZP^rf>(PEb+yPg|U4O^q5r9wG^6p@qAWS{P8Yt zfwhJ)o{Z10zr8Jd*DUk~45d&mk(0*PeXX#~VOR3r__38*sEX|K|@VAhxJ)lH(7ez>Fi*+NcRdJ)6E3APzV$@OL-zHkSFF{wPV%}hs)iEz`) z+V+p8vYaw#+^F7hje^$?vAiO%(#b^r+u{_@t*@0O>>C^XM;qt**@R6Ku^+pW@D8)Y ze;c(Ts^@s2ub7bLf*5Y?vz4QG{j3SgFj>i>TmNLmd^E^RDy4;OO-8bItP09< zn~|&L7h1BC1myRR5OwsbzA+l6eQHHqa>6vcq7lipy+)Ebh;A0CE)Fv2H{ZD;sZh%` z=eXw`vzL7JLJF5Com2l8m)a(UpSxO#QDd-M&O;oXxNF}HK3wy;8MRP)s>!AAmwh=? z#{r#OH>Y3oTe3~klc|#yr;|!@%yYS>M}_wklJ>b0I=~QrlnlO{Ma{~PAHhDq^z~H= z!K$f)QOD(;q1rg5b?No>2X?5Ad1cT>yu`FLH|KdznArJpms^xf;ix%nN|LO6RvZM!Iqt5vcT$u zym*!NYSw-t%1|oiHNQlMy5|jc4#7WXo`%*>%UPA02Y5?ljm86N`frjf!isfBCe}Fh zXD@uOmEht}V5k+%`FX#1MK1-HfHQ01X($u5>Myz2^Qyqn^@u~6IyvIP{R|V?mbPnz z5j^U#gt-1Z8fX~ZPrIx6&%w9a^$=Gpa4AoTxG_6;aARd~ZUd(`Qd%S_WMtV0?gOS( zq5`}Hs)hWL8KWUVwW29z5x2-E4!g1XE4WAAP3(b&=a6sRt?7oGolet_0|y!v8h196 zG!5?j4RSo-n{hvsNdDev*z+tsn;-wri8E*4=R)Hz9zqp1=52-8dcQaq6Fh zedCw*Lf3-$(D+T`;oAkw%3!9Nz1$xt!su}9*786`303{`E&N-iY*)uLg@bfNG%Csd zt2VfY<*vA7GO!`)o0H&_6Q6c@G*D9^s9@TU707Z>72?i1 z%gadvjoanrHxSrWY8aF5fF zq*A!GFcRBoJ@=8XJY{;9ypY+J-d{=PE`t76{PCYknR4f5v}(3&OiXtH(<;>Wrgx0I zG8{M<4EI|b&yQYc&#+M{9T2svAI@Ck7%0jvpK*VHeUBy@?k8TmQ@oT!&fK#9XKA4a zjkj>}X(ng>^foRQ(SFY)nrX^*Gohwtp}w-l+e=AIw4(2txI8x3*DGlo94Yw_I*F`& zHBs`#3n;Kun^3r~@wBNA-&@Pz6c^%jnA=Z2l{f6L;N znk`QyUHgSs#BW&--zJCF3qNCfJopH36Kc6LMO9XZaqr!#>?U1A*B5Loeg+XX#Yq50 z+SYO|Czc}*?J4{&ag845tIl`WZDxtrvJ>N-+n9&`{bXbV&}h~+xRtB_AVe;d1g*~| zx>aT+n|--eh?zROEsIQxPXtybB z-9h^49S>LP{6@Q+HU>a2%{q8sPa$_Rj5c!J_YP@Q%WCQkh_~T5V@weDhx`REI9}+) zy^hr4q)ElB=x^A;;yZa6Fct^+kc(Xbm2}7zqgCt!|HSO2L?FS(rmj3~^E`bbXjUkC z?Z*_H_NyP;g`qOyk_>pFuN%!b{){{$Pcf)&KTNW$|Ew#MO8zwI&j8yX>1DoIV~7xy zlqkOw)S!pnE+oQ#Q9)%$ycfRWdIi*H3(ms(u|_l))1>_MLatF}-0?c5(GVky0i9eV2fH47T>hdvRujB2t{rOGfsKz$4eiuMC7Q5{s6ipKX*t zPE(q2>TjL=ggJo70Wvu#!{HF#0smV3=%iU+VSP zP-&91QD7VP<+MfPL3>wP(05A)Ro_^tZesMHUH?VPTT6~SFu%bJ4caJvcm&SaYK^G6 zbysTXC!Tk$Eok%bh3C2Cbe`{qNCZ+*PmzmPwytjsjhxXTZ|zLGVw{LL zez9OZYoR1kssHny&s<<@WrENW76vppUY+#J5Bna{c1qKVk9<~FPO`Nwq2k>|7?xPR z-0nQl7?QrFRV>$v#o%ygnkhN(_1kwdq#K`e9iWM}cD|BAV^O@P%acK6TIl|^)ZieU z(FJd+ecFECSg;wQC&t7}doGsO*V`_CRD-ASw#XoO@6LmbPp36@F6`ia4u^Y&rdpx@ z?XeqhHd)Oj$YQqiyqdr}U^Y4!kLsA{1l;;P1JpnE4|kP{Kg?8agjr^9=`nU-6f&;1 zUx5P?FH|5KqLzhI5L_8#BToXQ46K8Rr0?oX%v0HfptWWL*W^GvzogVn1PYY8xMPt`B#X?X$&roT zr4#u*KYJImo{XNC)?GJ%6Q;aO=#YeFkgazwB{dtFAqcaBCuDKtv+*;fUrhI1nAc$oU76=91vnpE= zQB1fZl0F!7FI@tGj1NZT?2C+eif+PhLDtVlFg~5}t23TEShpyR-X+4=@@B}9Y|rZrNO6AsS`p1jzB6-`^<)ZL7@AZ{_ZN-*Ug0Yke$~0AAXi zFtQiUtkj}&bc4?%Z-XEnpaoIND8A6}^cC7E0nayqmB(b3z^K;cjx}u3Oofe(gP;TX zfD&=QLS2K$XJcV{PfBfTOWtbpmQU+rPa?hK_>1p7#Jw|fK3R;RTIpvjS=}Mntu7~{ zHfC;ZZ0rh$R`IjmWR@Za3dCPQ2fAZD!%EJqx7OE^O7;yL1cG+&QoXQsa+i`i6VqzcKxr(&4{W~; zzSk8ZD|Oykzf@Vlu9dZMduTIW?9bG^A4F70#-m?ve;_MO=Hen@$&R^zhTFK*$I0}h zkQW3lxx`Z7zV?F>t6^Nl9P{S2M#t$~>j6B09;082Q6+oGXY9xeYj6&Nvl5QFZK^Bn zHW{Uc`6+x)pX)B%HHBj>wOy@$klsXoPtCojdkU3|(vNk{{c`i*5HYkA+UMS4jUF;c zVPYJ?^^jR1(1v|DE0izeyLa{a$TXpNIiqw%FCBOM3@h(+%VAup$>JZgB(~HwC%**^ zQaog*C^c!08$R?{aPhy09#cgg}^zwLi745o8M}w2y z++Tmb`1{0(zy8>!Iw!sD?t_cPw`KauY;py6e%h+WpjrXPXgOB z_5<$H)EYfojd6yW=WLu9=7>5k{p)j{ z3q5UDo_%8xVCh`X7-^-N*r8u;V;Ap}`0#%DEEytkRW9uERt3o{EzZUSO+)%4hAw|AW87-+6s+qN#gj|1;Ck5+r`_n_;vb9G#q+z;V6*n zu~pqO<$b#d!D%@a!x+LILEfNQMHKNGDJ*Dej{W3UN<5_fdZAh6g%GQ5*t>UcNq4ud zwXH3hxQl=PlyRxnWXM_=P&)ei{{e~Q$ri;(7VTU!Y@XLL;==-lbn*4AUM%B2hq z4bi;>%nEUzp-Ii~JEtyalS;^+&*REptTw+fDT2Nm=P_ne%5XTED}b?S)zZd!!jD6` zq0_!A`%{8kF-_7=)e`pTj@zN!7r@cE|Z9^Uho$v#h?i3;u44{s21tMlrG8n2}FIY~SNJ6xHWV z{IuPX3CWz|vr8wXDN)y*5SCWQ_rgP|fRMRUVSA*Cnp^r{(6o=(3GrF?lRS2g^4nNQ zngBO2tvrt4wSbjE>^dC?Z<3r(@}nK;p^1^X+j5%)bWtpY1UEHRv`o}^dlsQw$@T1w zq+1N(>nj71Sy_uXJ~Wrw+Q#P15(l~_2<7{jeE!2Dmz`#&xe7X{3tTPL{-OFhm}Y9O zqdd>VlXg0vFs}9|R)OIv+QSXsERaulj^b!nmJ8OMv>f{0@EF#F6gf6EG!&OgtPzL} z;VWLB{?^&n*-3=?=@}9|on`)nto+{A3GpvNU*&YID+YEE@?_JC%p22buM0$FW$vpd z=@XnKm^j}0wA$8n6yLJ?9MSx3_+Z1Ijg5Pqy3i)QPcFQVNI^fKP)Z;z3Ib&l0%No5 zlXUaq1U!w!*ciKKVsJYa_(CLYV7#m8DC`1F-Mu{lO_1cz=;Y^KCRQ3LEIOCwy{9n8 z>1jls;i<1iy4G1^``UWC-kNg6*j|ey`6~$000&W$$HWO9N>Yl|ljiINYqLplP?8od z1qFEnCAPSH^Hag!PjD}_16jQ^+2n^-;D<{@uyJ&#ZR_Xx_*;3|m+Oi1FS73c=g{4T z`8|CHg8q>4e?FF%oSc`@yCjF{U_><#X5b-o6g(X?TDiLdwr#}6jgq?_jU+-2w9@0|;Z ztTI-@^y|#u7*-Yc81#vxp6z(M(CF+TUIW#QzLo*aK0?;l+6nJdJQGJ!C;}`D^qtJL zma1iY-aZxZZ^zGUtJjw?x%fzhr0feHM#+L`EAfR+EPI?>)>am;Zh1=lv83KxPHo}Q*_0YKS3EKNay6(w zyEVdO$^8pWz#p;Z-x9+X+S+csrdbQ+O%MWN_b>gW5_BMB!^4BzU>{JiCwf3jcq#_- zkIgUrj8VbAR=E<>DT%&>`zv1qEfX@H0bkTpFQI*CHE`-yt-OS@t=zf~dIMa{J3wb% zO?MV&Vp{tC)IDziMbWyuyR#`0sr}pslL(gUT8cV>59R3gY(JZ2f9G4+7f0vGmv*IK zJ#N$mXxQ}xbD8LrfiPZ=p-A7Z)p5J!yw1kPgD8+7PLP;l{^D{}M3lI;s$!RJ`h|MQ z*_EM~8oG+U%3&U>Yx)<6GzXKCMB@mjG(b0Nxi0n*`k*g%^K$-5A6MyUOG?}Z>Si)t zPat4!PYY7j+|z_H+K07Eq`S@`7lt5WnqFiz1fTH}p!^9PWMq-LYQ9n~*kW$ysKm!6U z8G4o5!?47DWhvpSXR>p0_NlwI-1TSRW+v{A>J=3ig72fwxwNM}q0v;W+1pD|$4~_T!v9T^jtr8SmCwI65d8K8Sv$RkLr`4Nhx#G=QjyO6Zu53- zw7U+Tp&PQ;+X~Q&hJ|RirD)Ia6aeD7xaMVK2#n{=cY21`4*qOw%jrsT(nelTPY58Y zkLT&>Lbp3^mrq=+`KGD2)Xhuy5txqfIv%N7uCAC3eCgQKB&B70-}L@s{e+%;In@?! z#)ZZ0IO9pzt&)891r&5`a9C=Au%In(Dr|c^SW7fJr`~1)CRo2S*WtL>l{(0zrir_e za5#B-dePb1&d#@a(fi6RTH?Er*ssfbyyIIhC`$c&t+ig*_%NU=K*@~x(~E)pF6(*P z^=!A6ROeiWTjC%2?tE)Ih%Dm==!p*@4c)8Tb?=uAh(&J=7(}T-9+2o&;Sv&iB~~Wy z85Ur!aVEjFq- zp<&aI=H3a)2`|GR{JbN_&Uc1RzXDhg5BLysWj++YhVnLHHpxva%z3K(_JnqxqfH2y zkQQAo^Tj>IUX_Q^A`EIm4#~eg6SE+MqO`t#{YvYS_wgeOSV(NH;*lyaB2qW(O6;spwhBb_ylwq7__b(oKvebXi}rWe z9(vI2K^bOneB8CJsjaoO2LK$ie=7V@Xy3cKLHv#3JQRK5-RN$;vQWW`3Yya~`H|+QetEq60!l=>qf5*18{Y=y zA(6hIcJBs?yEwL^255Fuo>}vD{@%Eqj_U>E1zTSZ*v{(k?d5F-s)p{^-ugq2%f9GCMnKu{@Sh>cJXD zXVMtoGT{OR8)$p9CmhviSU2SENM_5ch(vyxK&|(mvIU&`9%d4_l)NQG);{l4++N() z!bFHvn4}#~!ar6TF8{P#N{LyR%=&vFJL8< z@~2klH(kWYSEzO5xH_UEF**y5A?l*O+0YZW?pdn1l&6X0Q0k9_t^E=GuxIA(&g3lC zmN3w|8<)2X{CEN!5}(6!j_>O+NQK_*oUPT@Ac1zMr_7yC-z>2M2X&JE=NI<1uLcwq zb6H8RehryLxFW@%b4JZ0tE;OdlgR$P%7Bt@dWm)UY>pEcgF=DMUsipDQaSb-nJA>6 zCOvxsqFcD4*}1vBPI*yLQI}s4f6sL;D~2%=L{L@Xh{B;SbcEXC4*%CCbrgFRRMBh0O1p zFXh;0?&F+)_2H22y1Qk0ZvU{c3SmfqftE|m^764&(!7|B&|!@ir~1C#N{Wl~I_@JF zv0)lRy#ApTZ3&lz^$oc+vBxb7KYiD!b@G?X|Bin2>rDvZy&%_kPUI9B$Z!|G8MNUl*VLNom>p4r#hF5-8ohs_g4|t7&#KnQi7@1S=EPitKy=tJd#k`VHVq6t7X(Cr|qwA&z@Noi^ zvANUiWKb2bABFI~*>D&4mdw0$2V%0_R}$9w{_l?uf8Dh#?&!KYU~!5xg8nPkP6Yq` zN0hw2uI@YIfwYW_QWOUabp;O1HdgUW|X_ne0FJ(Cu(C3jDSyB9p%r;1I3 z%@mq$+&e%T>l5_a#aRrZIK*wc4iei+KYsj}M$7~}EtJbkJ!#n8^UQ%}EUNjMRIQ1l zzOy%E5K9?ld<-eZvBzI=fk}Y19|qH(1s!o1Tpk~^X3N1d>VGxeaxxWN8jSRq1BUh8 z=iI&3qSYw6xHZjWpZz+D=~MZrAZJa~xbK`(qR$m)c~$PB*hd{)@%Mqdo>f5tAH?=z zivIpo5k0gv9gd0aK_~s{ity=!95<=aSG2p#cYqao-8u=1HIzV4&%@w|Dp!Sxi9k=| zBx!NCZk^E_wB`ybZcpQh;`aJv6gVHiaHq1M(&vg{wj})`^3(Dyb^kN&z?QXpr<=J&^Zt-;oINb)d8=4 zzvWBRAg|7JP*V}=fbVn`K-XUKnn5am(frzSjK!GmjiN7#PM(S2jTj$dn~E|Z2l@2j z(5>)~H?;%$_>$+z7Wfj+Py$3I`0}BPJ;OK}ZxA73Ux(X-^-uJ0%Xf28 zPUA;ZI4(-(|0Kt@bmOP|nvfHTiHV%z%PqAf``i}3-MfGP2+7=gtg7vG1szg=Td0=B>>UH@T*t+dElK7}nqG;m;rx z74L9pU3mE{!C%KsFl_wDscdq$76cuBV-?p_veQ|9@Wqt%@1oS^eX&R^?6Hi0m9c($ zTqDn_U_J@PAJ@*~&9|IrwVyYd?un#5>X)Z^>nMrWYu|9O+KjJwLqn#G1rb$B)>NTP zS+sZ7G`wROm1OKg=dOIBq4V&eGZTEty`Rf>V9mLSAtd61Fj49(3VY^PUVOFI zZ)^`! z=duE|@<$oHx%%!SYlT_6jzMXH&F5f2Hy#sJx|qEnd#TI8UcP0ZVtwj@*w(<8!!=rh z$2(nGbMHLG{A4!FYQqf}#m6!DS*1Aa&<#t1MilLrbF=6{KjaT%ty;>ByVSEAA#nt=F zJZshzlx-58GrDcrm>IXY{g%DN9}A~LMD2#3g|H(EQbkh<&_s4Z;&8C-JdJkSrm)0I zRb#D~3I{EJgq#LjH*t8Nf9IA$st(@JtpqiJ_52Tz04t@bKdY0m@ebtbj!lx#)Yo<% z=irK2%Hl_+J=)ZyoN9H;XA{V0C)`)CK+5DXbHUrTTC>AXu0um;DkQ8-c*(tIjn(c= zLu8sVmJ5m_V2CB0OLl*n7v5=o^>u8hKl`7E(wzd0HpZ5-8Il>B@<@=(4z8h&KW8pQ z#ai7+teRxiZ*wuRecPdbO+|alhW!V;Q#QT7dE*;K)f5%kf<}xZ?M|r?QvSfPehmA1 z-`Qv=XrYcNoGnfX+`uzI4R61zl0KOj1S0-Scf;!9O(ejRuB^AGCrOMhE_{eHrwL3d z8JBF9hge8Xx7PvNhtD^MP2wzlkjbLyCpw8&PONCY@`Q4Rv?swg-MGB>V(Ym(E=yed zjTOx2tytbgLef67%O9Ggcm1%KYLD@lA?-1)?wxQ!!Ujnc1~mM*8oH-YgQ9!K-IfwD zI5yEzd*(GTfcMT)+@bIX=?#%jG1C1O3+MXI=Mnp34$hjg8ncGg6{Yk8{gIa!tx5NO ziVXq{PP}k+3C8p|D5*v7%#e+@5l>DNHowuNc)w-$<`6JcXUm6@HFQr%+$B zyD-GS#({`NNBu>6oJbv$DB~%EtIKO8b;1-_QbFhG7!7W6KN#!sbHx>i+CS!$mkI+niyxtd* zi%kCgL-P)@z`@GM7^50X4l5Q8V)&23&j#syMOj{kH&%{7zo@ri$F>%7>`B{Xav3H} zr|cc{G8Z}eG3}??j5oRo5#S=$iM(cy{TOvro7_f3cLvL~=*I00{7Kj4TFZ_PxY)*K zE5pwUXouYf(|+uhcq{+#f*g76e?(l!)wUs!u-aw%yvwwmiamVXd;H<( z^mrg&43AG(!(nrY#j=I6gi8Ik&b7zmP<+n*LUX+c^?FzBjf2`v?Js=jVhbfndqRxa z5PyE~ec0Hf=ZDHbNmO)=Sa;q~kg9T?SI3`~%~tcV3>MY<{ACT@J`T1vy5GdU7h&<< zBql;kdKvQI24b(JxoB;uHEZtsmKw^F-!qzQDIvW~;RwbFs#3`m-LUwXa|EV@XKM2R*1 zuFmv`QE}L#9SRtk>SKUbga*84ldvHluXRXgO*c|%$@_S&iFK1%_n-zY@xl>e_^-FG z3Q=@h^bPr}W%iEjla|%_IC?9Eg|BF|{CP6V!z|K=>7K!wKj1ts(E`*Nv0s6`C;Xa_ zczX$suzJA%I{t?3tn!BNMiBh~jBRL?HC429Rp0@8OIf8eZKW0gEa2?>z!2sJ z>Oa}M-5SYc1}K2&=R`3-alV*mwfTL-!!@!WsvCa^jja$bZzTu{roaNy!#A_#l=3`H zFQ(-ZKYB$_@A4MnkrCWh*o@J-q%<`>QnL$gXK)GpGF;%c7(=LVsE_zq*7O%PA}x6j z(Y`clvTj2Z-Tt+qhrxjjgTgo)7x&yx@69=+#q?|`%yQ1Z@an2*C_vWMywqys9$+39 zT`3?Sf$UNDURiN%zqFBg1nMD@Dpo)iy-!# zn{yx9Q@DSB@cf^MZz`P5d(3H`i{oPvXgJwQMH+R}zh;Yo>XLTzCp%yDSkK%&FlJZs z&moUF6650tSSl23xZ+7BWUUzArax3+cwnOPtGwmbNr;CofTc+_f~_F_H&)YB36xcy z$m!c>QEazP2e#?4)s}(_?_V@;?_RQ2)N(7A*N2pfO~w=5B!C}j<>rWMBiD`lzUx*^ zuV_YUy=Znm$y_hj=6NkSx#az%UVrFmtxt+iSYY8D(l>Fh{Z8EO)^{bm=E5g*n9K!# zeYP+E^@`nb@BTKCWxR^Sno9d>QB8yit3X5Xy8T$hvuA>OH?58cI9)sPqcLFS88%=d zW}RK#U&_cI(_`44;TVlPcrrGA$XlRmp{=<^O#RxbA(x|EE+Hy~DvadZA|)9WuA{;m zqfj*xWEFf=W4{=R=33a@-51ae0dnWj^ip{g0ia--sPy0%>3sooo1857+{U71XqwHj zWUl6+=Un(8qzHMS**-UXPgmRQ!1}|3Y9o`!bn-4Ak8Qk~Y>fqR5-Q1^QlhE1m0H9; zrejSN5TqE(wtJ^{c*Gc=J|E6#E<~90oS7J{m3n{m(soF`P_?*d)}(b z)?a(y<75hJ>D}mBui~faCucbn)U~&^d>J-WGV}hJ-MV=!=K&}T;(Kthf<`qz(f_&J z(kzH$g@ZlH$Vje~+L3RksgEtWTkhYV3{KXWuEs;)%$ek_hioJKnm!0|l-T$z)-Ro3 zry!k=QSA7&)8tAzSL4Zw7CBgT|G875IP2jb<)Zl&y*n+w<&E@c7IXw$D)5MnhU5Pj z)uLinroc^MY=MyhH=BaF>9eG~kq=T%YpbDg_;Q90k2!^F{QkbIcGjg#8KbMU5}LO2 z((kX*4b>ex7J&|@mS=oBcj}YTjw_fprIIDPa5zInvsn359Tv4`B0%fXDXj;_G!rGn z8V-f87RTCK%gcf}!<8)_!^2?65p*crarLF3wI%*fg$1U|JCLSmlb%>L4)6K!oOhe* zsEC}?6)E$B0we}y)7X_N>x~*;AO7x!e~+OrAlI$dV5wy;}=|=Vw?tQ&iDJkrh~q3`5*y+#ohvfz_>UXtB%yYcR~76;>-nx;8{0b4st=ObKH?Wm&Z@w%2&}g`f*ioCpTbYqJU9xqSC1EL zTkzGKd#fe#y1F!WOnb)_E8Y3TP7P~C4D^j4ComWdPWkS5YJZWFt#dkevaO-g z9m~b_Tz*3kL}GD#hkvAbge_j!8mOf)+v0rmz1$p^KUb0L)6kIwEEm8`n^9s3uX3^> zgWnNyiZ?E~$v-yiFPw6p4VTcl{H3^AKY8xSrDBn$BC1+z>3K=p@TL(6z`Ii!lty=c zJ^}VNtL?be9)oGhd?UKrJshlKetUB8@^%RxU8ZbY_8qNPTmHfhwiKxO$kITx$pRR= zE5yz^Ld@T^HKhyngn^LTm|WOumY*);38oAlVXN_$P(0QW#5pHebP{gaXE_&_zTJHa zs`n=S@PPnKW@1^{x<4J(vv%S03>j(oVur(VqU}zJ&#ab4*gaUk{p;HEl0Ai84tL~N zMji(r7-`ZY2R47(nCNsCnsDcDFBi&b3`;bXL`4tQ8hcqQvR%9W=O5Z7 zXQ+CcK_M9Y0I|2L)m=#nPr4kh!$!jsl_j3+N?J>9KVt3)@&7f4<9!2;tUoBPyfrf` z9lmmR_nRzbJHZ0&CPuaJf>U*2TLa-cX%7VTN}#4?UBS2Fl-7u}uXtI~V3!_Y@fUBQ zSHZ(iIv# z_fNofBoVPpPxOgIBU_H`tefKwd82K2NDg%Mu|z!N4Oj`BHYxl)uLWW7MYs<>Rt%W(+l=xi*S`72?o%_KCcIm8deBr};u;v+vwCjzc z`}YrUh8+se8$4-I^t1nq6Up>L)-krk@eH6gq#Ktu)oS3Ki`lge{?>?~O6T_O`-$A6 zvy_eLrIh*0PX`Z|?RC^K2=5J-=EYPr1cFY}2}-?+6gU&`I3^+|;0TdVhxn%*gk^&suLv*L6*xeI?UO#3rw5UfZO z!9CklUKJ2Ulv57BvX-p2e$|qq8_rz=Z}TrOdapL10oQEGR~C6t&?*;YhRq0yp0md*BLN1wT$5r3IhZZ4p4L} zSkmJtd6)N296bK2&CYi&>?`q+YRsWQu5w^MdV@1Se_*0T;ehi#qo42J;-^_l>%F6K+h%7&D(Q1EC+X}BM z+aasqk$uzmAc=C`-4u-?vI~yb>pk&H?)0{`%57VAJj6v@coR(f#~F1gsaOW-k3R48 z;#AsdsE?#R`xM>m_)0q*LSgT9vkq|8>#6y6gZGH(5#ih&eEB|+}ZwF?6{#ow3CCJw?vv! z;{?V;;t}LAlP=~&Ed279pc(VrdDd|}be-TBVmH5HZ#Po2>N=6;n|mYt}dq4pv z(zQ_Zqxq_KaB@oUkHk;R23pQ~)?8fWOWGvzE0m=s`Iq;owlit$pTA{kd88phU#3<& zIZ-%&?YoJxTG#iU`P>{E!!sHwe34e8i{Z<57>F=%H z9JY(CW|s7d7pJ3{+QeLWXD536)Ve%QnxvPEjKu0Ut&2XHpPg->bRM5jGxL*KHX*oRA>(e2PQuh8I zE$ql%Zm>E3)AfmUd|R+)E-Yq8LUtUF)7n5xLBoXM+Nke{o4rHh1nEJ9yvdTc20LRu zT%YLrqHj0as?rsa*K!J(NL;R@!eum#moKz12^bgN)+oR@@7_&|M3NG~o!C9r!8g9# z5ql$4StW5VwoSYw59}RjKbk0#;}%zwIp^1;S2rA6 zR0%jBP1{kQq|WurqUjGzZ`4S9h<8~D_j+2C6}Cn^MT3Wh26hx~4AT3&^2!KpQbNn& zf}2xjiLye>wVXNyT@yo2_cT@}xORKcb~e*ht~qJmPi&d}byNBL`5B?qbKBebtuYfeK=U6l3MsYFFB{OySH0p-rGhFeHqTliIml+1$5RlV_&sknLSrEL}? zwl2*|JFzc{`tmYD%lE~zD`8l~4WVS%rn~XJscRa`E2m1{vXdwjDLgN`Ic{tIshvA5 z#iZwK*pv}0`11HU`Lkl)y<_GI+tQwOF-Oan^a02yD|zr68gj~svSry<7+PJ+F-6dN z`1ilJah1*u-w1-nSQ{5^^#f^|lAXgpOLi58icpv07(=bZNbg5Jhhu`EOfzcC%hJ;P z{Q05<6{pfX|J`1X9*uVJ+CK0-#a7jW?Stfv)G^<48-$EAux2yzC-8>n_45*}kWVcGxf_+Hg($_1MwYN4b>g;6(p3kX}z(^{nqTEv=h2=4W!}pN+8F{t;WBsZcVlj0JqF zz}J-@*S}g@lOR0s(TcL9@J1L$uYc`V4naXm=*8T0WkJe+q3=z&&$@cL_}lmxPk**9 zuPBp@w86ZNN_o8{hpqaftWI|vE^j=5FzcKm(XXTwH7!j^^H(vw(QaSQT=_=T;$7zV zy(P?B_oq1xuN$l@cL_#L2vKqop zS7BO$bU(7Gkg(q{OJjTZKfi%({GZjp$N>KRpVjznG5$|jjeE%z6&0sAIG#Ux^vGo` z8;Y`9k!1mKs)gs}DClqpbD&F_K9n2JV#EX>@vrX`RgmrPq|u~c`|+#+OR{<*{#7zK z8hQwbCy*NKY58Juj`-IXv>+#%qvMkDg`wK`%Ml*pZ?XSOJp!3o?KoA=iuaRcEGNsL zjlVlwgh{bnS5qr}eOl!|-+BwQ^gB7Uks06(Kh~u|vj0hPpHJfRlCGyvbN53%bl9N= zY?Lp(_Hqwx0o}=yCzCDvD*lefBscNyd&{Emwmh_*SpHH&lFY@6-)@;e{{@RCZM!~Q zHf+Y|zqplm@Wr>#%<6^u@U@?Vt#$>=9fHvJgenXR3K8#Tb^}>GDFA&(7`v7`=MQVs z3t8Sl@pHdCejg8+@`7bxicL!Lt>nx(1DJudrkfTP7HHbrPB2QiF>`|WkmMRD;_i#Q zhBe+@>udAR6J7B1UC*el2p;{Op;X=!eZzCKz>$^O{yug9%` z86qhqg?6ApyV=P!8B_<+Fo@VH{I~niW{w1Ckr-Q-=EapSxb}-_?SFZ({}yh^ur^4z zQV11Jt4rh5&MpEZ=9@{W-(QO?DpJrf*J@i;gIWE}U8V^|O$zorJAU9l7O?=7Rd2Fk zxC{Sy!TOp^lZ-dreza4Eumdk)R+-@cDAjc0w@W6e4V{PC!zP20hX$5Bl<$-|6%!T%Y&l6YM3RX2|2J4Rh^7wJP zzbcRilGEe6R5UbN21oe#_;~Eb+vB^Ggd2YTJhzxFL5tk+%%x!7F|{3cqKqCAqs@^^ zk2ZeM-QDs#jw`r zp9_8)Uq<@xi|wtq5QpyAxJ1v`*jSk+G(YpA`|kf-t|0Khzn82|`4@OYGZ@J! zB4+uE{dXw;weRmVinACIW|dCIkpwy(J*mXfvQP7!PD$V)LK7$yNU4}u8zRIDg7T&f z$q^*YBrpouoq7l|b3Fit*5~N0ngtEB^nppACjv-Png?j^Z`RAv;~hDrg%7u;xGLSf zdl%4>&_#o=hM>Cc#M90xCfW@sz}%3m6_2N z-d|Ye(8em<+p$d-$3K|fX68l1e&bv=zw^Rmz}dT(|APs?UqhD}S9LSn+Q@mrsmsJV z;nSy68;mHvev}pfu^odWZ{ED&x%d6u-_b`ojE#*W^7CDjns)8l6&W9Y26{1lKUn^6 zf+SPuUNd;|d4A{5+NiDH=YT^~kD_P{0Hzhg>eFk73)>in*!OtsP%5SjS{k^fsYzey z&!uFKLEX?#*~_oEswIq=f^ht9fFhLYzJGr)!ecp%_VJKd`Lz#7Xt;qL#S;Gq%jvoi zY4(I5u`^%RvfBXk?O4C8u=)IjCzpC5n(AL{{vz$wplrcSo> z%iT&#NKG;I`@az`umNUIfJFX%Ej)v%{_FbiUw;E@s;s;pR>osBi2L@1lxYQ!%i)G0 z7A1$uSNi`oz!9nc|2QZ_RX`bywiX5*Ro}aG$S}mO`OLr8!_)(on6mfLF3xA@eNFoR z`fIAt|Nf@@YarymY}_ScXsyf;AOao$xB$U8Ki**ltq@J${6A0$#sU8xe!*)qG>HAh zSqj5CVZXWdKfl420{;E~>}q@vL<6F|aR9co$3GX)s}AA=%?Fn2=(8U`ew^as@;&Y= zdUk1kf@!QRqjoj``K)wy4_TXF_73qENEs)D>TrMLfeS<^qEae?&d3avZ#lfcrem2u zNJCSM%DJil9v-vyOw@pQ^lFRb^qs?!!e~eH8}aJ3_;LcZ zQq%!#3cdJ5k{xG`H3^o&ku=O)fPfyffjsW$-^PszsPT2Zhi0jf& z9W+zdaua&~a?{3m@BoziGeFpI^j8Pdf>QJabfFkpo}!_l0X6#3KVJzImX5v>8Uc;0 z>XLK{2Ah&}cGGb)UlHniEeM^QA|V25I9*APAeXM32jIlT#HR>yZv=&KpimIKU;jLz zbS{x&4W$N`Nn6XAP<$w4H}1r_bLXVMB08h~nfVr&S?Zs4&z}KQSh{&vXRi}T0tSGe zUN$Q`_|gc;x~`+c9KY; z_yEfmidL6FJv^?wnQQ340G4bWb<0UrJ%9eZHyzKh{K+R=MGFLcBmjC31*F^b?kW6g z4m-=ETZmIHa9tIjzY@TG6tsW-=)PH=sqM@HmKvU(&+MTWw?3$5j}BIIWba;dR^clW z_xRf&zJbU|omcH;B@9OTqJ?bsErg&u0X@6%AyzdW$@---Fz#8wyY*lWBPWzVIx%~p zBm$m^&p^1FxV~W+XeqAb24PR&hy#-;C#S`V0a9-y*Ug^!zV(+%AI zLIkxvp^ynDqwB&iFmG7(paYslRH0lI9t5;mHb-l)HHCU7(t9JH8rKJla~mo? zpyS#PMfrcRT!ZKFG0|Za6)pRxATDhQkphHSp3!MEIRI3!OxTMli%?-3&*cf|W;&l$ zdw1nNGFQ7aJEH&f(Kfef>#j!UYZH_|RFSu^zsUfk%7pp#5K5VR!J0m4JMsPfMg5u( zAwrCj3tO_t@!ma>iF@ez&)jmEZIGHc11tQM?;7S_f}+iG=oVr+UjR&<1xkp&}`+;kgv|M4%AIp;s)56|;00D}Lxg z#mZyKeKn4Y0>LPC^oD_2mULg8iI#Yd21yPdKK#W|37AXErr|o;h1qbH5t;H=*jlE8 zn&}Qxy_rKFgTJ`?=R&V9sI8PzBg}3haf$AzIno+5R39x1td>~X41|FCcFe1&E05N| ziHGn^Q{)kD2N0M;SHHg)b7QAO%8oLJ z^wR+UPsr(7hfJ94T>*X9O22?+ZUK<#_C1HGw{GA4EZ=3h1ZsO6h6xh@L|pn&F}SD0uIu^Y z^g!uIQbE3s6$<1=32~L7KpN=6aW{!B4Cbj19+XMCmDdAuhgfiljg2kBYM`bLQ2qhLzAhdHP0UZ7sTwt;s{}5%ixxHlSEd>E(lyWg zpTBpY*#5hQpTLPVQn`BdMg4NP%Ulbcn4@(`?Hd7P$POIy60ou0TP{A`i#|HoRRAp> zJ47lfDE~wYe)5SWPVh(arN?ZA83csEA!>QXs{>ymWPx zrG~!0+%gH=#553UcMGJCkVVDmXelG3A@N#(QrZ!VUV&&6;fHmsUEQ{A8{wylQZYD^ zH$|P~!3_jF6Ve_j>nk{xT2HJ6R)0l=WBcACXq1dY+zObAP`Gtp5rqEe*JpLs8zSc0 zK{r`|wjFO8tp+dFR30jZ>}C=dJ;sZfXb2&N>d|STd zGrDTl8><$h5)F7e-k=U%$C*KU@H-+w`*Mh9#Ky9TuP@e?<~mFVb=U#gwP>H~K`dSTvXZC4HBF<4R)Qy%extbXK=MiF)<$K zi$a8~=CU$meHl?#`_rdSg5AsFSKu2fp~@7oFqU4?Gdck?EpK`OPE?%xrO+QftOqg; zrCn5Wr#Q)9zN}a5NmCcC6z<*50j&B~WIXe@S>`VYdx5B=g}Mv(r}A3PAV8BdMu~{1 z%hF6HglS*Vvs?tq&lUsSf*Kw`+~&4jnHKmS2jEmy1D(F5?yGeQH`ql_j1CK?#}XhiTka@Jzw&DqvJV zAqx+Rt=mWE7m*{GE;P91|Es<445;$jw%x|4CoyUSOH>e}0s;b&sz^)hpn@nJL_tMB zK@J{1dIz%+5jMpQA|2kCo06P+-~adH9e$j9j#oF| zUf)`CjycAdbA9UI6%KPgPbcr!MQc_F-?!7U>nInT=vSGPexum`N~k3u_KPR`=kE3O zUFq(NwarA|H!Ey%IBdy>%jXUgVRvt8Vt!_P_PdTCd(Ns>D zm(h4$J;jYvhp6HB;kRpxhpv4pdHIs{*EIp_&lZNry%wJr7&40UG@Mzy+!jyV(7d8l zv44LK2qX?}6)*Z@i3%U^l*^6PvX=SEbL3Y77mn~bG}>}#dJZ@9BMqD$#$>RuA&xE1 zW$%R+#5#U-ke3wS#}{y+w%EA4aOn9ck9=^P7;b-I#kaBh##uwS7 zjx~S|xTkdaV#=<>Gt(F^LKi9HhJZ?5U7wAGg@xkyr;1gQFgxG5bLT|F*cxO9#yW2* zhz%?#nB(H)@H(Z8ri+Gr_LYa?vmXIL+LnlC$UJQa5AT`L;`&s3knzNguD^6dh&KaW zmxNT}IL0YzZD^Ue7=oZ^Tm1dCcTPFu>nj-LZ6E(w;;Wx>ssQyrD{P`8EF6*E%E1^J zd5i1V(5XQ}uUMwW&ZpSVuIz@4Ugdn18vG$(UQNtp{9(iS-rPaCz(p-Xh4R#ZyVo&1 zf0{~+XrOCJ?`?OmzRkXR^(yD>l_iDIhaU2TSWbc}V(cXq-d!hX+l5oK(Xw1=BvQn_ z+fwIiARL679nAmUx@z*_XQ?YlJ-&m7jN z{_ETMH}~ycy8Prt=5N=-S$dmw*zr1@ifLMjItuG77sU71R>x?ciPg?AD2qArc%j~XKfMX&9dfQdAD_@AT-yAXuXD*?UHzYX_;rnJ zcR9_i@}v0OcoJX!*h0m@#tTUZBx-DAB+6KomZg+>9sxuYOg+yT7}bmxmR27 z=}2enLx7Y2_}%#b9EfuRBdcz4OI(=3frCB(Nc3-!>H&q6YnjscC$H6d|5&_zbCNQm z9#iAqm+q3N%A5}&O!2azX~<^l;#==R@uVJS{_^2VENuKA6rzRzR1P0Mi&tWcKo+4` z=7zWw0Xq9#f}r|cCI+{O#jjkkq7eD~9&4v8_xEQ^{eF^IlA7@pA5b{!I3W-zDO~Kj z=lDLY=4go;7F8KbFKK{U#x(cAg9p0@U#?-~MJEd@xLRWcH<1bzdIj@S*W@NoI>2^1;^OmS1^W*K&-|Yq=|C&gZH$u%K-fLA}Glm z`FX)wy@!`^`o;$lR@Xy$IefgEx4aSuO>#1OPjaJZ!5{g^J zXICI1Tb>4I=Q)7=c{0sya$=m9eRS;02QepBGs1!~&4?vjy=Nx~`IJHjVZf~hA6igk zGCd0=6&00V7xNoD#QRqrmxJz<`98=>G|nDNSm?ta+_!T%z8?22M1iBe2XdSh`2CJw zBV=CRo%-H=Y-lm=BbEU2o&!g7o$vrr@=cPc)MLlz)H)T*Fq8*t@+V}IjvhI(4D@k) zSrg7vsrPDGQQ*lV7A{PWrDcFftDCUs1a#5gp=&ChxXQH1>uuUcvpk*8mjWO+; ze~iu5j55z1CkRY}D3;L+;A0oI^+S~K1l?%|$egX08K}eSvUUQ-43CJ2D0iCXBv$nf zccqk?e(tKH&_VPF#FahJSW>N<6teBvEAWKgD93A9@92xqyw^X&cX{!!w|A!=))_U= zp1kkS{KC?Wk-nBrv|E1N1oHer#S72oEZBKv{vu1ed{j>BSu`64u^_eF37hH0TBYp5 zK?Io*w$Jt+kAS02kDu2QXy3E;(utS6+5m%VB+I74kSJ$8VZJSU>b@oV2x_A z7tMgpZv3|6S|QTwDnQ(lkq~5k`PcWhY)DcD5us*9mFa@Dj_bIUCXze8o32wjgtjeU zcD8{z)+{mPCC0jps;>J63`RpHBHs^c>gv3um7hcewbO8lH&!D- ztif3=>HLOK>4vXcO80TEYT0SqXj@eE!TQqNXIL$>uG%Ed6@jsJoJL>QPY;>$`-HH~ z25N2zso;C$7c zOe!J)k~9=65aB5S>pvVtbWFFx>=n*Xt8bC}oVhG$ifW3NnM?ODQ3qKzs^j&UfR=Fu zSURFNig}Fm74}~We~Cj%GhQ{6296M#OF~#6Tw$3D08ng<2ZNAP%UuFT4KF0DaD3`(&+}syMm8@ z{UM#VrH`;!KIW*D0VAz0MeON(L_wPK?zV=GUIT=5V$cp;3O|9vEGa4>;X^V1pvw3s zI#cmYV)VZ7`gzz&PM_clq@hB}qg}j^u6wNpJUK+lL9j2N;WL}W#2Uf@=|E)Ujb%gD zd7x|nVc0Ym$;p2kYAWJn{i~&4f5pHCL@8H*;)}Ob#=<}L@|-Vt-?OSTv{rma^}TIx%iqU^zs)-LI}IddMY2MD*x znPzRrif#*7sZrWNLJ_KVz_h!2@-|1mStYfxwJt~$Y!Z=U7-1u@MCp^JcYs|R_sJVa zba@!=PE?|K4#=2{?PnEeFr;o;FdEV+rWN1Z@Gv4`Bc~DTnf}4siV1~{haEcF5 z5Jd1346Q?%NX3vcQ&RBaR-^gg$%8lbMg1pQ*?W-+C%(6WK{KnaK`xINSE~oJyUC_d95s8Yh zqp3dP4uu@3F%ej}QsPx@KZ>0jOE>Ih(jf)Nl?^h)wv2)-al;%|B)20&17l-jTPMf* zTVIML-q49RaEWZj+I;{YIzzha0qb!`#0IyF384t)x!ep$X-k0%)I-eYD`Re4a?|9> z)XD2(2{Q~A(tZd6RY~#!O>$*kpvh!>7i*6jHfl68;6BySSwSJq$nmeMW#GL~Z{;nO z%pW@+-z14W;9DY@uhTg1DwNQ4tP=QB6bt55Db1J4-Is^`^7z%w$E669T7h%jN7SR{oVl!wbhh<# ztr_h;&-TwCA2Z?1u!?*Ha8^Qr+gItc-ZyI%w_=>y1d1fRLt+k;+_H`n69E-oS5FK9 z*w8vlu+1|D2c~ifC}Zx(GpyD%gQqD!UYWnevNGBcv#7Z8L21jyhO=7`_*V~LgJfAC zt5i*d!mw3&YpmyP?{ee8l^6H8iCtlpjL{f;g2V%rG3V2i0$6%Z}Ddp06 zOkZDL^umeG!~Pm;=O1ejs$isx1M=(hfm!!gwqRdqIGbUNl3sZ=PO6v-VLT-Cr$nEN z#s}QJTlmsnjF{OZ{0c|ZeP*CCwX;W&8gJl*e_!Y;AONB{fpY^uV-UWH0zfnUj^GR& z3zOY|R9c}iPQY2?ey@dBkhPCPXBlAjJFG#%CnG!^ckk7j`D#C1d3|~CBkJZR|rKd2Ep+H$YfF5Rj$BX#v=z{|vkEnahsOsTY(?ylBv>Mf01-u%oBs3zY4aXU^1u<+?Iy`j6>&nOlxn*0Wtvi+QNC8pWSvnH=m)F9>PJ;3`&G2_aPS$bJtgCA+vYHe ze?(H#hzq!LCqk+S%fLI6Mh3)?AnEByXJTGhv|7f4R2?6M&S--$6mvhEDE4#2v1!Gf z5gLja;DacyNab}TuBV5-kDY%A6Vr}&hkHp}2aOn^c<42rIPXKbx}-NYjBx0scQ^OM zxFphU0xpQ{tNZJZYkRIO=C@39gRE&b^zkoGkbv(4i8b}_`3GE5MQq?+R$ zIy8Z9B7~m%+#tic$#VR$ULEq@P&kaSTfs^2mSPf|FaWPkJXLhomWb=`+S;@`x_|*v zr2ZhECv&8)t%T+~Yi9#FVpUVPshLizsSD2I<5x+RRWVGb>Bnqx9jOT8;%81H%}E5a zuT%XVS;tvIQc{wpWNw9{lDD)8v%LM41(T)lnDU6Zdu+i{=@`Hh*$_LhEIu0$Vkj9i z`?j6o$eJ$a6`!dEw;AUw^-{z})DkP`R@P{yhj%v!{_;#G@!F z9a;Dw%yqpBo?QXuKd@w(BT034nPrYS`MGSXYG)iS5QC8|&c z|Ds$v%(-u0qub$OYq83W#{6LZQ_*ookN|Y%6?;^%J*TEjUf*S*+LEBn3iQuH_ zMzxeJT?*W%o@!YoDmD&9mLIrJO)=%%U(ZFG1gWAK_^f)Y5!|Xqly2v zIko8!lj19ACL~DQH;z5Dt0-5o`)QNKX@n`;mhTf53=Kp)Nu#rxWlk^xC-BHroQJ5_ z=9vz{<-z*73l{H>%f}h7%Er-nmk=}7gBRG8tgs_$6oZhpBEd)k(@vEee?m^U5wnL5K7jA-0~4DYH~dWE`oXh6|OYRIDk;1`VwlRbs^p*o`MY6yN(_`s&;!knESg@ zPcMaPcEFjZ8mKfTjnv=HYmm>2K%w8ZEOo=oXAb^Tn)3=-%`kG_F%-H1veu1Tlk!kX zTDH(mJPdVHD%1ivK*zk;&JD@Vzn6Ph8m6Or6$*DAHboDx1|u6sf1bPGRGJFIa7o~N z&B+5W4CJY9_*V?}E7uD!-fctrB~R%h2w^08oc?p&c)+iyE|yyWDw-;FbZl6Tw?|~m z$CF^vJO_d{|ANw{F|}yzoR>?|R#{;GrsG(#c z36c=G`llA5V)6DaKhBPBodl!6s#Q3}H}(F<+alHip;3(u$;S3{sx;uJaA9TbSiEiHS_Cnw8PsmOz~=Q}Jz*QuTxbN`Bj-1t z-U{V8&jJ36wZGMK-`||>!ydM@a zOg2`a%td4rAr1A0#%{&8?sKV(u%8$`LI(`A*~V%F9Ai3QTte2lj9dytzL`T$I@C=O zzej-#=#ZZ$oT{AyKrew5WCfy1(jHdklEtsNWHA{jc-X$mBd2vnl>3S|cn$#WD~h>* zG((UYiG;36!}Dp%DJv`YbG_KaNKL-ZXoqJV1cIUP!4@|aDx;XvkO9rodLb-xcShEW z+rmY7DBecoYE7f3}{U8cs?E!RWDfN(Z&%g2VD(WW`8uBcl;3Yhrw~i0R2o=8?!3QWO%(TEJB> zolq^2o?ewlG2RD8`Q6AbqLbeI+vRNU5>emEzhRG0Twf_=rN;5WmM}dVVE!&}wzApW zLI?4iSe#(c=T;`N{vFLI)Cy5q9*W=2t+^$L$T55XJJc$ZSGgz)EYsQ%+Jp4)hQ|@# z*QV9;y2m5BMhj56PTcfRDzoWggLo)l#%bhbwcFa>l%B}B!yK8jfbUy8Bln4EZ-EQ? zW!^$5<=l@}CZh)E^sD^fiX!AGX2JJvtj2{sEvJZMU$XVB`)SxexcP$N_mqmtGrz&4 zp_JqbI9~`x(kikBWorPZ;!13P2X4FB1wTkeE>edr#KJ<5gm)YhbQ6z~gSr+-?{H8Y zU^Vy~Hw>U{#Z2eDiWg9^RSx0T6A#UxP7qVDo}T6h6*)}tPNK&us6T_bs{tB$5fF-Q ztdg)sD2*oGrzj1J0heE8tdpnISo;%cxT!dTKli^KuJP&UjN`$HAC5yxJBf>81%xPZw;!r2e1lZr;!9z4=s z0IAw^W4G~vEw(HsQySJ^%C2V*fll`eMo!`<%*+ZTFDYlx(mu{GLxPeYQ<{q12_+E1 zvky!f57-;Q&@8}kx+$t5T)DN#*O%x{&MS~A;rnh28CEWEKTAHB0|IViw#0={4a&TL zI^72#Pa@l{<5u|zS+JhxOQ_gF;rMvK5GjW|+)2O>%nO77d0Nih^8^N5L^%vq!yc%i zqPbM51Q=h`FT6lJU+S5<^IlFAeeGWe25g)-8Ukf8Ui`JsS|v(?0gms%A9!O=ChSIq zfZTQ9QX78kmA+)Cx?~{xe`tE@03JKDT$;EHJbVGx*0_7r1k5Id1}^Cp+JVKFe z#kxo5>}{dPF82H0zxpZ2>fXFjYp1#6;APik(2RdFEKzTcVhvaT5`fL%=s0MREKc8; zC@3>Br_fO3T`P^3;rA9B;4=C4A~GT+=8aggvQU5(5XS_kMf-{YoaTnRG_aY_oEjT< z9~m?vi>Ebnk2Fe?0)#9+oHQTlH(NJ=ztmwXk)%l$_*QhDyl_kh2}E5Zr>kPBRtzFW zWm$nMrm_TY5|o!I{+Dde&5qvfOP4~Gr3i(pncuPzl{8>6=SzsP2AX<$-%*nmEAZB> zTht=e`a(D?uDZ!rWx|mUREDRd^X{FEP+E=-eR<4_>_Vh7)16~d5|i-o$blX`Vgq3u zs3<`{$#fU-57`dAYiTYx+KXf@`=$R4c9|C~GM->&P8nf>VnaEsoZYv|F5!$JI?_geMvc zr1wrHxu(PoCcJ^<8Gc^q9b-IL;exQ@!`;>U0a&>HPB>p`feyu#hbvU zU|~9I-~Dh*^=sa7LzGUfup%b-gNRjaq8>9?QF_EoTJScwqpXSF{S1&*3rrqkZ$mu- zfcKn7D&r#L<0GS>f1VAtCI|9GYTlH5IRqC3uA5;K%R#a0{V?p8}Y!0mmUO!I3D#-y(MI3~He=r~t*F zqOqqbd=mI1uNOQ?6p1WVc4Z(uRP2rKG^CzcQP@ppM?a(^%A3$=Yd5p`ZM1j*OvHlT8s7|Mti&ZY@}Lt9IAph z_G6-&Inn0sa~G4RZo+0oyk63JWgNA8FhtOc2H~d@`4kvuDS2d5ZCYH_3n!Owslz?p z`Om*(JXvG~R7ggd#qb_be_CNbLEjus;TqYV8h8d^;t5}=JSW;7EI#S!Bdx&JUZ7hf ztp#moDu)?Qw`SUBwFkIv&g6kZ! zh~Lo}WjyHyvqT8$OhaE^A8WK_(v@-?RZeNj(++^My4csPow12Nq=k?)68D)nJS(u} z)XyjihGoL=6GG%5DWzR7BI##Aa$%@iKS6=-H;)v=9Be$|Ur)465QB|f9W<~~kLU=( z98b=6!V5^hnYxEgmq+ZY9-YSC=}OQEbaOyYl6R@niHi3D6lXt#!moWArFpdzIk!1@ zzEdt1I`nIsh*$6vq>TYiM2KJxSw7+$>wv9@y(g28zRUWr8O}HN&!vR-z}g7?Xtu~{ zO#JOogHpVs?c~|q1dWG;-)fR5C?aaglf{p~r{y^LF?|*L_LBIv1yW??h${rmcL{`O zsU%!!bnZtg{i}QUWln1d;-|n}T<8pEQ}C^dzMi@vHw zvpwYM;@t0besov(OZONEEA+A=tlmERnXY3XV-6YVY?1K_Egs!p@w6w~3bad=nlB!1 zC!nqw8Sint9LXLH8Ovw>qRyT$Q6NcjR&*#pBP08Hk|T#jE5kLx!@*8Gbo@XqKGGEb zje}bcioiF*uD3Mpv%{kxdi{?ft#PmOAq@)UgN1j1Ia<-o@OLN}7Sf%mgdoK=3}orV zbnZTilY7Z{$sEQL@j$?FaD~$3$EO}f!u1G1rl36zA@315fE$>*3ec9XQ!@f;X6+iY zxzBVVu9GdG^9{_Yrl>==pts8r3&4$D*oEA#VXB$1I6_c%A7aB%*x9ss^NsF|7UlX3 z8v(!&Uo_UrqK4rG*Xsinp=!YQHmHY6H)^&)emi0yfGk1&%-o+v>Gu@^h?@fOav*UR zf?4Dx&mVaTK=lbwhJ!>w34sj5V4nE^-bno+>fa6*3tq(g`hcc3qSdo6b{o{F9Ndi~ zEq@mGZxX2qzw`A#Y4bt^O*34LdPqx)2jwpLZB8S^kRyrW5ILs6Qx$<;4XLkijRgh5 zP*ouC{m&oO#TJ?~6K`h!e6k1?*nj-I`<7~nfByLG_}?FuggyEnKiio9{huVwRW%gQ0HtBwd2g@hMNWU}oMP{a-%B8ahurg3x zB5NaJU|!z`Bcr)VlJumG03? zCuOXvH@A6q7HYWm-KHW$H!lx78Qn%R$J*pAcY!Qv}T42L|c*hiu<#-2?2F2-H7+(B80R(01AggqphjAo7_!_&bjD= zAfGz1xcvL4`}!-F&p!CJV?=Ahu>1Ao_ThK8*-kkIX$bT~b)~L4$K$C@2SxlH;h4)v zHr~{Qknn`s-eF!m_Ht&3f&Gh_aHPslWi2(`mye*K{BVfSXhQzP2sPYaO%oXZfVI25 z{S6!$WC^^QM(svGP=9|=!QUSg494&bAbR;obt+>Fl@}969;4%Dk)dx8_-^w&zXw%E zE4o6XpQHo24vqJ^h4oF(X;3wu4G5Y=*S)-W*@hKge5}$n;fK$0d9_6Dr}EQ~$6xZc z-R%Y2ft06ryxUx5RG-Lzw&@WU?%Brx+qpjvd<4ZAC@8npr=JaG$<(Ew92>&?1>@uK zAatn}&ThfWAMszkdtC>gF0UrLKqipG;n{b#aQ2;b>Xm=-vHH`e7Ti`DUoKqh!?#Te zvof?oH_4L@^ktH8(_)TS zWHBcbJWm-=;j%|Bd}t^JFq-c1c+@vjo9v|vlr^tbUlo***w&$}=|S|W|9tp}d2i$Y z>cG4>Ja}yCMV!Yy=$5-)Q7N!t_l@XOD5kyzpair+rq9;i!>-0lrq}UFJkZMF9CRo6 zS7-b>?=3DmW|~a&1*oyfE^xhK>=CuT5S)VK?m?vy5KcJy_wag1n1d&f2uFa2)#%Ek zQ*)$!JF1n3SZ=_DKL2`vdKw4gi7uol1>WgJSp4@QoS+E@5E?C9p1IG#E8{2l8fW}8 z{kZ{7L@NZJ{b%n2#&F&0b>?B-=!+^MjERG-J<<$9`$KiSVHc#gB(N}re`tbH~IWS>vZ>$Mi~^dChHJfelEjI}6GS0ZpxL{hJ`-WvDv& z+KQ?+5d53j(nJJNzsGklp~6QRQ{D3#^&|aFVgb4Bm3Xgd7YEzdLL}un*N%%rAZ$h# z4^=twgVSNBQ-|yJ;6B1JD|yHRM@E;!S_^05JkMM6dukb-c$gLaDfoUA;;MU`}W3eYiFe@-!x;i>{{VzA9 zTJQq-#imX`K>o+)cTSi%Plw`kQ)+~Q5ig=%+Tys(fqf;9DISnOB<9ir_F*f$@g%V`@fb!GHsa$RvaeK?NLh<{=}Dtzh< zQp@iJE8>lvT@ww$v`7D8Z|niG^_VKHQGbah+v{s=a<*{xLrG`BG+;~SoidyX<^_;A zo*o_$?8%ogks*gdi#!>Mu-8xvQ~fIC--(c-E>H5?KOX@tacf|DD3QC}Y-}qICslB< z!iNWm&Mr8k{;nDr*I;!1g&-`e0k6xFJK@yOh%+~vGennqgFI1VlgpDxOVBsI;++-w zZj-cAiR9xt>p(!5;W~RmJ98o0Id*d#QR|R_X?VDKX1>L11*Z0M_rx&}!;S5e|?gv#GlZw(OWvIktBDnxoyL5C!7ogqXJG4ebS6$BEY;imr zkqYxl?pIArZGYA5+3jEXvwXAT!}5A?W;af z^trK0KbcS82U96Id(5=%rZN;k958p4j;yPwIGvKjXawkD;!Rc1Blq?9Kg0|0uU47? z0_hS1qbACZS53!hfD~CBgKhEx{U_?~c9e=&gl(UC8Jcdh z2X*fu2#Aqs_@LcjL;&TsS0@+;>y=i2@loVa2oEylK}Bga_0p#2v-|T$TN0h%cf94V zpFE3K&TOCEf)NA&&?Qg?>7Kq>w$m5qFph>CIf>$Eur}7EK;dON$pwT!Pw4!B%k(&W zhL0sGpcV>MD{*X!$l7GZk9%!kjKJnOfUgrZyS=#04crCM>I0=KC~>C;(ht(LQefzj zr;t?R2CO0CP?RYHZ@JoqRCq)uabl6Tc0}9`$E&7}Ndo*VD2uUe7O{_TI+L1lgzpGV zZ=YmRWVt`8YE$paV1>K1c=#!U6HQtaUC5?Re6c~64UD&3dpUq5KePsNsG2|6ZD+hDdSI?#%_(?Z0i`*Z-TM@#HK^Wp!%Z|8pHyL{9 zoNQR|k^yMj#l~-5CNEkZnijc!^9NP0=zl47sQ#k) za9#OrIRpLo>6P<~R-KLGyHd`SIlM;ROrd}6&fY=JYsJ#qcBkr;%9bUH`ZYnLBc;zP zCL5QFM2UoIwJ^pq06iUHBET#rWg`8uj3km$maJ9$j`|#L09&J7jc0qtw=?l(D^0eW zdi02hKNmd%vQpo&&vpQPDsP=Z*og=ZBc~d(s6`$BG&&){hh{pU`rw1NUa>XB%F>cJ zxp^f``$Rr9QU5kN(07$ieIz5|VNT`r`(?aYfCOteh8=#X9e7G(%K=+zE1cJkkwgbY z_Nn7h&u1A?N0}{}D^ZW^02Gu%8e9nt-50{~c&qdheuZV&P2Sj`)YpF9Z$$EHUc<=% z;}s`QPR!pr^;<*4W+w(|X@29iO7XZihKy1-_W1T6%h(zG0-* z)U&_snwdn-;C>|XjT{)lFw-CwanipJm#R#LXx);ofaE~309_Q1NVEp5p>@A`GxWFc z6Bg|1cK}4oPtE|p)zm=D{Sk?diFvtwjk2@j^?lcS$#{h?`To8e?2IB&`wC%9F@+*e z72Geq2+iS}Ml;Sf=$vy+7#Enz((e7U({WXA@+&)U#cYH?2W7y+Wfc)bwq7y^)OL}P zlZ(11vZ{!Y(Ye{-b5GM6`v0+>V$Xd2W}%DC)HA*9dN^}>G*5tE@P7aPeNMlT zM1X0K-Lh5JgpmjJi3O9QnzQiKXK5sFG(Eq!mmnBFwK^@$`9eAImhVnLQwY>bUx;|g#S^dS!hjTIpp&>hNLranWp z;~$TMGOF(lqO9+-+YzyvThh?=y_j#SpJ~v$RQt;uZCzvk4|%|eQoV7MSO8ac4o;uF zNKE#eUZ4|Kt^eJWd)WcXswBRH#&2JoyKvz`cm~4_H%xOVJzhMjjHkIy9;4oz)oMO`J$Sq*MeANsa&X6Q9T^8^}9Hf?nSsjsDWE5S&D>}Swd?NYi`2Jp=b z;Y~3k;vVt30Bg>>ebh$yV2B6JGdLKs_2%GxNbe-1nQo7bjctAV`;|-WbPe^Hl~WJx z$N%?Rm9zWs=P&&fkzsIM1AoZ@kwZ@8zRXF1jb{_b#l&sgp1KBY@ic`9V`eyZo*|?C zr7A_<^3C4?=ZOqa;^C!{$$0cc4z zxNnSp)h+g&mDK%U3bzM3u75ips~#qLsls4{nFcPS8)LD0F$wYjb~S(yNa%? zuBrolu^Rn48g>HHOR{KoNklT?#vs$U=Y4q?d!rve-q)35`m*i(r4(fpKwF?!OE({i zW{lZg_{~s@XJsE9kRradH1hBm@UYv!uv~Pe;ze zr&H~PVS0ad#^Fe(TQ>!r4}WLZSt-(t(w~M5@T!c$;8eQ(GVDG)EzHDu!4Qzq8>I@t){MM&x71BhdtPd%;_kY|tqXrFl4pV~Vv+lDtP9QIL`}t}kU9jN zEoA86)Q7Fx{&xzJL1>7MjrBtHNGm>JVh+=f1R6er&Ly*GWN!Z(y79WmS3u=qKbPLb zXcC%HN*iRid0HgG9jVb|LNfxtv8yf#97Rsb0s-eANV&O_JN*UZ#$vPZQ~CYW|7N_| zgX_`B!%Q*|`u2BXz{eOWQsgr?CW1-$d?g92jX>h$nF7AwyV1%DF>?j1z}Im=((h5X z0^-QGy2kd}WiuD!{T+-{MX7<5#=P3gVfZG+mqVXJ73@VVt*joVr^{i`rWsOo62#=% z3>y;~K!xcDd`eC-#MeZ}#od5{x*Ps)7RkXtW^io6i+kjb^JEQf9B)Mv#A*ABh`mMF z#D`x@2g5r)Gq0TScohbKVRxq~!~)nL<(v=i;tmA`{S^NO!$*U^L#li^!+@sx`zuVZ zEu-BRIOzR-8Z#y$^dbt&q-ZnjfVcKCf9kKC3q3b`!_s4F{Xoo#D(DACS%71(5;dpT zk1=PcJ_pqkUeFJ)5FH=yO*Y9Yxc1>a=c?sl$MpDoYwg zfp&x0U%J-z?_U~>iUB6WoPvI0@L|;X4x;4>pn- zPIe6gMNnV9V15cfB&qww$O!Gf_buo|d>(AxG`Hyk()(9hGkJtY7DHKUZL|9E18IA}T zj6gDcH34S4U3~s@)M`)f)0z$ijJIR5U`!D9H29RAGYih3&=cHyCjsItS8WDcDt-#+ zRO2h2>BrT7JNt{LpSsvDdG_O`|A;X$8)9buB_a5smHBbiA4{V|^_pa!tI#oJ01aW^z6)^}6SWqIOXVFq`*G zl)Xt6st8GN>~tFLVrQU~`bZWVQ~y@!#@3kQZ(~y9A9*=&Ce&YxXWbVucYf;pth-mJ z-1Dh64~eQnua2z^zBzs;{+n3o$sC__YrIL5SZ6<39-TYa#vzAzmFyR%2IYrSfwQ7qK(VYQ5DvJCaq`vix%O%gybA zt_ntff3~X=7m%DYbnbg>n!bfZfYYETzrXad*tL;Mvth)iy`nn&|GP7$yL9y`&sMLK zi@KVcnpx58Mt_S>zB}mPzA8D_X{XR`y|Osd>k>&vM`!*%%3osflKztT%5Ax98eQ+e=654MOXGEs9a*mR~G@(N^}|_pvDE zwZ1}cBUyXNUBWX4#>cN(c9#_QcaF4YnN&SI9Qa}FT0I(Rdk|ul8?- z;ClRyUwuDMUniFD=lZ(#J=P2>HkHcB$&oQLGpi{mcAcwu_3G6j%js~bI~3*pHQ|*G z3P%-5y7FyI_DZO~WylPYL*@Yhw7gq`?v z%W7CueY-&S!clx!??ALCL#u$H+l0(WcWLPf`jrxw*xtuSGzG8iG}6(|GF8Aw+87G) z@O*qEB>(%fp78$WGRjys%4fef&+V`uD-Xg*UBOuVLO} z$Bx~g|4q7l}ZV~18X&A>Cf8Nlmv0cBm{}q*n z^%GI;=ff>qea{`6cpKZLnX1wIX1ip>7hey<;uF*FA0MHAxtZrmif$fP$;#}fUXKWW z$yH$&S67z*+u#3%v{r_e&&j7sc2=2+Bx%%ilG7ihDvLb%W;udCObkAcZixsNbF^As z8S}KBmv}X;R9983sb?b-ajoMr<)qf{Mft}3>#$yDOG!=T6crP*s3oVMsK9E|70Sn{ z+>45eitXxdXxQa1KC4w7Vl%x~65>OW|NJ>iMMZ^qEvI40F&!Npx{~cYGvwst<)5re z_3cJ)Y+|_ka_`E!!lC{+(*%U|V;sBfCx+BLqxr?V&uni`)5m(E$*i`Owe7iE&Z8$YS zu~&G9b;&}%bn2#GcXgcdH-Bg3oh+nwWqPnMXMOMa4BDMLTlMT}l+BWw&EH7%xiEV6 zy?;#pc|(Xql;`R~*wMUBTlwl}Ny**Z270Ykqsf}-QFohvuhXSne}dcQPjJiL$-&3E ztp9SiV$^y3%j>p62aB450=t0<+)2v|@#}-VvHlX?+$Hld{hjV}pB=wd&P1$V9(_4h zQM$G=*4sh;>$9)-|7HbWQMI9+=ee9|&XMbh6_8*_}xEB`}&l?%-pZ)QPCQgOzeV;Azjj)ccZfs7DfTGxs zY_0sO#u1KP&KZ~LV?ub}EO9@SM{04KZ8sAbXh}C@oa=HOyXCozBQBGuCOWhd85x;j z^!o3+cZK^NsrICMu2_t8U3lU{Qq!p9S`O3q0qSo16Rn`}ezEWHho!mk~}q_i7B5@(~UP zO9yV;xY1VX>G|kGA8YW3ojdD0I_R>@>ilMBXNez?xxc$yWFVsPTdGKqZNXlPmXt&h z$5wsE^6JpimDbTcW)VBFTv9l5qam&0Ys*s;^S%Czb5T6a&hC+VSdeQ!I;e>)ah)5T zpQvPv)#F-gE&Vz*Q0I?iF0`9VkCsN?Ub#B-=<{}qql%3a76RAT1bBFM7<#TajC2)? ztA2K{v z7KxCWo|`-6>FJ52Eh!hLf+WpKwUyU(cI4;UqB#5AVe}9l&F}Tw^4Zwlp1;ef*Vkz{ zHSheJ+vL3xI~}@;oHOhP8}dgBhkI(p#(c7BMJ-OwSp;FT$~Q5(?GSSu_37&BqNStr z{`&PR*3YJF3yZXcg++vOe<-eaXRv|GWe(k34viG8oh*^|Dp{H=tCT4cQ`JWW1`1!k zq~Ar-Dw>n0#j)C2mtN2x7EAi7*<3(kdHhZOOp7jydGWy^aeZMElI6Z&!wT22Vw!08 zS?%fB*$SaPF$bK zhak>V=d)dM^71OZsgLyJezLkBZdF)iVasRHn&ul25D;cJhuXikl(RJYGToGC!g*}O-&`@oVa8%uKfK$T>5nS z`ua9F7ecNxVeF6PEZZ~t-nHtuySwx9^HUu>cyIy<@hyQEMmq~^h7zAwbg$0l<$sU4 zf4DsY zaFL3t^E~V&8PQ?o?~P>V+cPiPOw|ZgUdj8s+jHTAAzd~b zkt00?z07lTuFUQtzTiQqg^`3x;b`=FX6_2iz!=TV~l)s*Ls?M&84MG7)8 zF_~B#POr?Wlc1*;w7d&Q)x0ucAwKJb^HkY*PI4dezyjm!=uwWOWLNrmajJl{HWQk| z8Y73U+Cf8eCr0M}$?4LK*`m>Y`^3U5)pSce#0wpUX9qmf^$K<&UTb(gszZ1~ zB-{&=1md4Pd!qF8PE|!kDM^j(nDgY@Zxc5+ZI?ZL`mVZzPLlIf|K{!6h4$Ee zd9^N({QcnIpjO8DjR@>J2T%FEy2Kx*e)F}_D@5q+15&q*UR_^TW|7`i8zp`}+H-Z! zhhT1+RbA8P_>u1&IY&^m!~<(==f=7#zt_hqq+wIon#1ZA=f?c|J_LvRXcyYE;fr)R z32o=W#YMi;a&l!w&Qm-VEgX8K9{M>B_&k5*SXtw5?*gvc*{NRn%wacBTfVY1r%+L} zIF$Uo@wxv{K@BxEwHNgfjm^Ec$?4vhLE)LTfdwP(GiN~yVuVq)!p6!ehk80O4 zi_)`$s>e1RFOvMI8Y$|K`T73J=S0=#O3xMdCEH!;$ljv=@|wUNN?O{x3gLo%^Z7BX zZAH#UP3xk3(K;}Ri+@g`^QL0^`^JV%J)a%BWxTdhSBnaY30Zf&Jtw(xOTeP#3)ab$ zu{%ZksL!6Gq~b2q?;IFcpRjHfywY(i^r#sV2S@dYySd`ty?Z|vyE>i?<3IB_`UunS zmrE6!^q<$WP$WoJl3RxB)~(CsYCeyq!fSk4V)1*drGHIzwHmTR+#_~%xglphvnzIQ z-@awtK)Ou{F~*rD)t`(ddtV=WDm6{B0`14G87EiQ0jK5IQ~r;P-`r+HI3`7UR{HIG zJlvX|e9aH>*D&2JKl`C+D&*7r;-Xxns=a-7lJikMKC128w+D(a9&;M^H;IXjRj6o9 zR6W&9M=hf~JJNn|X4!tIscJ|MF;aF6P(XwsIwU0FY=p3~je~>w53>T4k@tg*&r>CY zaw5bW6$d{)z1g4sHB7*Q-PqVTS3+M#IciN0b!@xbL{GVZxEWH;#j;yl+}(koh|z9-_ou<9kC_;?P@_EdrxH_>mzS ztE~OP=!Q!C**(o3vmYKGc@ET}IAC_bRWsc{-DP$pv7=zmHqtoVJgfIL;X+w8WY)p!?AJxMH(!vR?3ob|I!fpJ9!2CaipJ$dHySn-=};W=hoPZ~<|~YD<2QKn?%cWa z@X@1Z<_7XUbOLf(78&QuA7y9rH`@*56o=)sR=v5i{RpBcXa1OB{M_S~2Ma4C--;w( zcy;7hkPVAF3_W5m5VY!Kt)`}>4e6culzT-rNh3Asy+vJnyY>P=$0MBd`?Y;Y`tNnE zi{m=FAJg$)dLk_=tFzdYWc8yXCrP|DzJ$1;&H}s2mgn++LPs#;u43^YFTkUh615R` z|GXxBkDAp!K@2zzL^@s_>k z%~+irbJVGl_Q3OJ+Y23zn75?dJ1ifRkjotU9MDh2#{AqNNrxe-C<*tl-d_B`DJ;h7 zL~%o$e5^{GoCpIYa$2Q7W3t9U5`Zj2cEwreruRUi%IJyRfH{&BwZ-he@4yXSN0%X+ zBfuFD5#e(tkol?A=R)S^vdMk8N7yG`y$d*a#pQ~G+dR)ubMhUV-ioiUZ*B_fmpgZ^ z(y`n94&Eetp7rqBh4{&iPoH89OFcv+BmjKB(rwwYMJvnHS39S@V`jLuK1uz^wtb>h zfILa5uEQ;y)8FeioH%g;`A6l7z8$Og-+PXlK9TjM1I$TH8n$YCu?~m(ZG?!OnywJ{ zml<_KWo6|{T}2}JCl_0$RpsASRGbHhxYY1$3zuI0la9jIuV0siJUrzxF%Y30bznyyiq&b3-`W%-qYL5YxIi5{`<#u!Cd+(7i+$K zyKpv?Z=*sO|LaIG$7)dk<(vfNSknI5$Yg|sVubJwB)#)r%e<0O%o33^o}ey$Z_j#e zUYElL^d-}rq`s4mF3FkePnLNf*+z2qPpn865=D);fD|--Sa~-NjXR)hhUJ;*<>_O(UA=jTg*b#+yQ!Gxb~=kDF6>iTQ5eEcNmq9yhbkl2@Ah+kV0WigOhp)B0GWJ_#) z!WjxxtIqrz@e1KRct?3=!)9qJnb+9#uVZ7@vo$}==U11;z77oBLDMl5HrJA>d#OG1 zaQMb6`;Q(~9ooR#k$dI-!^86Z^G*P|N(HtTzl!EsJ>sb>abNoQ!dR-=lV;^Jf`j-3 z6y_S+3oN|6JJHjGdC;Ccd2&6r(F;k%V)d&a_XY#QnHeZ;-dgYZe@gqhSG}I9&(u(@?tp`m0%!mZq9z2VxM`|_S6p4oS~M~ z`{)~o!{*wv%r=8AK>Y-eerjR$XCE`g1xYA({(c3d0aCI|kF+QMm!>QjDucUDldt8I1|Zc*n<7wK}J(=S3ZTFBqerIWoGAKY-PuG`DY z>nVCEVfV%CH0QNZz^ZXTz*OBl`>NomC_f4JMI)qjL5n7N98`qwI69S%L!KTv?n~Da zx3AyBf9U~_tm)Qqpy;a$lNS>^EH5K&FMY~Qis7jn0Rv}&$!>gDf1RX^$GR-`b=a_G<#tp0rI+LEMtOJL~wBG)-9 z_2-YmEl_I8LV)AST3a;d_KoJAO(H-Vr1Ew zuiRRMqgjD6;7}9V?ds1xS)b_Dy1QPoFun zvtnUk;dQOz+FJ4C*E@{oTT-+O`%!|q`s}1!m1F)m-uZ(2WEIP@5$V3Fv)^W>r=^XIp72-!@~JS6?%1`9Nj*H( z@>4E3kjF=dm~RukmAvQQZmyX+#LOInPZz#664GC=I*M-TH6j9+Pd~nxR2nBAe13lX zYoXiedu-k@Ux1^^>m=7KXLOK%S+!m~siKXoXBDW?C*$SiRiR{U4qFXpoHLK_eCfCy zx$g~-s-?yT<+EqEp^!fRWbqZ0%6Al+TvvhE`n$+W=#6B9bx6LX=5>|f>^M}-RIx;V z0ZsItIL9~RsL26*bFutrearn*DzUimQyGDL6}O8=bFd#U}NQw z8_G@vV#e03NbWH^D=>Gizcczyf}*e+P|Wp@7O^8e7j;azZ{SpJXg&(K#sFU{YTNis ztD$^(&=E}vfNAOa7@4mlBR)t@h_Fp}{rqwh5?#^mIIYaIDkrKO&hmfk@crWfAiynE zRaK_@G;!V87OfQMSEO^yo0W1cwQ+%)Yin!K6P5Q?`rE85Iz$NDtbge^Muc-fP!My@ zELNmGRaa=_Q{MKCTd7`r%RZ|@wGojpk87zBt*xrsg1fsO9nDB2M34(HYKbaWZES8t zM(*21Nx5_1K3}v5y|}`*?8}rWAqR?Azf}b)r|JmUk9M|qsxlot<~F|rt^Ur6nW1L+ zHaAidWV7p~rKMNd7f~_B!4qz$pePvg+<8h``UxUmrLo$3H|JJsYir=^t!Zg#L{oyO z+d)Zr69qN&^EQB+twj?R^qaSC&CGTSL`ig+8}-E<>e{*4+}@7>>1#^mh|IHnbL8nVi2{X+Ylf)DT9zTE@5 zJ6qU4E{NNZtH^XWs}c!LV~(h%M`v>A!+?MrT>6DXpHilE^YwMxzV}Z7(Z(ky|IW%f zs-mK@gOSl6Epre4fo0FZ`xh=;*w4eGG_;`)i+`J4J?ROkjjPwL$-22MM|)QC3e*dU zp+>w$H=6>QOxI#KOX&mZrCdSniiE#i(RX;LMJ8m--WZuSf8+`1te4 zBsh52i;Ii32aNr=OP6;UdMw0gSGKjcKP5ma5ox6!E0SxuU;Fz>iSu{(@BwCKQXu(q zlH#zVJQP|CvRkkabj3>8X}r@TQaKY}v4PLA3$s0hYmA$zkVf z-Zw+m7~IQ;0>V^1_~S<^_Dh?WcAH2=eqkXyFyZ?kPTfa1Qr|-AF7dM?+SEbtP?mrA z@FB&{bF6qyP25pN`4LL#mMQF#+DsAmO`NCGD=)V(O6Way15tf6)a?7mr_BD_w{GQg zUQRDvO_GaD)yaA2Vu0ILBg!pT^+jvzbW|KxoG2dW$f5e!JDJyh==5R9nC;LqX@rV8 zB&pzhh8sk$jv_tD-P?8enT5^Ot4e?0y!jY`93DB0_7OX&N(FXo&~2<}%8%46l@(b< zaJc(bW#uU}vwoA)gQ{6}D?n!6(b3WNT==JbD4R)VCCig{v`uFIj&-VNH`)g{X8>Ie4 zN{X|gru;+C_GoDL_Uq0|`%~|&Mr}MU@~=iOfe_W0O@^8hW6wrQ=->19<_jHrdyn#c zC8KAGlZ#8(%+d%_qh}gOJLW)7O?JKf7kuVTtQVoT%HidggHHUocK+3;Dy1IoS!r{) zCDp!yx?0?VLe!_yQe>_qH-Ne|Cyxt}*l9H1{`OoqUq4x%{bWrSA@Bz;_6b^&F#kCx z4Lj(suNAh}HPzUFU7;3SF=YX&E)QTTL35+n)V zMNfakVMDUNzd!rJ`VAXW7aixJr<`Sg6g8%+Z-Ud;H1iZxnjG5E<^?L5v~_K@wTg*) z1-5=dOBDM=)e0PjgW3xyDJdUAxzn<-w}0djnbbVLJT^eIwhaQ=mm6iBHoWxt{{2#) zJoZRyE+hRy)10EMIv)}8>Fxp| zyS%(yCf^EO7{6%pNEJWH()|3l`4AKi+mSZjtSLHQ*~9$&O(_*`89nAt%uGpoEa&%p z`LbXCCT=Vfnd!bQ@cTKiONxFLtqICfGtpwImKii3tPzw?z%w<}6<}?f#~gz=w3$}) zHYhDGFH^*yaQs64rsxNXqs$3g9CNT0*8KH@!D zbXn;6_8WG#wxCHuW8PL)hO5hCwfVriB^GmzFK^h`*w|PjVHSYmD!*2nk(Z~5uFt4` zllStc)s>~ks2XSbI5pEE*hTLBhEA-GSsVUD*Uo?nv`rB|=D=#)M>k~h_U=wrr6Mhj3=7LS+bhq%u z6JVUOHiU>VnjnpVXEgi7U8n|XBPlD$X?b3yIDG#6xgK@KxD%;+0@yICrA0?gt%

m+;e+r~BDW(iyf)$qi&J$!GI zA^`ngp=nbpaFMcp2># z90a6Uws&cLWs4U2!%v?*OH~0OdhgQgk2iVU9%QIr$#zRiOW=*y`_c*Qs^}_oAcK|` z+We0wH`&1Rzc6oqdwt!87Y@T3gW-9p8CO0D5?NLSf5|OJ9Rzw#ksAex_0@B2DO$}^ zPj4@A+T;x6i)TA5i0(-3X2LtMv7(#lC5v+G*RXU-ROLevhkkKtxT-AnbHHD@LL1By zm7cDLbHU8k7X>mF?7E1A$Kv#5oLpVKgZsOsIhKkpCj#vYdn^m1l}j;5M(?YYdEuTK zWMPYmk@lm>cBTbx3w+S1$&4dF;KS*{Yt<>-Y`dY(njOr9XqU&*72^?f9WMZH)hGSv zg(%R0mF0t8VuDx<7^igDItbkDc@(4Z>1nD8P!7+N1f?464jed8MhjKo+6JESqAkjY z#Krf4P84vxB3_W6Z-f($jmU1cSeTzT!q2MI&=QP!SFvkqZ76am6^mlT18Xak98HR)CrIfI+qH$ zp2!voirp1h6cYfY-2*(QTwDs9N}eIWufo?Ne9q%@vUUs@U168$1okC6CV8U0h4TKi z+4BSLC3*)fEvt{~;xrqG7;hZ=;&HfdX0A?uS8hsBev_ork$w3ls-S%N`;m;A2`F3# z03>KNW2Co0&8I~U))er>E@oJ?ay6lp(24=k5QVRK`A`4<=;e!bA^&SO?OQWUPI2gD zze}QjSTg}mM6O&NVGQ^k6m^$v7%*O1N$G)_<>}L#N4tuX%{{cySd|e##X3Hi(7O`D zR|pXw`LlWQ;pI%^c6({$&+F%X6TyUX8 z!sq=@nKy0Pv|LC>#p3+@>2tEW;8@v3jvhT4M>jz71Z65j@JblFbJp3YV|xhT znPky#N@O6cEV|I$6=3gEv@%XU-cGal5~slg4ig^QZDnmh)5eg+b`MNWOq@Ufc-dqs zn74FfUL<1>cRAz}cv(;Iu;genhw`)2J4ZST0vlbc;t|}p!9M6c&e=w~0V(Ln%+o{d zD_loZv07gR!`}sOQeojHk14nNLXgZy!hJbY5PPAX>i2KFR!5>YklbIVgL~xT<8~K z0k<18$XykQGj!s1{o7DdSbWI9H{RMpsa6#lxPIeSBc%Q^(-&ylk`1@RRpV*QPp42J zEGA}x^3JLpb4$HIy3ldV4+UjwugB_wnZocpYkbZf@DN*jFEB5dR@T;15DH6$e*V>U z*rpuTJ1r$}@Imp^nQ?%HMn93w-dvwBy7=R|$a;&4i!-i%J(<{D)eml(Zm2aqeX+1$ zC;kLG(Cx95sx|^m#0w|ET;&uJWnBE5^{>!pT*sZ>x2r00?8>pAK`fZqP-ye{R*=*2 zKM11>4O}kN%#y}oV%JPdaW#nH0AeQ^S9Sd?lon9&`R$bmE)IhtTA*3woG6HTYP5kM zFj0#WA6mm8lN;#6WAw3PiQ#aTL;Q#dLXf;rDnH4=35(s*h+ z*wPNwefS`6zUvc+GjI?l$`mrnR|##FH>Sd%UD(2ER??>DFZ4%o<}b3cKCfvwqmTTE z&Pkz#3)V3Z1p9qdhXodqO*XS+JG;0H36_JQl2Z}N|F9}iRg2#F1>(uL6WW?TI0&7H z%DvGZi)>qWb6nzM=HS?-nWk4C7qxu6-|Ss``yNn-*}``$r>tnUP8S_If0mU6|~ zntMjn-_Ngt(R10@p#&)GbU6~hIrFlp!%#cH7M^eH)^~w);z?v6^Q+uC*{t!3kx7?1 zfskdu$$Ht$jegEbdR>YP0D?hq57dJU%XYr|cJHw22RxR32pLD@FwQ;(8yNJxIhjV( zaWut3F{U&NrvS*|Yfn$iVh167FNN@$RD8ioY8D59Uq9oXaK_0gzqz2Hu`!O$YHccd zjbMf~1_F7(-G60Z=Hj9N)@X`j_+LY0*tJ^f{wHTkKT0N8eZ)XBr{VeYOoEne`+b0& z%TU%0Yla8GrXvlp_yiVb=yDPvMaXrRDMIhvg5*WhbxCpPa(#@KTEr!9Yeh77cW?mu z=AA$|e1%$@qXEYH%iv&WZ|`%($cJG`q5InVjoSz0$xw+ah_(=))cPGu8OMAebn;sj zW#T%|!} zRgXd|mFPK4@SAW@X!Pxxn3<7TTU`;TF}5I5GjSknAm?NbxiG(}sUc@{pAJw(hn1cU;W?3Xpn{H1sG5bDxd&u& zSj!2|fGd}B>_eU@#X+#wd0aG#0E$uhWgEYun7kmY5aBE9|nD?!237<{_Kf1VH_aCH^0 zYiepnW>R@gt7(m^@!K5|4vmp**%Gk$;67XiI+5~FMTm}@u4uX;`?Bg_;&>3dL6I(=dps7j$I=qL7ponf-q%;rCHbV1F|i}oDN_T zOfBya-#hMB$JG#fYCD05hV=Srd5lQ5(r{VwnYO0szpJipO8md&|5p~I0naRhCdQ$r z0PrX=AMMa3y(&ZK*K7`|-ynlHB#?sGJpsVe?~H3;bud{)#^X=-iXz**`TA?49TnQ5 z>$IALEv;gMS-T#J!kw^#fq~2Ch+aOAo4b3BfgvZfTK9CLLfi*)7C_^05} zP754NR_KqPMD7YH9?dYRBs#)CUecTE0Ppx*uUM#qOKY72+Y|p zB&x)Hj8~vfp4zx^X6hCRVi3Jc`L|uOROU z+x7eKSb^`?=&SN~6_7`hB^`WBS|m|9_I5v`iaK!bU>jO^3#~0mDCJ)_wTinhQW1Gm z_|*CHF-_e)V4|mQKzn$2Fq_n!eg7@134 zobC2lTX8h5K9XMaH?u<6ccmIT5Qz`WZCw6S9*`S4bkFHsmR74*9@VJOL9cl$jP0gx$SiY)y0aKZUS zzd%?-1V?kimHV=s$4AX3n-Wz`)0d#HY%!q|vf^k~d$v*8&K(*$A+DB7bU*FW(po^EpL^5r;=B;PbC~c;SV$B@ zh>{GQ(|k2GnBekoWlvteR1l<>XYtwTIyqYt6BBn2R8@h)zr_mxdlE2*vo^qR&b%Ld z91n5#&J0YdD6CJM{WJ~T)!Ea~!xH5>J_o2senq0xZoscxgmB0dd4QIT1^vEz;DxMJ z0qL&aOCPZMFA@GhXiIE-e!g&Gd=TzTPT_>QDx@~GPHeS6+FzGG7v}VfWa7k0(Sr4g zl{)-L=GyrO1&t2edimGyY-fb*O=S7_npORqq~u?EdLH)nf@FRRDXUsXb+%|atRW<_ zXqrykX?#B@{<8!dJ+!*SbRSgJ)srs|3#onJm#!lnGmO8*bdRiOdAy#~~oox)%yG8d$HNLZXKI18H<+p-1-bC!wIA2pc%SC)4lf zlf$l-u%CL4fJwUV)>u^i4>KAB$(S0}=U&mJ;?Vlov$y5l{iUscQq99R|IGR_AVnQ& zX!h)3qaGL-cy4o;8-A5gwTKZBEvaEPPESp6zQ$)^Z=iUrv^$mVx=f=}P2?&W3E|Rv z?qCMNivk9P)Y2$5gAg55bWn}8p^74TO+((a60_N_n zs5*PN+53CMx-WnNqG}I?Kv?y(8hTP!fJN49j=l-r@(HZnKcOP{hvrEgCT{%!*yfJ- zu)+NaglmmstCpm8W+-Qs@9Rvn;DxSeehgmVszlYMXi$O@D_BEY6WDNQRK_f%q@+^c zPgx^01I^6?FDw0OZJy3`3*OC)J=K_+@KxeIL(MyqXS2C5neI;Kwj=*m0=xLHm*u}& zlHHlU_<_I6hCVdj;+LSr1NN3Ko$afDOQz17(NQVGo$8#$%^; z!yaaQ7L5s(G6>XB;+D2d-%M?3@;7KbOjB80BSaibO-+aBo-6i2{jXK=(Evks+SLRX7QXsrX^gxbM})o%^#ghfST02|8k z0Y%WgsWx}^zn5<<0J}&=@aZ?vsAxsJQGr_0B>p^z$iImGaR8{zy_OTJTd!Ab_paJS zLu1x5HZcOhO^Y_mq>`eu)U!M3m?z6rS21d_##+%pWpUVHgiGS!qBIjxv7n6b*Y)=F zFg1@G#>$e{Sga#CckZ0A&n0hXMF@YeQXcf_{eM~5X9Yxdn2W&t%#I4;`Vl+WOQz6p zQdq7NFOw@ODymSbHT8^+a`|LTn<`}bpiOA{E1XE8IQk94x4pbV-8vs`d38O1U0cMN za^g@EXu$S8{}~H{BQES~SQKENdc6&-WuB9}z`IU0_qkF1!I=xS?Evc_Z5|k?UNMh8 zx}pkuCr`!e*C&#+TlF#(%J~G$*${z9`OH3vIyp(@!@6%YoO8;ClUFZvhqn!xDde(! z=$Io2kiV0YldD3&CUEE%HYFX?K5t@@0n!Tvw$by(a)D;nEzZ@F6Vr}3?S*}|L^Dan zrKfdA?wfhW^i4ghuA+Ny-%1-taHijY?Y3-tfOF_9^&fD3$p4=er~oT87^T`Dp9i&3 zPT^?%-^frr{h*4%T9j~X_37y`_~6Bh6e6m2(z7*2hRoO}hP9z42RuEW$V4@Sw4Ow5 zxTScV-w>$i!Gj0;bAm<|-W`+FX_)G_N;QmyYPY+B;1)=4zBV<4%XUZ0Joqv7IuQ|( zJuoo}ikXFOY3+|Vy3z+_=B|$qRYeZmCjfVv;-2VY*r1Gpj-?Dl7^eIYvCK$G_hZbPR zW@2T1H>5{+P`2nUyWjjiHf^52asQ0a(c+?HwQS6DE zq#_bg5Q5=4JCl0YRf1DD_mOww->;1xgxOB>-SzhmwyLfD@h~tj&IAWhAVpe|SPq$M znWJzX2qd2{{Q;vRhhd3c7M=8DgNL-~nl?DFee6}@zXM1z;+@7=#)YY*i39R{jo0d; zCH;{@wIY9cZ-B@Mt27pZ=m4CZoW6ywh!hu1Tap9?d>YD-HfYzpU}{R(ZCftx_){?7 z|Fd9*+1c4Oikrdc!&9-_w@Uj$IM0RJH!9e@uv7(ZefH8&TmQ`yja zafqMJSJ-L%2~QfpY=U}nkmcp1tgH`WYxI>(YTtu>MHCJ@_Z1n&ljd|X9X`Af4jZZp zYD}J37fswYb(kLOHXNEOw#>@hja!DtfTb)12w_O6im)Y^2L9gpF?q`w21KE}x#%;x zv2-M`dt0g5VXO*sR1kp+L^0|Z8>pz$yQ_|*vmO7``j~Sy_r$byLFyLqyk?Uv1{?nH z2CPCK#2o$p-2P7Gw2Sw{*TJ)Wi#NB(SyNERy7OQv+(2gp3ZlduDUjoTf}cSDO@IA$ zx;1E@0Nr(DOU~wJ7i+T5FFwZs)D3<@2WQQ`aLw9J5q9we*~0A*Ir#ZyUi{KCf*FLB zWp_m+ydhZfu;u{6cO#NuxEvC`$#8LT305Uj!>+(GHFbrD)^aw>l!x}2fuVU(DR7nw zWeYfhdx(kqQ}6h91cTFpmpViER8Y}m*!paD{XQ?*Q%o*9({KDa^^d|c{y~HCo84y% z;uA`sVO2VQM=q1awf9A}^A7D~N!M3!jZRqW`vE4LyBDY?>N%$pnm_UDU-JL_Nk-&jf%ss%O zx9;2t*OO8+3xX9OOr5@uLqMRp<#3y{hxphsF+~b7B%PzozOD6 z5^$HI zS)ifjiMfE)z5IfLuaKgd2@L213nWp=3!5Ibq7|pYrstPttKU3hU@_W{$2z(|=^e zm}6)9E39+{PrmCn-M};W`ojk@kP9a-TzFQM|L)!Cx8>z{>&T}{8S)))+3#+hcLZu7 zSZ_PG&ZcKQpzXe(hb!Bwtx*4r0{UKJK2(jb&6WM~l%V$dy+`Yzm;$$-Z>JN119P9Qf@LU~~kePn{ZY zN=Z&WLV(cA&TC%=2Fx-==H@4QMFd6fg+0o8cZ~5+9n^64QE=CEnlap=Q?(WY5#5CI zBOh9P>W3F?XyCDMo^6Fb!9mZTKj)FXwmm^mx376CINLyX!}G~=T4&CjQSlu$FDbQk zaF9XI>Sc4EhFj3$GcmdGd=CI_ESNvjR0}yY1Uq-G>(u;nXUd}$|G@X}1LcA^*nBV! zdV}Ke1#V_$S=!z&U#_DC{H{bE;P%Eskvuy-esukDIDyr|Nj1UttD$eMtZZy(xC-N; zB_m~Xs2BOGA$CyLY7vRdlfePi&I37iwPPnwp0w2eTb)XV_ocG$stSfxjD4yZl*n@5 z|K7RPtuH>ia5797%LrT==Tzkzbs zE*PrPr3C(DKIyf$|GJk8bUXk^iS7qPzy{s^DU!a(>W#KJ!-$Y%em-Pcm3TvgU%R!t zyZd1#hXMCXQ6Oe8L$@qwICZGdf+Op`za1P*13BiF4Gp(J(^I;YM@KXjY3+I|$iF_4 zbP++E8>6qw<$7a|1;0%=lY8S1Wvvyt%mBB4i~3c$_$0fp|L8Iy0L!;JsUVzm7+Mbb zkdc!=))|8iB5c!hi-${CSj${o`}ghrI70G&_3E9V(*UM_f4}<9Kt7|cIOefTi_x2= zr(rbuC2rcZs+h{y$9}-2_SaF|RUsoQ+k;Zd?Pl0SvUkT0BbzJjI|WG0H0#iL?0`>1 zPd9f@SoJ|W)fv2DpCBy>4w0q;=wMQI^4NJO#m+J9<3!TTGV@RU;KT->Bbf>C#WShH z1uW?rXal0FmyR4Cb@$s1G_u0*!HCD`%c~n@`3SoG;^O+WEJs)J;4Hb+ob>ptvnfHk zFfkpsGF&%Kclytk<-Y#cjwNZPb5T1EHL>{~aaMM55&hZ2VdCaCj^aw(&zc1z>WddI zJl)2?XySlq_*J55-2q8CGq=cdhX55L6n6Of*5(Zq8}F|v^gHjLs^Skp=nN!Q#qteo zBLNZBl)tM%3Ya}rUa1Dle?`Ac{*39^HHf~6%*S)~!E!Jcq0@tWNiY1#~7x?u& ze*f1~XKwt5y<9o!+wkxaY8nQHG<1TZ?u*l8zW3S##5XbJyb~;0eHoy^zmf;df-re_ zsb5Tofq|KYGd?cv>-g6hUmgVG zL%7FNKPc5;(Xt|E72~V;>mW{kL4ilp6bxOc7kxlse-mALdhUTw`_0MjQ0&`PLCmgz zIY=5vQ+oP$(<+8Qo4)nJgz?BFm2}f4c@5L3<$TS9OzTOIV4Bhm4QVUg37^2vSNr;Z z=rpY7k|44JtR3?Clw%Q0(Y#EsOwW2?JWWP5T%+2tV}FDJX;IthBVj2=!dfiY>I*&7 zRh1vnFw>Y318)%}sR6il`Emd$#a_8-6CPS(_Q1FkWI+JtqNHS=QMcbKKvjgyA8$xl zty)4KKKvV@sI`>+P0V4a=?0Oq75O)+U2z#`+(6vt)ao}#X+%+Z8dlm_;!Y3m@s5hi z3#)SRY>w#uA&nUO`E$d^lz$s0ysGW5Gi2fO+`02&KmjS?Uw{VD`jqZZp^qv3r~W*7 z=;rJF0$zjQ*YDoDS6}j^v_0P@mZt*FRRVlG4J)eZ>N22(5Cat0*VET`SfKp}1T%C9 zYg45%fetz5B(rmKLJRZV^nu`_j55D6-M6IV4^2lm4NK{+3Ou}EuXoIMr2vVJJZo;B zGqBP^gm6f>4aagAdozbFNPhdVF8w>+XNQ}UgPYW5A3WHxFR4lw9-Deh(HTc{)z}eK zy+E`94znSY>bM?{g+3bJBMZ+lU3I1$6klFCj{}zHgFJ^TB^CsNhDmRSwXas+zm(djF8ku z-@Oh72dWB)NSx;sl1Cci?yGfTM36u2R(7UMuPhR!7VTUGz4a?#JuC)6YX4O3?%%z8 z9Ds#_x{q^hq0aLbFCYei5Gk5T2I`_KLA5$m#R&nKw`N|H7Zw)Y+L%OP17S>!kMHmxAsa86 z(7QHvF%?GX2vG+)T1}WFi6O~GoeS|(7*3-ztBr8}x`ZmYo8c4YFTXxAw&<%YrrWub z1X>p{Nm7;%$G$Oq9-?Z0(!ccd-hXC^I(CSvuw{``3&N+^*un)4quHysE|q2ICNiLAEBuHuTUp>2@i($rJ5cnMP1HeZ zmbi)hj7!!rR@Hc)rd2zL;zUi1&%sO!G4mbP|3ZN1-vE1BwMMP; zrzXl$=Eo?>fTLKJPte%{FH~y1X}Gz33IK5^9v8Vma8gRv;56<;PcQ+iJjq2a03EQzn%USaBnM zIxic7s{&zxm9fECwLgRSEgSq%Mwq0fWSl=>crdQ#_I5@;bi)ef@7}$8g;_JUnW+W7 zUer+t1lRB1zt6)3$s4TD$Lt`O(PfeXy6}Jo6ukQEAP&AUNzD|k8<_W(T+@vY$b~_p za6}!me7<)#lMq9ZXz8~0g2v>5K!2>X?oX2Ww*}PI#rud-< z81+{8s$}4g#uUG0f-5Wwfiym-RQ2IZd;#X%D6vIv5p8xpaB3e1qEk;9k%=Mw0>>cX zu~M1l~Bc2D99_K<78^<7!TzPE>FVS1H<}<0>jA7+I zYg2u1hr!z&kiyS{%Svh`X5%5D%9oS=_16>l zxszHSbQ1=BTDzGcb;WhHH!Kg1fOWqzIRV`t(yD@&w=HBTfk4V=P$xX@i}r~*Z6qn% zVdh*O^IQw`MwK`O4|2eR2TyF&Mdan>-@s2p0Q%&XJp$%bNot8qK4^0>{y_`?ro1;x zMcFn6-z=DVAn#L_*>-?;HlJj*#E1Qiw~e+y-TH~W^Dt)v-_EH!-jfuruC9dZTO|Vm znaYaPC72$(p`Iianp#zWY=y6ugzzWoVLAfh)Pn!zJR&rY!#zn1=o+UK7mG8Wi%K!~ zP{r`T5dm?&;SGn-wjD02pxZ{8SXE|DuxLz7B*Zu>Y&cxhOTGS*J$NWXV?I+O+Oj)a zD4E-`N&m!R!|s1&GgnOCDx+Wywqd|8F=z=!3M3bC*h#!HNN=8KQ#xb&^VcpogX#tj zo7}Q_^Mf#+S%O$^t-qOY*+7kjgbF4~5YU>*knxcPuDaL-5%coUbU=DG@yV!RX&LC{DYz<3m46DiJxF9Tib_Hh1jz}mg|$=i5HL9S(cjO%J}6|iqy4=@9C zoFGh6eE*b}&clVn047yb?NJ`6d|LRE0=-wze)3|}7b7CtkB`DI2q~&Lr=3@bu$&;L zRlsO@koqOYZKj7?&*dVhG^fIE$zGZ%SiU%(uL39HlW#KaRO7G&UT@{x^=&w-#qfixl&%6D-b5B?xb4N0kJ zPAv$th|15&)1#)_epd2}Ep%whftW;4(muk@gIyx^j=2;zb#V^bH8Fq4o(umZou-LM zdk6aC`J=|nK+<>;&nBR5l?h^O93M@XU++&6W1#2)V84;g^@r#E&2RJY7_5>qC_-`P zTT`?NDU47zH2QpeePxiiGGLrboZod=uI<}~Afzl(;+X@ymoHx?#sZ#o-T!OTrew9y zBAB-T;fR5yug{}B9{NQKSu?=9au*AKS*v+UoN!Onqo||z*a+|Fak$Il|L5C%H~UZe zc%h8my66U`QcssdojTu{Z-Y@&PH4+U*V0gbO)%v~yaDeytHW6|nY<1|YFT#5wT1SB zOg?AMojV1uL;dq}jPTZy;W|atW^G^O9%#Xof^euNXJ%v7S>p{aR&j3bLp69)t2pYZ zSq@Vw9@CMana+TOjZb5W;*i@z_%3?eyQ!&BAs+6MlG71S7AdLh6dtzb(bMoi5gn+E;fRAN9FGXf10s8%wl>K`#=vsc7cI!6=( zw=c}<7<~4L?FOSD16Y#*6E_Heq@bIB_*Yw@0)P7dO|vk)-+&=kf3SC_g=TQ$KRG|N ziaYl1^#Oo+)7W_QQyUKdURZYVfSMDRF0sPb$*doYVM~1f4ib($qttmEqT3*{ntZ<^ zZ!Bz!hO=>xgx~)o8YN6S?g3+j-4;Ztzf}nt`wR9V z|LWKEfMBx35Bo7mpO@H+sV?9s}R)L?V9>PVr0|t7+ z>p#tlE&z*6LQ;eW6OF@F8^9z3cfsHA_kvV9z|OuE4^U7Uc3)eWBU~&pGo@#VCJoOM z87F3LvD?Aku=6nxGYG_VAIzqy(KkVyE1`I zSeOs$^tRIL14T+POtYbG&rb^L&xf>1Q|HIy!$5Xkk zf4~nayHQdhM59nB$vo_xl1w3Nv#5lOna8zf?TEuXth(j!sld3lA}Cikwfu)dpH^ zM6+?<)KoM#8;*{a)>x3`bVPlqV}T)Pxo89LcIP#}98e57^&4>dWc>qGZty)LBxAyc z)W017UW5v>ZM6H0L1qgC?+-lFHUzkU4|Y2k+J|Bxk|-1iD(!#(h3Z8~W#-|KSGW_Z zhRQVVa6NV8CU<7O}N|;6Mbmu#3Mt=$JNCtKL+V#>~j3qn_a-Nzk5S!tF5zhYx28-zaiKcZ3q~k8+XTr zQ8Q@2{N|vZRwoLwZTeHMohLSz73{XibGLSU0p}oSwThffP{jxEc2mMK9*j{IN)9Zs zeQ;y+>oIg9ARXaga}(6yQi>LDerej=0L!)v`9Qq9)hUjUx!BB8xq~FAw@CKZq3jb> zv<{#gor)M4@59Jk2H0sUB)y)yRUHR2KLvqwQPI)gU@e-OuD^Qqii@9ry3X_d32(jQ z6m{ukLBK!!(;*1h+FDH9kU)MtC?xSd5Nh$1LXy>Ii<5$7#)5r7&R#r;bVYALW%CCW zzYhXFv-pP+DCtN?&Yf#`Ij|73Zw$&>*wG1c>vr^@bY)1Nfm|+H@H`z%WrWI8zygo~ zJ2d`5ElpnxJVx;#@mJ@zrn=lx!60Y_U)Pg+rkcI(GKE-V&do*vI#;@|-#z1)%DHY`Ffm(w?;9e-bNt zqUm)EVq8BJyV>NK3!biic}9_G>nle&|C-9Qvlf*(yVG9BKQ}unF67Fd^w#Wwf*haF zGrPo>+oD}71T9`}+j`)vLhiS7YAoB|z5eNFBn=JowFtwwvFW9t0@EJJ67#&Z)5X@( zvAl2QyOw5((li_;my)GN*7A?Ngt$gLB>t9Xwi>db5}Nrf%dt;Az1KQ>6LTd{IkP?V z(ZqvA=oe;n-lFNX%R;lZDd>4(6E6Tg_gZa?-SPG2ua_=e0=Aq~vqkrv6_DUm9>0Kq zz{HLFV0>n+b$}B6DubzG0us}LMq=Fgx9wsHp3r)iXwzGShiHHb$5w-|2`y1Mzz_oD z54#Qq4?88Yd9YigLlnvvTW*6^B7x}D<2rIHp$B*ZCxj^Z{r>y!KFi&f*}@443D2$h zEDMTnYXiFTIZ{LbRpyIY#3y;LCZXzgr3Ik?cD1~Cnu*H)Rf2cfRG#CWsFxOoXn&?AT8e{aoeSe*|AFPB-AcZK;#de)^105Y!R2fbmiVN$c zdy0xfk->p>v)BNTfx~&vRFVp5P+;q2NUUk>RN_++8wxokAYjv)IprDisu$wYO(5OE z4ie!;@}9|DyLPR9x>ehKn z>x`a~;xAh62S%^=W)9_EL9DvrLGkejuv`wqyLY=_A=Mx@>+zvmw{F=%Mb8R42FdUA z+;JDqpa0-yrT)v)vHo@8e8`3E2Xi(MN}%#he0%-z=tvA>-w^1 zK^P?ma6!hC#iNlCJh|^>fehLn&hY?1p52 zHjy-gq(E?R^3!#{()#sRmZWGW-N(sg@K% z0b~iyy~!_M9)-j*`z!aNX}iusOn_a@ne0+9cb>Lj28M=)9&?es{&4ywHf9Bg_QiOZ zS3$GzJI}d52#ks_KqXnB_~cuI*qRPhn1ocjFu!;$|80}y8z}RZWzeb|C3=>Zj}HhU zf;}y^8QjL8k0Ln2-+ellJ1I7L$BrHS;Jx&VB@#wZy}_sj8lXMd;qBz2yblXeaYER0 zW>Cy4uk6i%;Bx+A!mNNd7eHD|A6nxapFMkqhXkZ@NOCiU@+n`7y@~qSAufRE_(C0? z%#}R-Ex2Px%L6$&hb`@!`BEcA?MxsX={zjQ-jS$#D)}Err@$if5%{FY2QZ_ab?ymJ ztHYjk0PyM0x$*rWs`a_NR!m$Ih4R<$)w5yI_;dPxcY(|?l*fXHB4ic7ijT?kYCj@+ zM}iIjtNkr_*wC?AlXd#!`ku^@*p2z53^?$+oEsM)&g?Yg3$dZjW;{kDrlfOIL1(rD zz_kLPNsc38%Y+ znqqbpuTrssSH=F=ERahDxW8pn}&2@pPax5XDjV0~;ow zE_eWJjZ_5WPe(&k!6FOPpFWs3zMAsp%>d+V`JvjHh$lh#9qGIPw9V9+Z4(41wgOyF z@dX8vyu7?GfdUYvv548wLz3%k$G&h|f13&|1zk&U0kC^x!1I{nE?g}0ClGnrH2AC zi3i>cXI0{5QIYic`1s4*TrpoiKSYy(qWwNlwNVwqsbs*~+z%>A0HgwxDsV^dhb^gH zXcW5%>@o;72EGClz%fV#OrZjY3B(Mj85wax5o|SJt&pD&=Kj(sjC6jgQv~=ElIi&7 zbT46;w<&n~A6jwk-lL5c6a+i>P}IZ2Zl?gn3rz@oQnqI4^Z{zU0+(be-dIRC1x%S# z4HzoHLv*PS8uW`7M?lQHgk1+*jumiCUnqE4`iMJ*#Vp44HdKChUTJ)q@B3-t{UO=X z8S7A#L$U5GSmJ$3tm!LFlQ){a{aAGLwCkLxJKiHD(viLa&U_oRjPzzP?kL;ezf^-@Xy+bt#~#oL-qlm;Y}X%jJp)g!H7%v1E3r_+Toh{9 z>g~psK#k9WNJ>z5bjB&S0gCQdq26SGTCi8w(ZJ;d`;l}#m`CZWEP@nB zvscXIuHptZ7lrE+U^oX*nQL~>`LCoJyMPS1UP+qIN=!^V=|vdeL^};0lJ$ok-KagF z?Fm~?azk7~v$_rVfTNTd{1wZ&J}Qszp7C13nF7cYWaBZwhOh7@RNynyJOs&~ zQ`2%m8la;~m<=oT2eLc~yWY{%2x;jkIN~eBx?V7#R3yKtdLxaE(md|dSCGa?XG3MK zL5Vzl+8?4qQA$@lgl0iSrtDLvPWe1|@BrkqGvf7#w2+4`-|`?ca|MWwKfTGs!1e9N z3eW&wW`^pRKcjqXR-IzV#_(EvA6sUg6dn4QB#bZ&H_!NE$J2l#z@{^SORCC|k36`N zBYS_mFbPu553puQI2`x7(H)!c*!s-g>n8sM4(0{)WY=kxT?WwgeafKXo>o}`FjwWs zM0u_LKyy=5sZgCH6Jo(gfghik5Hfs^R43)ggWhu@-b`?Es$HbWA8@VznAJ`TOUnW6 z;#EyTtM|G#5`s`z>2N?mfVoco+qb8`NUu!-h;~&U6gp7fABQ@U7Y5h$V;<~x?%eUo z?s4NoA_Z~{3A3@N8ZPWw9U>B z+AA|uR9^84Vm@%-5*R~!#HmabM$h#Km4Cl;_ion={#c;s(JZUZ&_4pP%B)S{{_qcQ z2!jh)HLdf zA|f+OE?_~0goTa79mDdDuI7Yp9K$cFo31^xtj!n!LQ zragHyT+BeOT#87%L(a*Xlr+>vbpgBZUOl72U$);qzD`bVpTR@N;b0NK8pZLwBR7P- z``e37_ClKtR=JJR+i2J2Kz7%X-dJrdt>HK}%>IZ>D@Af`t`XG+-24N!{phBYp#1TF zfBCUGaGCM{*5@C~@xRsh$71}CHvYL7|67g!Z&pJ+d}14R?iL6hJVc~dKsazbDBMV^ z0`&|m_I@xP0|x>n_`wFf*M0I|gCNk*7{@8<001uuXa@d`(K;`bIPShB)=2oR~y3mX3##c0SD+;99h0KUY3;@lAIahpiJSd^HY%meua ztO#cVAlTa%+N%IW@DO-oYmJktvH)v_(q}54W28v11ymBCkJi)EV?!oA*wP55fvN$D zMu7momO&t{Db!Q6gW`Y{5ZWLA>eX>J)qg3Aag8;|LgdJR*crG^!b9Jw{g%}Z;^9hA ztOwrJ@cRJe=oQgrccklfV1=$u~fQxJp z5Gmeq4$VFIqN2!@e{ppF(H2kj&S~Kb9=dFb7pDE`d)vZ`%0)j9ar9+``s6JZtI%9Y z-yPdh-k>ZoVCE;||6ZQ`fJ~0<_4(9ORgQY7DGZCg>IG)A=yl?E24cO1ts|6RK?phB z18;`GsC!=?^%90fQ03c@Ij9S>x0krF#E{u6XL0wgKaWOYDP)6de1V8nZ35Wt@(5tF z&Y#Mne7ObnS&Q7aS?t5DWqa`6KXUN+U=E zZtvsJWk73D8Iw31x;!CP6JM0U)0&E51|?4dBnEoIT88t;dNfYu62>yRAKjhQ2H?Zb z748e;2ks4je)R6$JEv45L&L)m$LYcjE*1Ld_W-1Z!xfnMEp?fYe|Ta8FekC0C>zfS zJv2WcwergdJ5z!AENKrBM?sMQzus_3b0|H>XlO{npm|0-mhyW8Koosw;scnbc=b*3Rk0E9!YaE)SU+iM zX({J$?s{zh1p;(A04b_dmnV(f>{|XvpUAB(*q!u9PQ8OfL1J`UbA9-P7W!8V+ouYn z|A1-?0T9F>ZV1RTVv)L*hWBcPc~n2GgUsxQ5Ca9vS|!)M-{?&sP>Y@e5?35Zp2NwX zP$Q$e#uuk+9Cu=}%nRRND%*W2E;^_v!a;CXLjQ_kuo-`%2>)t4go4O`ByP|Jx{N`B zAu*~^*GQqhtBYM`^=pv&m*)^OHaIkNEBP4uFz&rAtsoYx(CH*xIxinu#_XsM4I#g2Gg9?!~}hWp)uALotDBS$P`U@(YFyL|6k9u_HnUibiggj0!c z0dP?EfmLVoUYX?~_grf-63Uf<=%s@c8fQ2z-~rh)QI9*!Vm+Oz@o=Ar2r{c5cZ|(~ zFiK#Ly)A(qPbm-Hw_d!iRjP22{Li6 zAuKXlRG<`5?APgMi1&qr_b1S`#$*? zZcBK~VfZl35+F$MwB+;-0QzUwq$WQUcMSKbQ;1J`ynZ2ex`!#!xuxQ4VRZuq9+quI zqy)7_3!m8&pr`TfXI0%=7xW^AqFuq+e`>03tBF+u!#N95_&R*6wBN9@(tuvmczh76&^y zbWJ1>1+%B$kT9 z?svh7!fkMdL>AjKvXjLYg|k15Ma=epJjL@lsE}jV_mKSu9Y)RNV^RT4;ykORze=4wAT zou8bzX2p%s$&SoFvof++%FBnTvB1J`A)>XThC=**2dhcMx2;^v;)c0IP6XbrMlS_n|4EkQer zVe|kL9B%;MeA9Rocw=vUcz98Vcy0A_7KpC|_L<&dZ-G>{Tp1hd&}^ zEMx$JzBgujp#tR>QTPuks;{KC4p2Ts@o7bY#D?N@?>?lG{1i7;fWW%Moo^9pnfN*! zJzec?gdB7v%=f6HZAx++?=!@IBp&V@o;Vb#dye8QksX0>gX0b0CQ}bYz7amp4_Zl? z()VsaxE4jPcTxD2+=jYy(;#Y|m>!z_{2eArMI;&`by;faKtCC=l9)Tbmzal3D(nq2GwO zU?kL|2soX-?cZBTvbQb6s<_iR>vM!KAH+Kp`M2soBsb7*YH9$;jN1j$RoC_O-0Ld} z`LQd^WOVJfFP8U|?-6Xj#_UPO_f!w5X*afgGtBb-aN;08A?MRXy<@u#_GHRW%1Wko zDO&T5>9=WybM?w=@YjC;bbA)1_mq4?qV*M^lpzBEeCmuL&+Cv2+8L-s`q z*NjZv#i@XZh{5&lXM^v1vEvs#P382webqbb_X-PJG3*)n{a>Kw3vhw9p231mX-i~} zPIc#t47uF6;nY*4`=(JhHusv5QLH@y^f8&yHZV{)LH0OrZ_Ay{O_4VY;2t#wZL=-xMfxp_8&NqxzYipy2GX1ouD#4 z)WU}7G=I36`a&zIsRlE5&(f5-#-#&aGrGN*H}KE0l(D% zxU8+6NrqwEK&W?UPjKyaqm}O69DWUdy#>#xgSD$G<5pKIiH2;Rg~AtaVih%?~c^LCQ0q!eB0*fC? z-?JSWNa($gU{(9K)NKFn>7nvBybMF0UAQb)vEihrrgiARfuf@RK7iS)w8M=!m93U@ z9vfX}KX9Nb5C868BzlIUc#b~q-rUX|T#t1nbRe3g5O(SfJ&rh8w{aSXutCcmLILd{ zL!lhqwOlV|Q@rkkun%xYhGyk)2t%3_T!!gZJ^^+A&w=TX*$Z)xLnx@jzm@wry2Td| zk~OJmM;cji%CSG**;tcRx-?wOlz*s!c|)qm=n_FjJ9gi*!kVK;P1=iu@m+}w;va^q zxV0)unN}0xrSeX#?UtQ=RPoWJdpMKDD)nFk8N#xE_-j zJ3-dlzw%EoP!rf~&=%D^Bq&9dx`S^wOMHa6c==Mt1c`*`7b62C`n_d}B%OpECLMZ+ zc3o-*kSO!pDni7Eee3n{dGayPd+NIS;2S<{bketT`MI%;hT;QpGD(bfk>m?p1C+pC zr-kKYil;6--}$hk5n{$5YJ|}|T?PX3keOdC1|hOn-AQ(hF;qnrt}t5na6O;Iqdm7Y z!Vol4Byk~8^|kNI-(?69$sbW|G|KI>RSq`QqSf+LSA&{4!Hw+{<#@L8>+sR%U&JTg21bAT zEL3-QWd%(6#*9L=O1R!!n@=rmIgY9)Eu$R=e|MRv31pd@W7XMGauVd_^oiX#`7I^n zsm0Io?J&M74sm#TUPW-G1LaFlU#?Y+hfe7G8<#QqkKW@%?)37nq_9nzu24cwpJL!O}`1*@hFWmSy5jn@!uOIHn^Vf96TB*YJ2;%#GRJccGFCCQ`YV?bp>N5@D&1L z=Xcz1Ia~KgarkoXuRa!12Br5tzidC7RQzPz5HlXXB2MGdw#AsV5;(Q(xZilp!GnxK zLZJfpl`vs;y1rZ8r3FEB}@}O@}3hzM}c=L(!{@uU8d0(uB(m+<%J@4f!QboApNz zvYuL@_^#ewnQ6!9T{!M{i__gxs)tELFm`w5%9$QQS!{W)=fvNkc$?CVDp#Y`ZyheR zW?n3HcYD_ez1i8USn*=%MJ5B{*VZ#ZFIN6|w4~$u`DeTKv5SvpUWBEmFU} zcuJ<1!AOiH{9T~T#&T#ZT!j9KqnijpZssd1E+Z46aG^BZY2TI8x_j3y*eoWUeBD&1 zyCi89zDIf``k~1}-kC?!?Le6YYq2wrJezgpo{N=F z)$&tM4q54e%f^us2Db=d%S$C)x?HP zFY$T-Y@50=CVlIUHDPK()rVO?jB8=z{x3)PJ@7~DzWFgI6mG+URTa3gofK8|a@eFE zGfrW?A*|^9>e^Zb!2`00kd$_~IfD=`gv1gGpfU;Elm7K_;d@&MLJD%P1;O5!u@0p5 z;^EAEx+|?~vA*9dq?{&|FVHLx$#d=(DPH@W)o+BwWk2(~F9*TP z0ehm!_9R#DmXeZ?X1JT&EZR}4#?rcQp(SwA6GBTe2?Wr_%vrgeJHbxc3%MNDuC<_m zNn{ZLb?Kg+Lm(vNrATDSAR-*>9*+KGm7dYhlzmz1hU&eJh7~m>mMIJ)6kQc-S5G=G*+d3 znG;n7?&*(xz7-Lqx$w zw8qBO`6x0Bs;roLK@r^PWr((|QCeKBl$YKI|CeKK4zgX!;Qoe~D#NGWphCX)u3fwQ zS5_FjzW=dYtzGn_-3wXHgi(1J3)k9CxRCx-*t*YNG=OsT)MnF}D}{XSb*zGD6sif= zuXxmrJL>iOPH2^-@fU6(`x%UR_rdBKLawMs9~~#GF2ZY#h^wug9V5t10S=gqAz_5! zLH1&NswdJV@Bi{*$Xj{?AC#S0VRHsW@2-4t&MFv2SIk2=VRm6FM41fy!AUT#vE+Sr zwP40`#?qa%F5zFCcDLqbEk$|J2x9dy=b0e*y2Yl4BbM;xB5N!eisLHYQXhJ%;#9A&~G)EC2o-cHNGxnNe~isWF-TUXkWIXSB-|?ZvHF zV%XnB>UvAWwe+neXlXGF65gyiA&yAENsCvw>!Tiq2ZY-G(S+a{$yff0Q{5 z$Tfn0Ga&1H86V`$4!VEupNj~b9)Mc<9$Lho4Af5TNAfL5Lsd!`vR@vDwj$psDF_no zF&xlLchiJx6+}_cCL?1cTsI5=eCbqn?_mgo8~k&r818Z(_)tUFkn-J~`;v-OI*{$l!KRCJ2pFym&!5=<$USwK22bxq!4!C!@J{RP|58gpsG zWDX$Q1R2oyQYKY@_jL$hX9LfN&G1|F39LG6KzLK@snS^r9}@2S8%e&7L1m` z0^~Vu0}>Uzfv5SZ&0B6;9h|LedDG)4nh$7{yiTA9C_wCT8JaeL6BDD-D9q1;xYip4 z$?SpCLeJ6QzDUfVLix@f=_VO0v8zo<{gC-Fy=;hD2^Ps;)Eo#fS~e$iXCI!lAgq!yw%PAwi~g&9e6e1Rlo=I+Oo4sXEfh!7L6)Bp1mR<@OwL&`gfP0d%BbkI-N7n&lI~XM;O;G_Eq(o zeR>v>hW%AZp{R`&L5Dpr%n1t^W*pyfAD=E^S4Cqt5F341Krf4HP6!En)**F|W#NkB zMd`XC)KMLM*)>In-9%T1;Cq&eM0&uHUXIcOde^6&O=}~B@g;N&rQpbbq(2Vi(q@6w zWhgXP0Y!)EcFC#e*Iq*)-Tr0G@kg3qx)pUbA>9_9wT&-y{A`=T@fsAb8HJoNo( z`P05e8?#|}aAK69s9#X3zQPRz#>QL_DZ%`Z)60e3u}RIY!#t@Bl)G6`IM?~>L8Nn- zYqzvIa?ZeJ+W5pq#R=}RHLb&}OIB@%(6L-g$sCap0Hy;vr|4o|dxps!!~K3tr|#2W z=dP*XY5P+)>F)@(E%621z$+doy*g^mc`OWN?SvV+nWLE5ZfVk5D(OW!?=j2k@qOXS z$Y@vko6vv{o!RZY3z)1#HIJdB3HXE1Q{q)+lu7ykleKWaY%yRIQUZsm(m@Ktz1{D3 z|4Ij@ZAoiPdKdQ-2ru-Myy}qBuf3aUdayQ7Mrz>u=N3AwQa3kbGKuHdg4;tX_Yk0d zr|`i{G;(_h{jTf%LN;Cs^V(ORzop0Ow?F&y7>=sDwWXs?Bt7#_q>fF|m!wPJgO}Sl zIXLNSV;=wg2vRM~h+Fy|$q=twQV)mRPZZ7NWbKvI!^e0MI|>K?%Egz59X_bY5XD-< z5X}Ugirb1~xJk{cRVT5aCTf46E|9x}+?Ymh;;IZgo442WyFF3cu(-MEGLx4R)HmA% z+OtoSNA@bqOw<*VtRL}A!(_dlF{xl_ElL#S^GAcY?Y_UkVZjvSe!d>j%|qMw_tj)N zZW=6{{h9i^SSTm7DKj<~=&3dBUtsuErmLTA-_oaB*t2PV`BCk`Cm0L35|1a7^-7q_D1N@|;*RznXcQvd^-AQrl^mRA9s+NzLSj+@-b6wEi!z zuqvFT`4zqMYeG2M)y)OpY)1WUZvmh5_vTpcBAdAMuHPC#`3o#%!u{voh)@5c1tOwUjt}E)=SeDET1Iz+hoZVZVi7VJ!d5I z%;gD5k;F68Yt1d8t?N})egmf74j$}+zpngI>^;yEfM0%}uRdjPO78P1?#KvwOz>HV zq5_>U74bhxZOSxn;DuSg0ntHqm#Xo;?$+sU7NdM;(}IaE=CWKcg=!d{GtJ#zEMwqY zcN|}*=S=_;_7ZR{4TaqB$y+Cz|0zI7W5cOgwF|RzZpaWXyjWgZ^87|0RKe`^-6h2L zzRTKk`O+ZH&ZyO0e|RP|Ezx31TOV;_tyH4iq&EL?PGWCyMY{8(qNg_?5dy?JR(fVE z5i)Hp>loG@>OyO)3>%4_y^N11^$wDIKAhp!eXm>km#91kuk0Yu4MVR&zQ?i5|8jay zX1X0a>|yV&U3ZQ5V1K57^s6^!7J=U>-VLH5FPYNT8eh7k(RA`5J)P%^EF6ne*=>k1g2{e3{_WPAo z#sF(+e;QJ2N+82YKX50zud4Xo_o3UyYtX@gak(d$%*G}*jZ^*^qi{Ugr*2`1UuxMV z{Y*acxWbm|9A#Kso5Q+Y zuK(gM8C#w6Niqj($La`580P9Y)GpwQfGDk0cmC$}W5N{XgX__lTqIKumKbpv&QBuj zjDH&R?Pwz-oaWLF$YFW}&-Sg;yv& z*T0IfptW5bfjzda=IM!0SDv#aQ)Dm&CdF_k11>`=dv_RPIQ;diREeTQl_+tK5OauD z<2`tEY_Bn8BK3Y$`VmrT`v+A4^Z$b~3Y#YA4VSfHX+#^akS0<)#fiG$gO2iu=*uhUF%q>jd& zIvV9eJSQ<`B*&Q=!hps8mo-aH;=x^{*@X!*4uRBvSI`;Se&d|UuGR19O#P?02wYqTKqhc}4;UzAMvvG?(kb#U<#C=JeZRAoKpW}`%flhxs7j{n3>Ee|uOMuyLfnZ79(iW} zj-H!Jn1;ux1l@4uEKSa@*ML@(9eS%u;I9+&C~m8)O$C)A0Bs=r~PT8?SFei zK?yBTc=**S%I7%z=I2clRZPa~0$53D$kS~lJTbN8(a)+-$?v$b$xF0h;pFz4|8oTA z)%TZdJqA+eYq2tGv?AZE9en zQkz_NVLz<-rR|8quI~f&@V_3-bVTV)*Hs{{pzccQMT&R`&-=0UpTqg~A4e~#DX;)U zqd!;p(9}rtC$g-a-?O>HZoZ5qs~|%jCGUSKBkDQ57F5=`u{8d=wXq^~ai%U-(o%;;`c z=vM`D*NOZ;CUne|_AZ=-l2Z0uTP?k%8II&zR4-Dp;^uZ=BJz>QiD{1%S9RGugKD#z z??YiyYq%&Xh;c1tm%%+rH9&+`h6A;))XV^~|dzS82{fz2bjDRUZp2GtZ^#G$T^-5|1U z@-sRrZ77q@o+Oni7yRIu5s74$ef~+&m4uVf0(#tVR2HUitn8=0-_cy3+4Hp5X;T{f z$I2-@4MFF)f#;-0aLNv{+J`%QZJH|9-u-2kb8tyI>2g-{X85b^>hI!>&;NKvq zniyra%;vq?@q)B^=9s?fToy%%-lVkLg*G9HfdS&uZ>398-v<|ShTVhwS6q)hkw38& z7=|qGEvhkLNF}?$7MZS>%CVEOKd_o#!gz8C%|i-Q+XOyYYkScn>rM@TW|40X8Af>R^aN= zc?FWp8Qae!eTAZe;|!@}VsBp2^LVkfO`Bt3W?{dYLWAvA47Xl=f_gZGC_jP~B`SQJ zpSDS;b1uvzpTx4A_hY!2XY-eMH7Re@Qwd9!f9h~rW?^~JVHr>SD4c+5GCSnSQIbsS0XJ2oSNka{P5%8Q@h8Nv^+=)tXAy%?ag8uwbnkawleimpbgD zM{aY{%5QRs!G^SNUkAF6F9tTrue(RQD#d^t9jdA4l$pvXazF6-Z7*q_1nuAej4b)M zXCRda7H)2R!}P9`*bJK`?O%yoFyn?0MQSs*DL=Tv&OOH@;U*x09vaCjQ;K#_vXi=L zU9Jv|fjMI_yRFiNw16fVpCLBf0H%c06-_GpV%QwjY;CNKf2-G`{PVY&*}AZ8=1=w^ z!W2(1c^8`=P9+>#>VmMT-tFP=UdUWC&AH%~6L}pB%g1Uh7O;c9m&xn6JaK@!**mF+ z-rA$zh||COQ>IdDm&EMH1yC-K)Rq;01g5#G9vRS={X!AzIQ`eHY<8^!kwQk!GnJ>9 za2jtlkQVW36Pwzct^TjXuIaX-?1+`TcxBA`coc8a`c~{pdXxhRHbGl8N<&>c=B&xX z)0KIaF>SNI7oV8)z6e4+*zoMP&g;~1ZnE{<`sDfnI-_-0LY*EbpaH^1+YJ@s4`7&A zlK$1j)0(NR5}U&3B9*Fs$!y70u<`a@i^s#NdTbPPTLml>0~Ma|eC`XJkTjaDo1+;I z__DQxk&$z~T)?Cz?VFF!l|0QO`%5s){Fxt>%+6CqLhdzX@lcT$9PV%M?=vHh9ev4I zwRjG2POd`rk62ER&mD*5AxaqwNW3C5WBV5uwmh*mK4JQ!lH9sk?A zx)UCQ_@=Bv#>XBn_0^DM(M`dqF%iZQKL!%}XQgS~l_?ST6Zxuen_qAY)pi%4N`Lzo z;@clr#C%()v2AF{F$NlywHVq@^ZlkI8!c%S9G+6dMCJXe@Y$^F)ksYA$y5R;YFE<3 z`){Q1Q)ZATMy0!*PZ_bK7_95J_n^r7+Hb0Yn+JpWm)F_pQyq~Jd+n0s?C)wh-iJ=t1Pr;4fMJVWa-marY?oq5Zdo`QJ_I{qN;#Gi0x zOWZqgOPUjE=^{s0v=F2I09w7xN<&?Lhs0q&i`1Uqm}tmL6}!1qx>BxPXYXC+!Aq^B zEcjf}!kFiQx{{%%V@EgE&M;Ku6J3?hAF49iPv%jA%~YnKe?_RvYS{lK@-8m=Hyt&< z_~e}q4aRk}+DcNXd$C5@uCbf#+@=<{$@h=cZt2qjoU-s(=4c`w#p2~9wt(`QZwT-OZfyt`!g>|@xyE%;%A^Cebi9Dz9L(~Ju-^8@7 zBAk+AncYcjMhgr+b znt#HuSN8@#>VT8p>{aOBRMnBH3kUDa{FBBu`B$F}`&n%HqR6@)0wKOiUFyw&51qb8 zZTt%Mznz^_(qf3X}NjrlOu0}kscIxX2!Mbov3*gP4Y~-Fl7Ns<~IfS z5&V`u^|RY}tAHh{A(`|c0lY0?>7v5O8P`m5&7)2l12zc)j5o!ykFU0tAnCNoao+v1 z$G6!7_+&p-B@dfSDjP_oqD#R$7hciWzSt{tk_Xd*4sOO@J5_q0n>}i|$c@Uxl&IJ| z7c*cuA0^GT1nN;!`HWUNcV3Y`uUx`){{d#s`WH;= zfdtU}B+P01A}FH`zfGC4EPvC!3mgf(N<&hnV}w0X!wg70368cuyHcl2ATe72dPK>S-vNEaJbvxFmhQQjf!tdxeg^u1&(!LaANCp?O% zdei1f7|rYc)a=q%HT67AC#Dob#(HpShT-tJgVd>YQ#n-H+K@)4P|$_)7)<|*L#&Sv z0#dj%hCti-aD8GE^of(8QfsSKuU@T3Z3bQ69wqFH$0ZEcLv@|hPi(%_EV1{lk_Gk_ zcDOQxvPh$jls$}_5NEs_Qn3qH^L$1Vo$Q;uU@aVgALwcHr@o)(W;%Nk;}m@(FvmkO z-tPu1oD0jKDq%_@o9$UFOt!M~Vfaf zA5@%|7V1gtJa>o(xL_@t(Y|zXryD2TPfTinFI&E0d&$BBDzO-%(UcI)W_tdZ=AF10 zL|i@=q~tQ8MDQBDrK##o@X3*tz}o>|GPqDONOtN zXwy#n$)8wx60)=+jQ5`XZOf70OlYgmY~P+cS+kPFG4-w1tJiEQbFs&=IJVB8IH=<; z6T~rYc(KJ9TpieInr2C9796_H;sQvUve4 z?(df4%^&1-52b4TOhIu*8K}GCoGPshYFM~*@){=k3(~ZbEc)5BcEMt!=K+<$kLLdZ zR?68!&o5-GVJ`lk9?)Pc@fk&*hl;5rv5Rf9%}ZNK=0;RF8XX($!?CEgBn%Vu)$QM{ z_1+x#7kUJL%x>}u(^^oWBt;&-h*M*ZVWdp=hw#KxX`aj^NSoXEw26w{~+yReeB zrhPN%dAYG<*9nW<=G-Du=NU`hNY7^Zpv^d}!F`*^7j!jYANZB`sTO{>AD;PD(D~|c z9WD0#YNoC()-^h8#ZT^^?sW%5#gd-$Ol!T{Gp~M*JS#R_8{VZ!STj=570rHASNyH7 z-2mcja7M}6OqF41Fa{GoHI zZPET%2mZ}_<+s|V<8t1GwAi%|rjyV@&&7~bT z+Q=|M56eu-Iw`;n5Ic*vYBN7W*RsSW%dsW*-PAKL_v6fWK4QZ0K_|Eyp+jCXOAxh< zpH$4>Np(5RZ0>;N2^GsXh?5F7jk8WKY1z0P`LgEc?HBESXloSNHi*mq(Qf0a5%g9P zT;o=pJ(e4dubPp5GUqbj{|&>)u>j`erE#O;6Y~b|o3G{>0)GP@$!fcyTHhk$Y<8bAa z*1T21C%vp8stvpG-GPF6I;T2~Z|VDe4=q+A>oP?n1TRis7D}S%;PVeFOi5$K61)|sDk11wxjD&u*p@}KWhCje9Y*kDNsi#X**|meU8YZES~nS&{igN2I$ynz zVbxlcv@!ewDd;TPx0TYk4SMfT+x+ordu|frlH{!4$E9Q~vSiV*j4DQ|sWvA}s_~~j@}%ErHXgS7FI_Jr69ZDvwDglt zNPlafs?sN@ir_g*dGC+Dx@bItF-=dovFsgG55Em{BA?&w(sJ*#9C0kP8Q&s`Vb!Tx z%I-8uja1*-pyXld)_;^ z4uv+U$RK7>RX4&K|MU1fzs36Y0(TGzmcrScaHO^UL6twY_RBS_F6LaugeN+%q~oAL zS>7MJd%9*zUpq2Uf=`KIU+m+_k#2&ro13V!?M-cT%lekSss-KFUK&i+^d~ZY3PX?v8{48@epaAI2x*vf6mfuls8c|rNVB`%&Z3( zg+;+Ij`g_=117t2U4t7l%T*&wHWscQ9X$B!B?z~KB#s!@IuNV8Cz}Wd=&=%)C*m|Y z<`n$*nteR57UJsY`wXYKtmU#r1LD-Gj>gII z35FO}ZjK8gfgRqL_i)3w{Kqrrv7E0Kmr})7Yi^TAw(T+XES`3J-ErlQ&OK4WCwlT- zyb46Z038$bw`hiMsQT?SlV+;CIh9^YQ=-P243vaZYZBU0LY4N{Onxk@3C(H18@c=} z9xzvZplzQuJnM z$8{8BQTa0T+of}qF5^B^JGuRc4i`_tvRVHNBXoLo=>Tv*?A`0u2Akt-)UQi7zpesD zvKTD<#k7cT%IBzN_AM&hbIy|cV95dG(5{R#RQ4{VvX+qNo2x0D{CXS>FD~@k<#+#3 z^?ImoflUs@O55icnZ2nC{&?ZUV(}5u@||YF$q)i!OBaaFR+DYrr}`*yEoD^J@;p)XI~1!4sO;1n(5=y9iS!o z?v}gCf3$eomG&>dm2kUGw&Z)4-s%ob6^kO93~?fxi~nfd2KiGe`+c-kgZLj}6={X3 z9(%~_uAXj_y0rR#>H`lvbSh}2E)^Id68~oA&IffPBg&gH)Hm}>A0VhmR*RWfe#5}C z=<9ikv^hmJ7lWaOb7l(I_c(tqcRaym!qPB$Wo~oZf3TL!#-lsHse4peGjvY)_U%7cqN~H(cZ1nI{#R^lqrkV`FIu^gE38Svrqg+P2 z!mlajXWu=qw>A3zVeCD?vFzVJ;0vXvk_MGTT2vY+RAe+|H;h8aD0_!8dwMF#DAJJi zBuYZEGb=M0*_+H{@6CIj*L~l5{_p?)9>;qfzvK6a`~F_vaemKzeoo4@-|DhB;!|Af zsC1OSt#$3<3f9sXOCWBmc!X;C7KcTV^q&J_S=nNA8q5_*aX@i6>>u?v)o1=lf;PbA zy|Mq6Lfr4sv*iidi$RHyMcw@xT*$rXoZiX>KfR<*>py?*%f3hE01jV>2^Slu#gWeO zEH0qp-m6#m{av69r0a*)^8VThWCYI?O==@)Voptan2J2pVs^63DcYT{QZU*5ZXVK1 zT>~mu7+S)qgt~jJcP(Wkk`moFWx)`ypHAAoNMAgeEq|u*&nrwh*t(0w2o?f6O(DRo zE~uY{?1q*zURclp)gS8-Fdtf4r&0^xiipF5d_>Qb}!C3ju8~&cxL=bR{IH?Z@&FY_`w_r3H2f!69~R z4-Uw5Uxmsx`Npz|m{ZN6h$y>UUcmcWb_AT zLpKICEPTWo6$I$o5||tyKJ-8lOo2`1E`WVqG0;X2FXDGaZ^%|Y&^&edJQw#8?!-AG z?_3 za}XTL;5;RcMpT#e@8A5#H7i9U;SpgB-44Z&F z8sK}GIp336EEbQKN&Coa1wt4|#x)Iz=YNn!h)u?HWlXNJ>Xr3<6}wilB-Hm!wk(ri z!_u37XP7=g!|`mcxgT6(Go;na^wxH#0_op>@0FV%SH(988AklKIBNY$GY0?Did96B(VuvoC%QRim^@W>@#<9KxDY4@x&z0Zc*qQ@;!NB zex?l$-Z-xZno6)iOVhba-Xg3}b<55*+p!782ZKVDPV z^grlw1)#}1geoq0(UXe`53tG;_SJ8+5se0^+^l(Tfq_KeG zA3eUw2Aa^h19{kFFFOp7W1QHTX2yaSSHeg}LPur6q457A3&tjZx(ux~>9?MH8|vj= zcp!D(vvll(}2sR>9JT~HimZ=|0#tM9Q<;?&Np~gfS z^bXMh%+DE(=CqsE2+5h!fAlZ4C<;_2;CraPuk0DSl;N1ty$|P}cEaf7`7y|@07}|F z)cHq&1YyDykF>&BT>^!X*xxhSp%}1%5c}S%+QT;b;PjV`8Ec?ZBD-bZ>iL${t*gxK zPkJk&n2_8Qzr&LL!?W*n1l)WbA}y)%e@HQgJ}55lPj)Uo+Qs^Dz@T{sP@iHRInC%} z9}(<;wIg~zbVG+SrcYaf(TnB!(ExoalED>`hTiG%^=tRjv@0J_6d8;W_y@ZA*imlQ zHiuy7(85^_Eju@3wedEGiLX$py9N5BPxGPq;_?|q8dCR;pU2n0((m8Lq>|Q-z z*AQAxW0lw<%`17lK+*Xi^N|);+KLUs6bNP%K2!PYh{KC23I~+JXVpRL_PnuBFOhdJ z7W8fL>Oo|Oe`hxKVNDrytoBH@MNr#i;)A!T;~kXgbqS@Y3JGe{x_mUjt`CBpu?mFn z56ijy9p3wF7Jg*7K-ucuey!J7unQ+5-l~?a=?#^6QVG9zp|ExR5!T5<5sU=~>A(nE z)c0p2QeAJ4LalgSAzx<0kpCTKk+-FXIH2nUXEku4O_`H9d@ICGo);f}?A?3l!#wOE zD`LD+3G#A+j})=dni<^6!E$sKiw*)@v}7Ihws>33VUb05H|XlVW{IcP%>D>IP;|KY zSZm$Y`NQ(DCy>3W96t)q_=z(4%Pm zt$PRw3YbTtnuqF+E-M1e(>81oq!KCAIt`o$0Z_%nA)ALF^q=}GDD7RR4ea)OWVpom z$I;*|5BJWS$;Yd0hhM^@{Q-*KZ;t|)ot;K7plB)<3)G2+23nUo{=OLO4y|qsvJ)mU zCenwB?K0x>$PEqYReMlgjw*J${t2P_qK-fbCz1K_=HUD(lEniNyhEq@j+@YHNhEsW zAOSL9M7+9?m52e*S}Y{@P8Npp$4R*CrEM&$ys$bL>it(Vcg5yy**sKY2O!7*G@|%( z=FoEhM2;*p`YMPwe_K2G^KUC74SCgMqb#=ISe>kx9e*H=12YqDy3@dtZIhgsBUougd}A*HU=* z=-Q@TIZkt){Riez^<2D<6P==jP3^cDFqVy=yHZQ=KW1ijZ?4cDH&8-%R>p zFxt)$+II+$Zi51LM3U`jP;tplIJsI(FgkO7x@il^oc|4d0q$|FcYbbd<1`!PYlQXH zWu?1Vb}95GH$@WmpwQvbU6)7))LzR}T7l1x#K>=dW>u%oQ>vK<_w*ioq$ z3@s9~UnM-C)ig+9>k_fUAfE!Z1RGdfLH)49Pjy2^$*a>3b)Z>A%;X64yvu>+WSW!n zOyQ&`HgBGHrx5=zjre)y2m9UDYTioZyU*cx4xlw+mj?aCb`8jht>Ev|e7VX=;%gL- zB^~OvUdACfoE`y_#|aYYEfb6(4QcP`h?u_##xmp|(cYtcJKR42OpI4gXkeTcc4(V~ z7C^wE0KTye@F0Fu)e)7b_T$EW+rbN$b;P!JTU=Xoq|2cx>!Q(@5LJW6H3-yi21982 z%vtTQp72gAG3e^Ok2uZAFdi0Ce#7K4m{Mw435vhu4kY+9z3wi5 z<1KP!0$_!Ak1~ZiEdb9%OuoB8+j0=C9iZM8+>D{0u^XZaP&l#nv9mOzZ|R~Rp9hU; zZ7qaJ1I(KS@oFyEt0OSWmGuiy8{e0l0jR5A#*14~wdkrtD0yfpWV~9D1=}Cp@JPP? z{rOrzmhJvYYNESO>`ee;)%EWRV?#&}_@i_+!nI^DhK6x70S24bV%M`16V0Tk2NaX_ zpIm}aK@D1#g}8rtV{pBdNM8a!)4CZg^gZsTRYhj;M~s8Gn6dh@e3uPXYjJ_{bl6K5@9)i=cLP8WMf+rrGJQtkMD9+_kdg&vx-zAF&c@F z4Mb9z;sIm?E(dnXo0}d>=}!Sz4TJ>|(Xp5(8{0I5Yx)8NBlg zq-oE}2gcrRJcYBvkm0pFiySzs1>BkpeFy{qtq)V$gb-mp+M&s&T%NO9QEaT@QnJO> zXa^)_$;%13gCCQ%p4I4q2Kl_w7#uoF|2xV6fM)h5&mV@KSO^cRF@6hBbr3THuH3+U z|3K%*jrdNcI~97b(90LH6?_c3{Pf!RTLKdTZr`>81p@m^j;CZmzpdo)I%DhF9`A)o zZ(UHs!5je?-nK6*`M&GJCV|Xi?1OZd71{*hem*9=(O7s%7XF&ZB9Kze0o#*eA9W&d z2Xt^uk95j_o_z?L1)GM_40_Ogs=E#b!}$m$k@+q_A{j7RjYItMtGGtG0nYyqCII7x zS>P7|936)Eae5;HU>tN>K-Uu@Cgm9eL;=5%8|gUrAboTze8lOJ7vp}P(2H;t6t*Gg zEtl9Pgl;cHn4JH~HNUMpbpZO79qD-=*BbUr^S6B?A|WBFZQ){|-ipvQ?T08M7naE?QMg{&pVW@e$^#R0#D#rY8OPAr5a>5esz*rTOR+kqu`lh= z)1)*&Y1LqZ#*E&eCLxG6_(JvuS3uB+k_#|-{1`MD(5)MR_H(AQ9a{7HnhT_+s%@b6 zg3!R~hjWkAg!;rLi)ii#HVtq#DTONrZ@~^0dy#9_5XZ*Qp>IQP^L!X8nLNIVlDY^$ka=+>J9UEwMbGzc3Hr#SAyVFvdqqi1XP zS#U3?h`!RNB_oG`v!wfq&5zUAB{>gUYTSr%xDq~ar1QD14k$n9x0noUo(c?5L_Lc5 z8sT?!3F-KM1wJ@0H-l@*Z>Z@dcW*($z@z)9bF5d@Sc~{3*ip6rQ%^Ll8;LXEx8(t< zDS~|nfWC|-JBL;NHp}kHk@EBdi z3y1wv$?yj2P6%n9iJav#r+DY@U7U_oB#)Zd{%UcF6$h7O{UIDVdTo3IvDKG)B$|a_ z04irmlfNbK?vX!zELcORdcr?Kw!VO}p0rBJui5^5U*#TIZ%DXbC|N_$!X;U*i$Neg zX>PQKSiyPj!jwz(&}pBeh1=xnHt`Uuhvf7jrWT9vT==jpy61iOMg0Q_#jrg%eU(Vp z|L}S8qk3gt`<8xy6g^j+|H=>YZ;#~fscb*#3tOSjoiXsLmVQLUXP7dE5s&mCqun9zJ{xA;)weckG&YjmVx2@a#hV80JH z5v_tw6xJPZ@NRCI)AMby?J@li(~DG!|JSF>yhiCSp_}&n@5)~9&tzb23SO|u26GTKY{t~kF{`VK`EIo~4E8?sb54|ZT zx1X>ti={B(!b z`ejA_0i!R{i;7K;Pe}WkC4yT|$6i=-Y1}nPsqZIi z;qSG3+~YT_Pf&VS=C1VUfbrwM%OwB3@%fid!r!mBcRexQ{?}LTf7}|FUObY1Ui)lh zS)hP#?~Cs<#X)oZVk1-Ug&y`6&h%d|Y4vXQ2c#3=5rq5+8i6EaCf|@(%01_fqR#b< z5g$)IdpRHV`~;WNX_M>LRuVSrekkRVep9Y1|1PGxdS3j#OWoz^H{IlVDm8LaJERk# z!!2N?;=f#W(KqXg#Y z|JMig-(Pj>?z?M0qFLS}2=D4u69|?aoxhMGqCn+QJ9kj$>mjqi_I1s`QN8B;T};{p zk##A4y&xPDK2g%NCHr0Ac4E^RDE3O8Y(ISiK!*t1{f0y`bP*vxXt0hthpe}+O^GJ+ zi3rQFg2mZoXZSC-!y< z0mVIv(%ClUFZh#UU_dSyt-&o!=EI7p^j`;;5Jat!;txWjjCR@R{;U~~B_t<4>@VV3 zB!Uw`h806#A&Tv6}+8bCF-{3d@&#Ej_ayu^h zzbt$5?tf47g3P76D&JF?AhRp6tl`NS24EZT{C6su0r7M-`k*9!^oypm=U}8v@oawa zX7Z!jO4BSV|ArZ=gU)hGhJ~o2ZPgzV@>%A3Of(kRISEf1a++31jd_sgrvsS<)o=8a>gW|gZ$A9(NWY`hP3*(M!UDZ4wZ&%g7?s8ao3tG_ok zvP)BD{k*4}!QM}}N#k`Z3aY|zOX2x*lg?cXyWqLf{MPQVA=4=hPDrY8wQ;|z*HgCB z^fTqvZP2KS{ON6X!81+I>xa$cog4+OmV-Xwaew@uo-!9LEw5*Zp5>GSAVT%1m-JjY zL(gH)?#aY|9J1ZCjf4#NbB3qbIdE_T3`gNU{3VxKQM~lDABkZ-xZ5 zY2K9N3{kFnnKu44J1LGi1rGuGwMRv%AU?{(Sb$rTj4Q@drgWIN-j(vz3m@JVL^)z7ZA< z0$k66oDBlWO{u$p(|_+Gw6St@B8N&!^0ev0tsZ=m=;$~#nj_$1+jT?^1}x~y%!{wc z%TOt}J4@lFkCy%!Kg?(HIakm`@sT-GbB_Cl@bbWYc@xZ>iU3Cw;lk%S|rJg9$pN(N*bX|G3;fOr2o9?1|<69b&L3b{4 z#Zc)t|8MH8JqI|x76K@ZC9S8w>UQSjJ>`1-`x5OoZlG~P|8<9nl|a~~uZO2JG)9|} zvKKU_!?W{f0^lQ!TUIE^G!VTX;V6pwqGkqyCfTUV-MZ4Ym3j!sd$eCk$6ecxL*lcE z#ukiZ>WFO&;@^2yc^@>9^Nriv>1*!ygL;|tj?<1I;t7BEIpoD5 z1!0%t{*MVNJhv$&Um+WJEz0972l)mfbvtz=SOFW!2dHx>q}`W4yGvQXo_2V@bn-sR zMSZ(+@mw#2`TUy8VZ93Zs0Ocf++SAFj^*+P7K)npRvIrWi#)LT6r(`OJrJbH&~q2} zTqTk(t?>Z)nDT!v;WhG!2jPztGnB(|xA4)E{QtWFlyCDC`72Yu@gHi4xF9_`uhXOt z)AWCd+!>w_<(dbSW2m6M_|n<`uNM;m;qoA!*~#_6cT0H}DG1dh{vWUZuOoSqOqYxV zBxx;MNgQLgCSObRx-SyxX>z;dzzz6?TKOq?g|?|e+-5{^YA-MhYdFw9B(=EL5$|!k zmWN-$Q^zNs@qZrGY5b?ZhX2bd11ih@L(We?5|ZTRD{Ec8C!v-*y+|J-Tqwfp{1 zBieTIIC+lB0zW?`{4csy(tqqqT{$r5=G) zs*L~O5ZrX6(|UF!y(D)?EB(;Caie*Oa`bCMC@TQ&GsT^5DeoReDYIDQunKVM`)%LZ(d6c~JM8RHTvEvToo3{>@k|y^f4@ngamS}XV_kEXeG9+6+k$p! zdA*$Psm;zarhErpbeVRSB?V|3GMYG6%?H`K=cCR9+$<7{@Y+w3t$}mSiH|cK62mg$ z+j-j#QLaQ5Kh=tnTv@NyMGRhI9X=om*LQXWDTAX2ilxjmd9_JW39; z(r4wc9!FLeFW6JHFrg!!k)Fu+PI(*k!va+52)Qey%J2dAu86Pi)7bn*UdzI{&A+L5 z1(K#zLM{E0D0H5KsC!doyvO;~qdx4A}ny{ebigh^x@HJqP7m9($} zRaynN{&91=BzQd>d7#>te`ks~%7?Z{dM&376Q874DYEX$vy=9vueD* z*Nw}$HPEs`YtCVmTSN8PUK*O?1 zFp<}Gy^-&Bbg91J8*s=-H=G_iw40%2-S)FM~lBDZ& zO?-lcLdtOer3owZR^23XI7-)o1Hr(yX)21KE5VNe#AHlK9s6C0DVvudNbw$e@BjdH zz^`M_?*m}2Ss)7JiFo^7kVbUrlZ_#V^W@JTO-Qg|^mcgUWW47;?V9hHUlrk9jn^>KuVj}*cz~7G zQu6PT;M4HUM#%5vj;HFcA|v;1fmq4suKO!zIxjT*v`w}ihmFLf)YZoZC9%0QdfG|A za66X?yEX={Ny%Oa%tuI&+K~3g%X6c-0-O>FSCFwW0#l7v%DuXVe3vWdUxcD|V`C$U znm*qhJiiAUIII=DZ!NWAn#YuW%MsNmYn8~#&m&{w<7Z$WY;N4h!8Qj2&J(G+kT_@w zQ92_=^0L+3y&vqPFP8^~GOX&(im7%wZJPSK1Kz{mVRaNi{*#Bl?bU^}wzUF+`Jx&} zlD3>NVrd$(Ue;6(Jy2-5tOAh5jY(*%WX2^#T5h~pj#JitRht&|WV!}!qIrN&f>$}* zHseAtRa8kA2Ye!HvhcbXF*XE=C)t=xfHVL}W7!aCV^p_WMxV^Et>Jc8l6gmC)A)em zNL;8|aMIk&vY_U8!;9EeBG%x?E3zdxq=9o(H$$)tUa|K#pXvoJhkWNlx@xHocc32B z^@OJrbLs_}g266HBb7|}{^0H|(d~!r$VFVhNeO36}?DlrkWTUdHU0zGSf%6%W z0gJd^HpXZrUW}k)56m?Phu#3K3p}T9(BlgQ)2n5`z8a8lRNw@+xNDW_S#Uo@TgKhM zzk-Er{c>SL0>o~Tdp{PoQgdvWmzOiw#5UR`+ct6Du(8R86k;9di2U%Vbtk5OVV>6= zi5wjP$mbPl?}88^*$yGDM0_(eA8615_~A11ir8Tv>5b3rX0LXxAbhVxX1A#z4kQD@4w>;!_Y}jDWEM6w56IIm#>BbV zsS(WhMM7s5Z!Rxq!8CrdUjmZm5cJewX8c=f1+bZDl}Jm7PNtlgop7ckCblomO8ZB^};wYesCbH*2v> zQ1kTLtD0+?)VKiy%(HOC4Ot(~tCBaC=l*ND7GLICRcs4=@3CU6O7tT4-h+PuWMH#QHMYT*z`FYG+vh;{fJ1}|n)c*oe{j%o@#+OxG| z<=Yv*MAt7sv##9vnE@`yOmJb@ENtQieUT1epBcSl-8GPRvKLD>vcaNig^Xe^jK&X7 z%_dzf!4^b~pE<>mExD=2fo;q*q;zA&~hqp<~p5+A5@4xxiF*D`!=hNcb& z=f|`bgpiyt+RnP-?t3X?H;f%);RGfmYuNw1i4qA`Bxd9xIBhD*>>8#0X#Vmr&pbjX-~FZJy^^q*?O=3F**c6r#n#*n@g=SZxL zSx8Tg3E(F*EXY$`boi;*&IzVK!o%U{Pru(?O0_jb;=T-?7`XPq$-m!4>cF02TL?pX zMj}wg0z8hCTmTr9=kA3tcIm=gRI#%LSL_+zOtbqu&wal|oT+MT`ZKmzvXOrvw3peEnO=nC!(XzG1xZWzYhf4oHfa~xQ@fhtXN-3fT$RO% zdY|^CZgy9iZ)xZ{?eBk~cs!?dmvvPZRcV*pQ8PxN`~BPHDM~&Z#w)ty|EPCYC``C? z`-P>hD-SFMdN{jc`AO2<4KsH=^Pz|08c{o?bs4q)3iWNz_z5)K@i8D$oyi|UPQNxH zEhN{q9V`c4Eb6Cl+O+S3Q$?L}HKbb^TiOe)$S=BP_fAs?W5b|Y1V?kmOhk6x4P+cJ z(g---{oXBJqV+VRn638r8yA+Y=1Iw8sg}mAy7jml+NbXR13qny1HKMhMUJnmLztb(&J=Y(;nA%+rIzVs&U|Oxb(R{`UJr_0lS#)8=_orb(HQxxIuqrD}I7- zC3kVk(Yax>Rbj`l!nPJp32RllpFcHAI;>6>3k_!6*0oB}Xdjun>J1wL!02+kH~w1J zE2=9q+hKS=clpYR2uM*P_=h@J`W4?Ut^?Gq0za8CV~3g_kue$U!SkbU+Mr{Rm)p;i znIP4#Lsi+nr~59igT%xKOIL2lhWu2l3lsoBwVQQCEO5eK-Q5p@f`aUUo3cT0B( zz`!$rCH1vT8Q;ByoOyCQDU(x*!!kSBNtImA1G5FO@Eol)^Q&odSz@8qGU`=rpdS{} zJYs@7=vt(ILzg*s>`4`Lv-5?U+h^gX+b)VPh4(9n_QjLMYN$N}+?BpvLU}1 zn$ALIq$OlDGG&ZorVcb^<|6y(U|;6hfZGe=Pzy8!vk?Od=EHu{N)rR%D}al@TP93! ziMqs07E3Ki#jhW}5d;vvo4q;ui($eeQk7%dEZ7`-*86n0Tx?FJaFMOcQ*ZOUz&a>k^VhTSuu?S42H${C zMa>HAfT6$v$6e#l-0PEzEg0jVkBVac^^uw0xMg?p>PrT(qZ1~ZeR2`T1xxNd%d#_h zzE?k1UCNRp9F)(3e?w^8?F1N4`6DF~TyKJI8JR%OH>;FtKFw9}eV73p3*~-b26iWx z{HU$nRIOnxkIKQxI_G64vhZKCjm>k7$t5InD>d=yba_@(uRA!94(}A1`p5XUjD7$$ z>{a6hw&8FdWQ7eudj0C<3!PRenCv(^cwfTf#i8rMHbIJxtt^(%Kdpj^P7Cv|pl;-_ z4JmD0-*c}b3g^Lyr~!|w!Y2#LPMtkY*!xUEUf%}DukBHgUjv=dW34*A)qwJL@I?>g zM|!n+iJG1L>&SK#YT`4sCD#tJkUOIC?(x2}kK!Z1?y9-mN?81tqxzy1B-}nEIWvGQ z<#3i~E~fYQKoh@5c?|or4ma8Bq6r%sfkP4Oe1=|<7*WkV(CvBSzpN=}2~-m_pHfw= zR_KEwRxIUYWLcG9Kh%o(f(aK_T0|(h54bGMY?3E$a;d%Oe4vdgDXVK1gV&E?<1E1J zIh~@h#qrpO+a?7*+ydrJY43B{TVac0re?8yA)_M6mL72)h5s6)y*^yE7UT;#KiH*p zlO+qYC4oWUh=_&aGp6u}KFBF!A3pM|5GdOdG)t+l3k3$e_<7e{GHC0mdN$c1+{dDk z;;npi52o<}Qegc{N`fUaKl?HbK=Uh(*@^MZ4b#)puRs}l_?Ys(1BM=y{fK@&XKRSr@8-AKDywDMFaZOetez#VyKYBZd{gD<44M_b zbv1OT{SYJn;$YZqU-C10Z~Q;dldeLKE8;m{rn3tN+_@G$-ZV?2Y?s_IxK>%fL+>90 zPty4)6|zR!Dkb2D(#b}s>G+zF*fvX!#G?FV)_mtaUQl9;peYt095jTR4*eK-@72?P z`7kqCnMM%c4Op>^)23A0ID5R0Y|N)_mcktw%Q!YRmV@O(`Kzptn}XG~3V9i9=jKWn zY#+Hszi>MHtgs|8z$A+gL;D|}GzHkEOKJ9&MO~4VMx>1*6IRyp;NEoS;ml2ZX@g%{ zK1J=aEv6Fif@-Io>AwO5>)`-O=WOAs^OWDocBkw;kX^v}#^!g+1L*v`( zg^a7R!DRN&xwLle4^T6MXBxU}jTShcV`3#&;wDnN(tZ`8;>+ziHwRTQxzYT&H^v}n zTV)72Gw`@JuOot%G>t{uoxXnk`YEPHrl*A+uYeC?Lq#kw{@QhGC}(3E*2@;XJS=sp z&(rixpsiYH9!Wj*KuK9O37%o}N45t!8p@jV?X5PX>H^iv2}OF)ejkFjgK2pU z^Qsj`0W zENL>8%TtY98{g&K!QJ!2|EHcSZ&yb6l?+S zdXBldxgoz8M{cP57Gaxj{E;Qs73?zK@}1la-{W8CTOL7iziX`eaCl>$qn8zTw-H4d z*Vcob&!$_(u?BLGKR?>g(zhypa2|@h-O#UwT{Z2YP`YP)3Z08+jA4O3HnAKX9c9W; ziJY5oWngwg5890xP=R3QRY>{3KG5PMqT5Xumuur?^(EmLIgzYrAja)@nwSoIXH_ag z;_4Rgc>U_>d6+p@pXr&D*0Ddkh7|v*@t66D%=!lOb5lLPK3$oh()U@#B1+IcXM@&iY(qY=KLhS z8#~JDC&Enf4roA?^L|-~rF)JJT3cR6JD;PHa&L)+@lwkj+fhfsLhWT*(2!hn-=z;* zuN4Pu0w#nmGXrDehe$h$ii)rq*)h&zk!WH;G0cs@IOBxb{+ct#)-Yv24Gd=CvcG92 zNlS7>hJ#>Ut_@ix_fs6?y?Yi)K2ElOTh>;vQOf1cDBXHgtKpFh1QI*AjKe~*0WLl1 zCqZ}U&LtdcPuAUBw#A%lopbAhU9APXf;ol`*)olv@!*(koKL`dd8}h<*8(O578U*5 zv5CsZ?H#ZQA!bd93-6QX+6LSvX2-mB8awrjM;0xDw=s@Y45jufHy-f7@+M~S$(BI+ z%(a=T=FArA#wF@AHG6h#w-vcIGs0Xm?+C6fG7lcRtsWkKMiJwuV7IN%R5+)4v2KNB zD_z0B8(Q%G?P1{KMo@%=`Pg75=P3N!*w@F_+c@vEW3JcUB&uy$(;=7n*-0phX6Ks9 zm&%=j^cHvolZL_Oxg{I-otEoT@e-s;6{;3c!-D-iEg|Q;%4DFiDcaxV{>s@Z zk?SCy#>dA=I0&fFap8cbrJhq|I3^)4ht`@NU(q%8DMjNysh8Cflp*w4b z_L^iBwq%vv$xp8c(c6KGj|-3vau9JLVTxyBuoJf5SwJP|$jnjei(g1c406n9z#2*p<@$RJ65%x6hMo)(GXp=mfcwL240_#xiy6 zPs3jT<*;4$*H5JSPtE~%W{L#FW~c+zfeU#u2#d{+fdlqOef?&DS$GJ@m7JWMSY{1M zub9qwZ|zBcF!A7F3w-^U&cz*g&vfCNBRoITNhSgDFKOa=wuq=`Xk6T(9s&F$!4n|! zrHUWP|D4MdSo7=PCwL?S!%_^g=npnTVLp2rUU-|P3KB6tJNbtW`jU+Wm-?RRk&X&u8_T#ay$kX;4%~%wnMz39Y z&U->$AI=PN_ny}J$;@?;Gb4Bo(`l1G8LX4u?0OQFy59;&WAKzR(WZEL=XWO3c%Lo| zOD1r@QNCs^H>7Av22 z?S+!2bg9c%s%P3<`otLMzn)f7T5^63-JTe?O`QcZ+$wM6$}1|oxP$oPMxS@aUcC8E z_rRe6Zmpt1qi#i6*}f&)?F(dg{rfbIzI9PEA}Nn7iq$3E@3;pPAlvhePD0AY8*M5^d<>&CE0BY@yM(Xe{Wiml91b zVGhz3&z=JThw+G3ym{wC&*VU9 zMiq|@B9vshuHu(Mc)5R5;$5eo zDGajF*iOw7*T_*7gd2ZqEIZl=64VORiwSn&c_rVHfYpnMj}x zM`;nFS{CjCKBsvI4SkjOmq;)5_aHIR?d;40Jn7o|s@wcmtUheVi63%J)&D{! z%(lk7$Lq^WuFUj0H5W0w-LAhM@8o+#vgTK^WpqbEsRVycZ`Ce7Ltm@~!m>B3doFRc zCQNMnTe0j7e4!h4K;6Wk;^bJ2OXIIk*pC^2QV@0p-Ty-nAjknevH{CpkZYe;S5K86 zwCf466bbagLOwkF{XHi0w;FdF2Mi`l zFuro%o)1NpMZHQU?84&$J+cutSiOM%Ib84yEcWww0boO9e0LJ>Ng51h&cfe7#4Lot z!fz6g9XJpq01|7oCzDiTG|`sL%h{;a@cx6j_;`bL3AzPvU$F4lEN;H@7L-78psz(2 z^v2VTWaekcg`E#p=7U};ImCUmq!@p~2PuI2j3;|S(S-VamsFeXbtU36xZxqMh2qVd z#mQ13tg3}F>!yF7PK|WsN$(0|1%J&RLy|g(sPl>93wf+F_q<@nADOepME*luOEFFf zNDlQsPkb;D-W;LC>pUJ8e0pJiu27}qy7()@59`TGlU1jjB@`CUjdP=6M-E=JAi)a;?rmvfn`gBY1P*q&)vN!J?J zfjny~ahbQa>8Ua;j4j&M0w@bP2p#mXnpEIQeS8F&d{MV;mE}J2qnPHS#w}T@37{B^ z-fu2MOhR*Z%}%3vLqKuyRyR+-Aj@d{n z#P#?#{Ghs4mcb1lgsQ{CBDN59^o#Z3bQ+7)^8EMY{eFw9_0Z$K4aPG1_Z@j4-xMkQ z!Dorn3s>S3A#(M1HR<|z zyF{9vf!rtdsUV~4zj2N5xVEk%qUk;F+CAgbYU&lbHTvtvuNnyb4o4e0K%;Tf!AW3Y zD;MXolA;yvX|G@O?NX)!@6Q*u=(r?K*AgV=AS@ybuF_LCO#8mBmM|Hdgz(nldh~WI zWJzZH3$z|`b2zd-~79DIScFTOd1cAHTy0+?LnR z9asj&iHrlGq*JF*!rW<_8jtS-34j`T(6d?8)@0x1k9sd}9A4N%QPY$j?&O3?x|Zdq zGJIgUMNT~=ANfQTr)v^(KhXGnj4@t|8G%q__~$mDeFSvN9=qZ)H@0evV%P-%iuYVRX^=aYxe}Kp3HntLh!Y5Fa8X*#5A+q18OzLWqVKQX`a!}<+$n0ol&e}v% zP4bP@KM~*Bz~|y^9Fs1*T}L)cczY|PyFAQ<+H6Fx`gFMmBZ@6bf zUyB=h**wdG9?WdK>uksDEqY;*=PzDlk$rZ+^8w2)v*pXo=bqowfYR=}^EKq!*6)A} zI%J!>9{@csGC34&=mj|qh$6Z_zuXnoSTkPVJfB!g*W&N*KN-9*6?_DIft%AlnDj^v z#2c2k0@7d2HOHP01LNM!pJoP1|2^3TiAAO=^5knwkN-Vu-bB4nVwDP3C#m|XM%n%= zM29t~m;Gz9ia=dxcACfmi^o5`*zir@2Cb=Ys)^k@IflF~20C?LdYg+U&ee3LAFhrY z6M;~&^)UeSx;vjtSqitbrX;x(Pe;XsL$tM^OgfEtT5dJMPXLwySRh$4z&$rqx#E85NnUmI|(>W z4yGBA49;LBh|_YsCouZUzF$-Ck@nhYOk2Ha`-@$xy_0a)w`1aB^3-p z@_-0&krfe)og_kJTMp!Py#w%@2&a~tDE=hN2pXUWIqYm{3<;% z)$ZE{{u!h0GI9sh9?Sw*3duA`nPz~FPn-1?Mv~TT+7ae4T~OEv=XPx`q4wGfgMjjwtOAM?qlyh zrkHq$X8M8=LW*t4y^nTN^vWlvGB#G|{iemYK^~Fv%C&0iam}sG(R#p_N7@}?0(TxB zC6`0whaq8%A_D-Qm7zs1K%#hnBQ5s(dh!Dw(s!=RqdDCM(x*#-SA^v|U#Y!IpF^|ZN->g?Y**ri+I_ow= zC}RV|A780WZmr<3Saos5{}dPyI_xc7x*Y^M;45wfm-V@o%1grp0FG#~ zjcb7ow%!YHSfqG-4Qevd6YN&v)Neg>m(Ot<0tFmYsT)S%OZ3ZvEwcl03F595 zxdX&SP9B#F2basNC8jNk*!)^^?AmV{XUdEjRVgnnS3=nIWz=Ek`1{XFCD-Cu8bs;EWrng z-}cxdcB`-kwy_PN-4F-@V|VLRP|lv?{8&57l2zY4yB2t+*Usy8)nZ3?L?64UZDXQ! zag-uBU4Q$+J=>jb^XaEc(H+KByw=?398o9$_7V>w9kj2XH_gXDA@VmeWO+I6+WLqu zPse~K<;ov!WR==-QxEi<9U0)h%0u|YYj<5<9z=++AKuQab2Ag(U|A&XHb(ZO6t`rm z`4q`q4X13e;<`xIx@}lWQ`W|s%4YjeHz*DiJ#3$*o@AyUy~Mo-UAv%1=Rzn^tKvp5 zcpnjrv2C@>6f74jbTEc19 zu=aX@<(cOoKJXf_p}K!od8IIL|S-tTD%mm zV7{u8)4ca%v_#6zmeJYAIcWK-r=5VmfZF&DRrTqKfoAQ$J}7;b-kmTrkSTE>eYDKy zzB-u3jy>wl?to|(@_Hs-h%bHg0>_Pt^F!dUNFuYei1pkBsaGiK0IStIG2J2eOGyG3 z({!kVE7g}RJ$H*?8M6llV(+(&bQT%kHVWYfFfI>J1>Ro%*?jfuy&P}~vj78pi1|Pe zm|cgE9q14QfISXGS(1CszpaZMw5bE1e!T+xKn9&(rT^wk3#bJ)+Sc!978@=7RUM;+ z>8?LOl{Nt3;RrEn3<{Fz#Q^PElwp|#vXBKXo8v4%hdmSH;90fK_{bK%>!NlbSX7wKT~00)4-J z(lrq<#Virb5Mh;e1z4OI1v{r8&!jGX55h1){?}$5aNWok2ZOKQv0GNl9X+<7v|RM~ zh%>BcB(uh0H3zseUXTrW5EB&xMo{mzA1OLKqLwQ3HY&;!Zm>kS+>3R58Iw8? zPFjkD@^{rS^lm3qYd!=j6goNqDxoysI4)b-hdRQ!RlixdYz1$)Y`n89&X1}XbCTfzz)CrNB~!|K3+W>dIey2gSRI5|gH_>v zin}Fb|F<*qbhqQN2J*=%-u0F$nbU70$ZNaF=%$=t+H+c-tippw=Vz23-MN|)&%zF33^(e zC`|-z&$ubs7OZ;snlCMIuoVm~D=@TjKqm(`g&tfA^!uxdyP z1Yf%Ul3h(S4f`&b=La!7qhVXCFZz$GD%C3rxVFs?AXOnr`|gJ*ESK28r`hn!{ysBj zYoykk(fNrqQ0jCb01V^=-jXlx>$@9M?GSDBXqO!DA-PI;DWMb&y7!v1qy$HS7;Xsgb&<=7Fkl#Zu>skB<{gUsZ8yf$5vgFnB9f)RAO zF%HC^<+nX=+5^g!u2lZgn(xrE@+x_8=#88o^;vs^m>p`QqQwv$Ms!8GiC1oz<+ zFg4xp&jo%&s>bZkgVP4H-yYJT5r5JfH7~SSFwBiX8iaw`@cy}xkXb`=KpX5mUqOa^ z)C?qmJkx8INdzsZlVbsHc%jmA+**B^b*m}%1?j|sUxjd^EB}dg)M| z?Xg8JfIEq4zZiyv|0$ZhXa-*Q3miW-;P3fl+sEE*(|xcVPCW=TMxQ9fo+Qj*0fu2+ zeDvo(EHWPvQt!F7Be*dTs+;FzOyz61kVo@CxTuHA;6CtPbW)Lo|Eh)hpW<}wc}Si= z5Wg~b1hOF_n#|o$|EO1GAl zl5u0(N@0h-gla1HxBQN>3O5NT22^!0!cuSFYfZ22%<#9$CFTt_t@!h)w@ zImK;|r9xWrk)_P39luKVE&&VudP(uo4B#uzY!<@lBhAytRHP?jcJ5Vq?*^&s0>Jhm zqOboB6`PQQs7z_yAPpGVia(w#B*eARVLn(<&}9$aVA)SD7kf$qMU!ByK7be{C~Q*m z$hsKS>VwL-ZRcLB>tIOh0FvfbrNs(L>ER&dj*3j45CBKePKds~v@X_k=u<9ZhYT`5 zYe&eV!IXd+U_G*GQruXmW92mf;sk|0b=-f~rMbMcEtdj*kh1f7BXUQ0B>zPkf#~_0 z8NT)UaIfWyYe83)RXb^2r3IP(mCIbYz?)=0H&zYw*cD*CJy79U#CG_m>$fL6xmvCu ze-T4_1%LGv{B7KTnpR!LEvX3+)u+~J;PQ(F=Is}M&x=#^4B&8Kik)Y%;k)8QGfb?8 zRHCkci|Xo|5k>Hu66ooKWXHGPXjDgC5czC4!9%BwV-q2gbprHJWgx|#lcVZKghn{| zzl)1Xo&Fu!2F}ldqg?<4>mDyH3wNMJUeiu^^L@w;R{}welO8}H&EH)+Go>D&%b7!6qbTP5b!SSyQo}%eqPM8*ifIDks+=Utx>BpQ!X;)K!-D-3*k7{ zEZF?%Mugkjf*t{YC3p9*o2EO~Oq{zQO`m04ZR+N?H*#b|k66(*22*UAVhlN0QC*#6 zvz&8fD+QYVKv2B*amDVSwsZze@GT7U4S^b)DyNJj zpp?;&q-K0cW(3LNp$%{5p>eqfzsd6>-rXnoOL>b+==-T;>=PZH#56PPq?ME}k3pkxAUryZqVrje#q+=ZgkI(R&z0iyB@dCYfJsCyF z!W&==`QlV4zY8^Q&d`60@-L+CYz1BNFJ<^~m2}t5;r%o}jSRtN;OGB4Efs8`j}<>E z#32P>uPkTOXUtoGtOkAG5d^!(DkG(P?)dt;r>E$&muth47NGzdtakMhYG-H0`>eg5 z?IqHn^oep*m~@9VS3K?6b)LWa^nC`FVxl6lHJtKLdU%2*jQ4zCaZHiS zWS;r2^`Q6rUDy9y*LQur$2rg0&wln^d#!uj>t4dKH4xM?%p0-8JIcz+8)VmtDE^vR z=XC#%olNTFAn&CM4#T$Qz14h8UA`Ack!k@(q@z!t1Q?A94#w#;aHg9@y{zz{5G(w< zpd=zD?AJzGtjQILsg>1gfv4yhMoZD|ynfr^d^q>&e+|!rG@}ckL6HYk?<(CdK7`az zPrE>5iQ{A9=$7UUbnGEo6~`-rx$N4KSkNJ=pqudTt<-$+S74 z=u*bJ5?kSQ`&cV@NuHvj6}&M1sewjz*gd%i{bldLX9*9!?qGB7|N(VJ|_(9quo>{K^EB(&Qs` z8r+&PJ|pxhAuLIkqJEDfA3fpN_%5}tDr%&Gue9V-AmL0urOm~wLgzjJxMHgzjPN$K z1F6&zxJ(gTPU+Jgu&_Iz0O%WE1jjn3oj^Lnpb{Ba-I-toj}*EwGXrt?^2)Te+&iYQ zMQeVx>(=M}GRcB61Vdv7w{?JxQFMiO_-5kQf^lP}Pew%QIWhnL`W z6;d|&_94i@ZaST!uLz1Yb)`9!MA10>ReBdiyW9|zak^cz?~^fs!W-V*-(n6!n2or9 zPg{;7bo&r?22N0-nfUhGaESO0#0daN*S)^7b{6<&wvfbw6XyObG&~?;KA=4R_G>Psy(X8wVKpK=@o&mNz&lzSf`wBZsFis-(X964>R&h`&@W?mA&4Mei8S70U=H>z{ z^7`l>4ZTlbq_C{G6DfpP%Y~(OjUVVro6>Qs@)be-;?3#>P^}vg4H~Evt+s+#|_LV>Xyxv+Wc;@%TAsRMb|z4C$j3?KH2igdOm@ zVz7Qq8+ZXHtp2p4e5-m#{xc3`mEsS#5)K$<&-_M=!>*H|%^7eogY}EyH#iOT`e~tf z(ytS$-B^1UJ&s%}=W~FN#oKJ@KBlehK#0@LN7aF^I}?t!0)*cSw_M(PePwP+`zCx# zvbB6@lQi3aK^}cGo6+gis)qvGiv4^2IgA-{mKKIPQNDD)=#zZp8-Optp{#x#VHr*! z)nbTGaKyliyujnzGCHF{Q0l;i(dI;$%l{+ z@;$Af9`t@Wcw5S6Vfcu#ct)LsAv%@Fw&l*HhFMGtwUlNbfg?IbmMzEBVKspTYd*Fa zxc3cM;i&;Z8Ts&Z`b=O7U11!+dqa?VM`_kzSYR05;&!S{slMh7qWnAY=yTln|RfgLJw08YBd20$*>W zC&aA~_|(KU#|;>lIa>1O_?`3M5Ap8NZ?)4Oo1$E|(HYLhe6$827@+f(`N^j<5Yw5y z6b5s7sBvm4XUV>N#N#S|6w92q0xShA>V?vpwk|)Ps}Y@$a&fDV(4m2h@m zC;G|P&A@&hhVvW@|5;qR&dxm$Iw2njmFf$SrGs{BH6T6#kvWsWxj+Bgyh&`8+L2?Z9#}6q!TvxOW61Y z0J*y)cdsZY@O8`T9-oAi<~?WzL&?`2dLs&<8b1K4HKS?ZPJ%|g`a2dwW{3AQIQ9np zu=TmB*$63~>8FsSS~Y}^w~*qFV^J?uARShL%v9>{cY3HDt$TW$`~z+d3I&c|a${ly z!`^xySaKFs&~vS)E~ddd9ykIRU4#IDshAD-iX90E3Y01{03^qtbq+{bZ${=WWb=5v zxm2^I2FcV8ybV7p{RaDofSiK0H$-hXT*hO*FH#!AMx07auUzVGwjdi|ud$s56_}0d zp1yvWksdQQO%7e7SQ3Pk(!<@bfec1~vX!-w$Q>mzPOMiTInJdnf@KZ1oO)T6U@ujh z6z}TQ&s$(y+EDOBa>3g=O7=odOJ9daR{F(we}SPt*=(@9Z6H-f;3zPA+pmyP&octU zZUl-h@*y`z^yrcdILmjyV&F|il)@B{&x#4`X;cgQM=o@+6EVf=+Xj@`LTHJ0n+(g>8qglzq zu`U2m%5GncC7ahek)5G>i4)0bZ=i3ClHEuFrado-CU2?IHnyBg6VKU04vDhCY;n%Q zpb=_Yk3dBl7eK&r<*El`Wzk#%23gA2jrnJUo~Z`MGTIh60g?OSXPQ0cKb#L0cCwX1 zFvhDMOPiobO_)vFt;`Ta5T+NWa@u}n>cyoUj?0>C3I>Hnc;v35S*baP+s5JFmBFKe zkK0&QgBCGTs%s%NO#}hZGdcri=iq_+PmFlk6UU4+9&`*szl8A&=<$P{gqZNq zlk_`t0wYI2b~*BlT&|2_aT`EM9;W3~JC!!$krF&{MDopMIHc~B^PyQg>D>GdyJQhz zU9mNs+SZ@>*P`cLnL4ZQuyaZe2jvxZiCPWbgPr{yCNmOT`68@OD3~7U)Bpn4$mhU? zV^3%q_e9A?R~e^?{Pg0-I&uO_LvmAm{{zh6c@HsAl zmyNajquv_Wy$^8JBj|QO<1y@yRfKt91ikc2dwCJ89b%VQ!2biRy#~yz z(U(By?*fgU+4M zt_vm$a8c;z}E)NH|d0Q%V8#n`k#Rh$YlYfp5PB@ z@J~Y32RQ}MQ);Is!3}CkKI^-5iI6OieFw#@Tei?G8aSBHtX%8~Tx$6H#&A0%;P|@X$iU>z;?o#R22L->#JqOoGlP|Ut$1ccPd;8Y4!s*Vvf+U9(znM^B;O2d&kFFwa9jF%Q^WSj-NWxTy}gxbXD~k08YQ+& z0U;THI$Y&%BxtYOxT~_7h^3?t_4SWAN=hjpBZN(SIQ?tG56@L*rgk zI^2=R?D@4qDr=@$;+HwaPJM?~EIidW7Mf)$k9%+(b>$VxxtU>Bb4T(JBz2CF)g+xMMYI@{-YqztkzbL8rSX|i6Gdl!4oa9 zoWn({^r!#E_)2^;>>6a{h#Zo*FBACxxmU63e0Bnlqvt4=vhPFO9ABfWs)$r#_qRB@ z8{UCo_Fwl1{RIBILi5F7|54RrcZX554{sF0`5?n^}=1by`zel-vMe}_RV zCwh+S)a`3|>DCbAjFvZ$*eRlUD@pez!g|=72GdWFKr964;$TMIQyKKzHpmfhMCD0$ zrMy6v<(m<|+WU7~?I%e-Lfi;F9H@B}LizzvCJa5?R;t*eufqc(_<4o%s^Hip@2%hovA@XX)mEpAnsW%iZ+Z#zAd?YSBfEp~6U0{) zuGl}^k=uK=O$IKd5ctlFt?yKsqu?v?KTXR9K2ik=kFXImDqvxW1A?2wo2L!fn#q1n zeeucwSU%bJ*{T8i=y%7zyI*}I?TaU*6(AC%1p!@wHpe9~U^k@0IH-*U*}q=7L;7$Jn>6)hA52)z727+3=a~nW z0c(=32gfCIT_7i#G-~=>6bf{6?x`Io+kB|KX4D8ZX&sQ}>DzqVa1(Qzd4qBSI8Q3J z1g+gE`^Jir=SHhW&rP`(H|4_b!1Za?p344??=r(ne;SYejZIiZh zNtT06^yp;A3lV3dh-&2BZH`Uhus76(JtTJjm1z&%Pg2qvf}%Loq7ry)cW`m*yuqf~ ztKiuZO^1n41HB1YFmCbogL(#TgPU-vAVmA?9nib_y}F4(^+-IXnfyZ(1U}#zY@2wj z&b(=Pch!bI(WMhvx}D=-j}&p}2E{v+Oh*}r9valooIrV$t9r2Ug50$`JIjbh*NQ>-1dQ~cB0_&86BQgzmDD;yejRJch$XSk4rrO8j#KPqYPCE z6P5sI5sna4*j;(zI9Gy#jI=3=k8)9h3@W9k$a{$|dmWYi_)HbAw9zgtaZ@h660A9V zMXJIaW49=i{@4@??M8#8Iq=(wX@HO2-d$NO3o9Am5acJb8+SX0%HL(!)t?^2P z8@?`GvgEH8%f3w%?ffP!<_#A?C(^m$VN$H>`9tDcLoT^KM^x|xB*A zj%}b=P=LLwy4D{=#+`eS4~JrXg$FUBP#JL-`Q^LJ^qgrsx~dC&1AG!naQTNvvk^vM zKGNF+a9msOEq4|K6WAn)a~ekBX{A|n7|fMZ*2{Hj#3h5c){`0@0HU0@5TMh*hD`7? zy`dh_$FFO37P$=@XPB2m!*w|g;=wr?vWGY4bIn2iK54(N_*79ACUfBR>Iuo1@fKu` zpOVGhfm`$pI@Iw&VX{|vpEhs^54jnUlVbxxTM=Gj5wAkY1%b(jz+d78HTlBxMwUeplSNCKtb&+Zy-gBuS}nOaXROyEp^ss_n==`~wuo z;%xwR%IB<*!~C>EK&T!xe?DrR85S0{`nyLAT;#C>2ub%mPgmO{)&K5mHGq~6xw-A- z`xFS12P`_J(P;>HYgQ-T!-CGS#2uD`8kbixMQY?qfsz>bOtirBN&Phf!3q3QuYx>9 zJK*=@V=TnDdP5CHO0IwxA|mx|Rh4BHcoU2mdKY&Bf32@uJRPh5%v1d{9qPz%)THd` zB))5==>DmI-9Q3H{L!)`yxCml*ksxA1`;uVtO_MOAg(luL9jmYUr&b#0?+7mV`oX~ zTgk(~rk4$SMqDL5;?+r#pH$;k@InXtt5uqh4BD7txXLg^W?<61R!5g@Llt&Q)1A z)_>q}YCwnU(mA9UI{1Ztwi9CJZ8jFYo1V%xq`EYrIyH8IxIrWRUJ1p{@55zoMS-@5 zCen07!2ssA{*`j~S?koF3ub9&i&C@Di~+ zW@TaOR!->VB<=TE?bk8Rh&B*mDHtYLnJ;biZO|8<5gF46F)Z*@U}^x;a7Gcg708a) z0GdKRZ%)~=)lj~clbUq7n>TbLqIk9ui94rOJSIVO@X45>z-IKs^q~M;SE*q{z+nn9fA|9EQgk&FYi>m%!8m)pz_S0m48B>c@^n4*E5%2^yC{dFM#@RsTK6 z+35fvvcJmIu<_F&EO{*;w@xOb@(QZ)8k}pJtRU;wMqW3`+r&HG!$&Na*&El^feffCqyDXYS9pvbb=o>bvgd+2r{Z`~XB?g;* z$3YbZLIHqTzeLChYHB9mKt2O9l)~b;5-~MpftXaPo2G_W;fLw(ot#u zbn46UeiGq;M1?43LlFBzDmJZD=AdY9Y|6m{C>4h6zo*!KoqW&25 zj{zMY`xEa)>CPHOE@DvzT^rzJF`5q&eDNb<|L;u4bnLJcxnBo6q08yAv|`dh}P1In@nlN=@cul4VVJ=b>Q0pLft zMlhF^Z54$#O3Ko;%zicNm*(TYi}{_k+S7`QP)GQHL;h!+uNKdcvr$XR2g|3#V8(V^`Dd*3qF$-WzbipFDYcx)E&w=J1jQ`!C;!=7mDZTT z4qa>{s2mlU1t9A}w6z5P)PB4VuT8RP8?s9$8OuC!>wtpA9h#rLsGWHA^`Jq`P+x%# z@ewBljfO2JAYFh$zL@i`bxPPGa&tTj1Xs(wh%T-*UOpVgp9 zx3@85%td^5itva@A`6>I;g3)yoX8+x)ie^&FqL>%@=fKA4yid1rr3^>eVv$-K_MtN z$N5e)NJ*-P@mEAHT6DWaRp^w=97Us9_2OAb@Co@DD#z!&Z7TQy63IODeG}zJOH2wP zl8q?>ki`cS4SA}_C0uQx3H?=f2v`oi@b>oJby{0`rORDt6ZrXik!L^T%@|X)<)KMy)BC!DFk(SJywJ8V;eNi*VvsZeqJceWMwfdBqh(4NW0`?|FVyt9tF%)8O{c3^l5E9^k?Udwxeqd zFQ=2MP@Jy7|p6bg|0QU>Y^zD?uCaD@O^Tlpv$|cDk63z+vV3BYM0#@U)%M zrEgOj4=*b_l4^mOM-d#bvXW*?YxGhIExS2}KTl9||DM%10GE3Bb!;fb50%Y-ubtJ* z8sQhbK$wgmx8_CRii;BOhk07AwOCpO#=>k42!5iMC3JA`J0)94t)&oN#y2hRirNp4 z^;CLmCfay(WCP;>5guS<`?ho`cvV&4pyD90I!HkZ;EA?s>Cx$w6!4v*8~8kdM(Z+< zjQC$rwvrpSE4=#Zht4Nd)Mwk&C!WzBs1#CUhVaE!b_Z$b(K+G+PVcIu|6X_0{$r=Z zw9qD#iMKT!c}5M3@LVQ>AI`_Gx;V#HFMA{5%>|?3l%N0gV(KAd?NX~PCK z**^g*n}->{2Cv$%D?DW0yDP)MNN+`K>u3lZDV0-5v%tdQ7{Nq%#gg|(@zCUnTf-O6to@ubD8MdDG}XMMGDG~A9%1lLv$F+_fnegOGI}Qfoz}R`-kbVPyFx( zq!oC;v7Oc1N<8~zN1!sNT1hZjDaf+IT!C4!&o3_EbM44vw+{_P%2JBGbZS`GArzIr zprN7R2WeR4a>86!;sg;Yot0jRMmwLc9))m3_2)u@9wh}htdU5#6Hseyy&Bh^U70PX zLIr?+i<3^i1{5irI^eOYLxvYskZIkFn5(7SLkF#4?Ldfm2;%hG$sdq;E@Y3-tezYL zQDuv?t8Mxes&EY22Wx+8mX=yA5Bg=rqsEUTM4ae8J{+OYoZ%Lg`@-?;Yr z1@^M}ReDT`O!T^ley;AaV51s{m$6b{@rq*{HdNP>}Bfs&v)q#I3u zyjujx{B0Z@9E@u+WB0csl^sb4*!$v&!}?^%M`C$h2NpX+-M}doo8B;5(`33eDRFJh z&3gesR5=S3^;MPaORYF!k%rL%^*&QVi%q%sUX7s2suOdhOP;RwA@raqc&in#8-pF- zJeh0HNV&5hhL6EMYK1v~phY3_RUzHk$MD4Qpo-o(0%{H!oulqmxZ>v3C(IN!RTMx zFMLX~<)KcAo57sGJ6~VhvqVHIok2stc3J&ixj2lLG*z{a7_x{I#Nr3hmqqp(5aAAV zBz@G^Q?o#&G-$Fi{nT;#DXf8kiEcw!2`He1ZzEz8v7_yfgm*rWFV%q@rrCf53Ad$b zH$uw+3=jW@s%$DNyk$@lKKYIN`6?G+Vz!_7ZQaY+uN+eB3GbrvvFD8HDzbJP(A;0B zY6wi0P#LvJ=Yubufw8v_p*^9%JEOmfN1%2)AC^+9#Ru~MtQf+wKf_p4B&0z3cOLEg zHo=8oM}&JDKjKe`ND-dxc({JaTH`dql`{x2V^j^pat(t!WI3#H#(WEgCJw%uko6!s zg@6tS`DGH%mNtl5aGhJ~`C~!-BG7e(+*x}6q$@PoplBj&)-0jr$z~XZ$!7Q@BnO7( ziUb3RbH|+aikouyN0jUllry81e`&C(43`|rA36kT!BX?Tr|aJjse;}~eq^kH63)eZ z)rUE;qce8jK>^uvxrdML)$E6OAmMb0=)jRibYsQ)gkw>OIsi81G;r@4q82P62pa*h z>f|dj7cuNZ9lT_6>{ttsrjSx*7@N@MFjw$+r^*jjvF7NE<>xYSL^U#W8SOaAVNUsR z1+0}uuoem=1o)c`4VGZDn}$S1MZuMkNQu(l?mt@uwK%&&m>0BtrUZdDLSIIB6Sdjr zsWJvli4%6`Csxa!s{-+O^iU!*ttD!K_do}bj$^)_HaaWn&N2eZ*Xd-v`8w5wn^+Hd zAh@RA4%l5bJp1rIr9TrBTs_nS6Wn)cb~!kLKLqJnu+^ph{{7nu8nH;UT7t!y96Rlw z)x}}dYn;KI3leA5+J=Th^?O`hU9k+`OnWOtzmOFGp6rG!-ebhoWoZ60J>txyp^$U< zHp%H70PmeB6j9K?n{dchiEk1J=#hnDjL4=i$Vmx|zjdq-@q5GgQ_$|oy(q(?B4T zsUZA-+NbAB(qr`xA0R?Lv;Fq}>uR>|Nddul&S5gc*MzQnVl}N~XnPGFR=|4vg-E&? zPm1;@AKYreO^t)izw>`qW2|f^qGDb4puc=x`05RXH19T;Kez*s?Q$=gdg85t*H9al z6-y%vMWAzi^q}VAYWrPjZ<4WVKie+AE}=rx!H;EOqv(^3uzr=3sOT8^PftkVw?*v5 z+LrI#jKko+1qD!wD}$hona>n@;mk)^4FHq^%okRvVf<$}Ufhdn{&gn&h1nZoyGi9; z=#x3cY03|=<`D%U4Zm>e_;1djPo_C#=*fk9jhS&*fd`=RR+Cbe;uJKWgJ=YGI zkuR=k#UDGe)S z?j{|}F_>`kL%#n5ghKBTMxp^2CefX>^@`}$UO|{bIxI3pqh5&5xyI@6h;A+z9)4ka|?v_5G$V)3H$-`Ai$51HE*U{ zWWb!Q41%D9)&+s;4!5@SpGr(j%x?e&)0w`=kfyIWwpZL)z*|E8GJ;)$NszmpOl~8` z3t;^QR0G)Z5F1eXGmnAM)rslC)$NgW@6|drVh)4$W_b0Xp7^kT+m_!L%t1LCEc6(joW<-0sy+Fu$Uv$K z5ZX(eKK&~ql)9y*0v1KxhPDToR2J?>j}d-P*IgN&zkHUi)3Uat*&>h|AnGNyT|KiO z#HXQtgZ5mr!Vs%>J3bWVVqarM0|!%mfOg3PF^DoQ%9t1PxJ{ zVwaGe72L>=baOp&1yscHpVf-;ZoBKo^-&>k4p3~1y?`ILI0&Mf(jT9bZ7}$qNxoVT z3UAZ12rxlkxuvK6^APuj0Gdxh5H7O~u za=|OV3?5^$Vud{CGcOepiCxAfp8uo4RUV%u{%36 z@BO^Oh#(@Bd<)>SxzE|(G-8k2N<4V$;x2;mlWQ9*@7r}(Z zQBCxt>#qd7@nf9J*tO-CNYo15M5Q-RMQ^=bCc zSTfxoxzTMSK9#_XeAEdvXEW>&vp5sD#0O#-DrG)I0;u+__xTEo24+DM*_EHrPoFm` z-VnR|s1vu64j(vxx?q^9L-k+e>KCD#3Mu6l-5GI*>*&;euR>qobv z4vGs_>tI_OtSw$)C3Qlvk}Djm&dz`FVpthiOM&GIs5gZrKbf73!_H6EE%6d}63wL= zX=k}m_xYvs`h!!w2<1B|c)(U$1TdHwWYET9$#hRxM{hJV1`)qf&qe%!?57sWwa>pgG??$E61 z`VX4ai~+C+U*k!3R21!v5!dKZRxO?5|DFY4x#7hf9|pgCRiplL56syVxEu1u?+*}v z3Uc_7MVNGvveKQ^Mjwp6g^@F1Kh>rrQm9eo5}y$P`$7DpHq%>uc3t}uKetLa^M?Ry zcp`m$6;;U_Iz)U(R|TLOR~^e?m@#t>-%-H}*H^>D6?&-CJ9+Wtc>L9+ORFRlmjM;x zxC#25v>kH--w7}zoy+$m#W57lfR`r$R>K{X>9K~=kpSEI7gnE{Do+>pzkmi4p8@xP zivSFy$3`EIGxQTsgifddiIZm4?x4}0G{hbVsL&2EeQ;VDp9Q2*#f2Rx%t6ItoNP*5 zA}IziwL(8VZ5UXKkN9rVRd;6=@f(55Irm!Ncs8MnO0e059UYD-Bp$^|S2$-Pn=p2T z5TPyrutjk97-!UHH!$!JcJRixo11@0x&N~Y+9NdLQ_#4Q zha(r1xpj&7hm^&tD&|;~cZqO#Xc}R@mgeeib_ zT_0g!rywGJj$RVSe1=xPp&q62++j8RtJ8zHu!pdaXqqzMKW4pR|2*tgv`EhHHd5W? zo6I{kdI3L0$`t_?$z^;rz|6NmIY0yGIeT>Xv;p(RpHw z!_sarAS{cQKqE=V+qvWtI8L1v0$1q`ct@ENu|}?-##s36^+63_OM#^BagHqfQm&JX zI4PANExbB^ZA#_?xoK~I^3Zep%L6qMD~((z-$Kfg=!^j!cfltrhOBD>oqdm}2~;}~ z-EY5j-LKn4kJk%o=yEA$5Z0zc+{)?nB;$$5B0c>d^{f5MFZ@d~R>p&RzT0t8D}uc& zd7UG`Ygn0yB`9YWr#oX#6MIvntysR2)clIz6PUHVpu9X`<*M$!*l`hm2Y4VzMZpX_ z?1(gY_Wi@Kis62@08PyW{1#d38~8b=?5Z1LInS~Q0@qQY2_Nc z5}N+upP({VgIJ!?FvVyM6VT$ZR_ALD@k3IjJK42Kc zS~*VJ%`Ld<9>6(g$zKl)s4y;jR_G1Od-Dz(F@iFp5@>13`DI{A(* zGf3Kf)xn6zP!>s_iv31&lWpPQ;nVp?gs#UX;1x)-QrQnl#v$v}V1n0lFHM{q>91f? zt-APlwbei@EMQ8kJ9QMQ+S(D|97U0Avie*@s}VJ?QCu`pozhjx|XEX;L8hP3^Sd;>w}Y&TVnL?!hBk{-f?&<(*qV>xVv^xS1YD4p!bO-rvNX3$Bvm zde$Qf3DLUu*=&$^U;TllL0#7T3MOmLI=)S}nFC?|1!aK6|Gc0T{|&EQZwAz&DWQl$ zskpP$hikZ7oOpY-Vb&m{!@fcA)okWE!U)l6p6YFr-@ZEE@ep)VqQs*TXM=@+NAU%K z91v21csu6IZoGy_TVve~=WDI=x6Xbxx!h;UU@9a8w%8^dvXHBpx6E>!MOd?EI$xaP zw->JkAQM(^OtmaA3j6+{$9kQ`-6^tWhN5yrU~?*srd59XbNl1VInCqyU|z9to6p%r zD8N{yy7egLs3r?>PETFdnDoCUmwD+C@!X%XrNv3F5-I=i3%uz=jhdZkt`s*ILrB3Q zP88~6x!BDB!dD9FhNQPi6^C2FW8vArRL7YoOtE#I%V3yf^24>OVgr>>O8K%Gq{L1D zF9i^y{q5+Mf^^DlO!&ad=CHW?n+2DPCT%tSHkw%{M15^EVLt^qX#Oop@7fbBNLtW> zFv|s%7oqbkJ=mKADjO(_pd1@D5s@gS0RU#~s3&pJUcp3NndT&8gZNm>@zAQQWN_xC z1MdTNwxK`>T6wCGAd}#bV<&nxQ&(obH_RZxUS5K1AM)gMLGAjyPS3oeA^}<^nF3Z= zSwW8ASiYUg>=qn(#5}(bp=U9b99?~w7G%6&aT8+yeiltSHv@=_NRVyvpzbrHc?+HS z@t@r`<}ID!F9z$t^LCnrMTP*!akT;M@}h@YyhWy5IeRh`Xc&jcjG~W|^yAK>^sL1ud5glO+v!5y z*{R$-`g%jgZO&g@O{V|-X)>_CQ@v^NV0spk6vhw1HW)|z9!cKNSm_+}Ty(bLSUZpX zdV3=RnF42PBRV#yPM^o>xSIjnaUO&8BsR_y+MR@=<3ccG?}gZiaiUXdZWZY%R#RY-zO z-b=&Sh5iDr!t~gTj{0ki+aB$?ugOflakLP=c+%m|)0+t~Vbf3a0xj~Vr>k$*bmmrx zrgNk3H14Gj6eWH{1hJV+N6;f$T>+?M4+d}ybwPpg>PiR5gh?q!3N+YgnG0IZIpz$& zX4hKke5OLTlxSA5ZNQ*UlI{l)n^P8!N36ptV zhn+?l7KTbTbI_U6{CVDgXT(tqZt>(EecD zo53-MO)jh%+BL=Tk2z0gbhav09kz!-3u>}i>0K8CAI&MN$lIS|BxPyV_?T)+RtNWU zabiAG=S~$B`4(;Bn0aH6q0qtWq8hEeAi$)!P1UO6PE}>W)JTrf^!fQ;KegBu=DHX& zI^)1>$zRLfrMl#slK-?#C?VJ!m)Q-7>Z@Kp7g2Eg)a39V%ZVojWeMY9 zu?dF#s`afACm1dd@E&MAYoUGj@ioBOXY&~5rQXm_DyBj=XKLrG&pIyEm_PIQ&nc6_vdT9A6@ zkvar`y97g7ulmh~zp)14iOJ?J!8h~VkJY!z&vz7Sm+$O6SR~n(l9dP(1n96-XX(DZb|kYcOiRSzp0nv^i&TNX$q#t3K>T_ymJz_@^atptQ^TxANY8VK8qF@3g=9-H(!fy zsn+Yy8veE(-6N6sQn}3=S+@_C0=F+lTCzjlrM{4B$64kvdBcGu^I?@#o;V>>g^1zo z2BQ}GHvg31qJAz|TcWpSCX4FFt;z(I%^PG!%I3TaP8cz5Tl$lIu%n%Gk1HDF6g0>; z1hlP#x$lSbl1iwc0V)e)03BQtMO7p`4ynSKAyt8k^gyqZc%=D)X?RQ`Bx zQr05Tq2+egXLhFbo59lO!^s2s&*lPDrk*gQ;Xm1z`lC`ua{`|8eGV^pP5t79&YYX` zokt}(UWz&9@^<~%T_b_l&N6d6uC6f2jr=n5c#3HU^O-&;hZ#jjd5Qhr3rhpAb!9bY z3rB3P*wFpE`Jc_YJy{_Sov0FA*q^Hn8(dU2H*ZOrKNd3-mu_*w`JqePKhK|2g&n=I zz4zZ8`!e4VQ2GsHkhR^-e*(-2A8nBez5Oh@6|;Ynz{=LQh^$!2%@R zth=Xi8Ik26q0|4?b`YOka$ldZK|)= z+Lt2qs1SbgPpse9`>_?@YMR?7dp{@5U9~c7dZ5nHVj*J0A@0FK_2bx+$NWsw!|5IY zGBRd*^2)_Z!Sx4g=q-oky898OjckFF`XP6{D~=}M#C zr{f*Gib?mb1w6kxD%rTRez2_JhvTvOocO+o#+b?4zQ(kiqn7D7i=NFV&r>!Pyis0u zv0kg+l-VYlia=!cjo-$s+@Ga0=yvprTz{-GZR2vqt#`D4Q^?mGSE;vov06D->gb{x z-&uFQ3OS$K_*gUDaJIzbiDS&Hp{e)cqIonEQ$uWdQd$dBnNorxm)+-^Ghr{A+&W)Z z-+w-lKQA?FteGy9X&w3QDRo_%5Fq7NXZ+0j*Nrr5W}Qyg%j`HX{Q|x0Tua^0Bf&9D zyxQQhN|l;!xG^ys%y`e|eenH=IH}v37Q3H78Z>=4gnRbq;`I*|#NwG=yX?EGupc$; z$)oR8@OKa+e|qj|5%gog{hc4Zfa%2OSA%yp7WcdKnCCMUZ&P)txJ~@-IL*;$BQo;( zDdlmCn2QGLqIEe2FA690t(78vGV)!V)tRF(sNm$+mG9w;Ii)*esGH1@A;v4I8rGPy zQO4Lw>Z*^T0Nr*yJ-I3qin07Ro6RMhWo5;je&Ug{)M3^jM6w(F!=ij5GWJ0oyhRe3 z_>lC^gH)o3lzFq{LOQXQI>BX8_mx>9ZWa8U|aAnRmtF__9U0Bu3-J|1*)dZrJjZx4ozVeW#=c{ zgvaZgEKab&ghb8wj<=~!l_XTZ3x(upxi|@RH6_pmORT`^^q}cfm{u525!02(oAlbU6Oxm4+fmgO4feL=9e^_yiOxc@TmYrV4a|fsoZev z&8aqzM*EK!e6q47H8KkHM(XwXlztx*^3Avxn0T*^)qifH@EAU%&xU(~9Sk(=lpw-6 z{wS|&L92ShY+|*9{J2+L$)#sFz`n}{*$zaNqq#{?q>}F>y|$vo^)CC`nf}SB?_W$E zR7;K>Jw*(SByw=M51oiB&oEbIh$(MRL(9|eoK)Oarp2^biN?P0_8%y8G$%7C>67QP6|iifvC0_*4PRUcZ~hJ{z{4eJs%uBNjr2oAdjpcdQ|Xk zy8eEb4?m3P$R9zJ)i2k^zvuCyk$Zw>W6B)zn|B<+56AlyD3qo zcB!+;&*~rBD-@SsB33DhYdLg&_tD-u%tlZA9nalgdbU?z`^DvLaA{_8yTYb)Se|;i zJbB=N@<{#th5qN+>8YxEpG#q_s@zY_9475m)4EO%!*QC``mB)I_qCgdIy2ixtWKLx zDtyg3JZId+WItc3!lyUgJZ0K+u58*mCBQF7JWqgI-YQ6WZd8KZjk@VW-{zg+tHBI_O0RNzyZF+srUOM zJ~sa<34LjDr>QEJ@|&{arJifuhx?Q1P z;P`l$Aa{_merzB92q6U3--)^>lAk3g<`tsy!gM4o`_k5Dm2raM zvikCK)Zt=gi|)v|L-<8wbvc)d)lrU5O*}~8{uRARI-p!(mv;Mc*VWGwd{@A<3<+eo zgm09n_88;UX>t>==U2TIB$e`FAd=*JlgZjsSvn5PBrUzX_8nb|*doS;&tZ!ecjyW( zuhUypj_93xC5I@EAOM>x04V$0ZyVpbIzI?G=^!HEMqA)B6%^Y!#d6KC$x&ozLUvsmTp(6Bx93 z=~k&Iv##%Qq}_Wa z2znWan3$NnJFVm1*adfX`lv)om-g7=n$M-At888A=XAGi3r<+NrEbCM9$Ll4>7IAf zRLhl$;nYM&iXyj;n4;jBxR?WvDEkulVHqClUhiPkkU!KFYzx;S9eP zjEupT%lpHRa1H59|JZWQLeRp&vW0tgTKUPfy0^t9DwgUZgLbyVyZKM0J?2kxuKesX zc`{?KIRBmLl<2qY)#h{5F8T+#Ko&1!5;MCLmqF;Sthq*t%eT(N2tud``bsSzQoL+Nj@l%^5Uo!t>qT6QdXXf z)8f^GA^d$0g<`ie-SsIrP;hZA>ow$7N$QDkME z20L=P`wqD1ul6QEF~?85SEt?jDshg)E(y(>63J=&rApEMU{HO$@8*%A!+Li~(?cix zxsz=(?{r!pJRLc5EPhc}G~AtO_Pmz4TSM$Y0bP-dU7sc3v4XXGKVm0(@zHf@=^&sJ z3)?`UP?ByPoA^^v@cKz-_)^FrK06F+BsQeHRW31EGbkr$Z1KsEKO}E`#Rj@h{Xb2V zC#Ji7GxrE{9uONF=9e0I{e?R~Bjxr)U+AKZ!?|doTd!3NoKvFPNijpa>cqh+9)&Q3 zDK>cg_pb-h#_3)GiXR@H)apum{l(%C_XdxwlDzNHbPSfv$Lhaz@3fu>csVh(KI`Uh zjru(tl67_% zN|L6%*ynoZTh~8%ag*Vv>rs+jK1LZWzmF*koE3N6-KH$ZKJ}g0H~Y2i+N6J`fMi6Z zr{{Ki;E1uYvwMu&{z>VR+W$2de)_U$hTyvt9?=@drm!U2u`+ z&;MKAvo+%1$XA_(|0F8bMP1A{i4PPb|Bz04NqZe48~Fytkw*W6wE`y;#_I3Z_RV^v zsjD$`dCMN<{w!j9-!Z;Q_jObLlW0rz#3$z3;q(G@x~=c*pHwhwr}Vvr$>TC_9W#@w|)y{g7% zyt=WabE5en$Ca{U(&l>a&QlufX=6X<$e$9^ao}O*yAV;ORQ~+Ow&qgGw~p=bZ##0% zi1X^$Y!j`?oxVE$E7d9Wt2&T1KPdz$4eU3--pC+bVT4_^n@P|oU=^2M%l1!c!O zfpXzb9S^Z4Zm}T6^`%io?Wy5V8T5VnR+)yFFqS=2ys~eC6BA`Y*45F=-8~pcw%A zC*FTjU?@L)V(R5!@F7JyILaQ%WFJO%VW~1@)bzfUw9|X;i)+c;Yb8T^-O&${(3%$TO|) zg9e)|RSOx_r%oM4G10w}C>f{yNxnZH!@5R8q?lXF3l)8n4cG zaA$D|&46$`KcCG8-Ult!@t3F#U_q+7aC5flUz z3F*$EYv@4{P>}8xkQ!PTX?XYHet+-%T>nuxGv}P=+0WW*uf6tj|EaKNUtLzH-0k)S zFhxLBI54w)s%V^cit0{GHq;}GuqZ%S4bA00v7V!7E7L+?%GG0R?b;Sw>KPDm9{8ka z*TvCSK^1nMOAhk~RZ!LNj5r`Aod=CeUXoeb9*mcut|vZG;N~ zYSr0NIQxxC@}#MrX^CpDh_j6x(TaW|DYNn{otiJ-4~p-9i-yh~@$zqsd3o0pPis}I zcJ9J+qkx0reixK#(m%uCEi(|8qNi?&g|B1kYRRCL{dAu>-?gh(HxggKBE*laIIZpd z9d;R;V~5l?5);^apVZvN_AgTBb2t*?r(<%KJ~PPbLTZple-fPiW}Ve;2DD+SOjO5; zZUM9;`~2K~@JFEEagp)~s~7L?=yaN^_@~BpKcppEVA5>PB;F4>Mg9DV%*b&#kxHI1 zVntLI?PeQsVP?he84H5!kP(2(G30*A8~FV|X+{o4HWt-;5fTrT_Xa5`3b5|0w*v@g z(rA?LLxWL`E4B6!FS7qErEb4(9;B?XJW~Vb#v|L_7hlTT8vx@7=Bn;y{VdX8M{fa* zQTrPXbCUdGa;7wy_~=oLetBK5w0l}&z9SNr{GqaALR%BhufyqymofYI=T=&ypzoE$ z`=nj$m+te&jND7AD7kp@po&V2U-6W9JH|li3l4l~=z#)4qn8!KygnW&gg1EJ7;fXX zi!zZsk{}IL0@rLec@fyb`(OS|$chl_3=5mmLv3BY&$X`%cVFl0npfBf?lx`z{?&rl z##%Es*MgclG5w>LpnbRqfIl>6DKGhuMLfU9@x!vym!GP8P`YESaeYvEagF293-56J zXb${YB-#UlK@$bv27AT$nA=e5Dju_Q#wl>r)L*`ehM1{5mkWN@oxpo}J(?YqQBQ3i zzHvutzdSL{yl1OI&J?F^-+6)2ZnNeA(0aY8?uSF^S(r~VQ)lI{qo7ZbJ zv`oRA;#g37sjc@y5ff5HWegxOV_I$zqWtUFb?D0{{_qanZxOqJ?yX%-p= zC@3iKnDwwtPEAQ|iIi%Fw^@Pli5*z5!kj=!!cbWurxc{!%R<;rs@Yl2U9p|*zRh7z zDrq$~Q+oPL_zLIb))nINHQ4EfL`!<8yu`{4z8t{?@s_gepL>Br2|oMg<*O-%G^Wyq z35}WaObfXr+sD&1Z;34^G|E-10aMl`a!Cqv_VPJ#qx%RV8&TUtS>xc*io&bg@4K7g zDM)l7D+}-XMOsyD?Au{0O|aLlI7l!exhi9>Q<`e#j*Vs}N|4#ROy7+e5oih7G-JKQ z@&Kr>q8sZQ9AyCyyT$(rNq5T9?TPfDP-Hop2qf)@9Vz6a2*P|B`Ea(exw#t!y|8M) zCq*{cbpGF*%nUyVhb)-1z6JGKGDzY!67AsU@&DR0MP6>N(8ZR%yVzW%@2&Bee-C4^ z+irg)7)3eG6)jj>e`^YJ+KH&d9kmD6UPrFgnaX#xf1UQ4`->!8%l1JUHmH7 zBOMG_!kD0rv9lTN5oS1y{644TbOE9K&r`ML>WHDm(1`mmpd}CVT#Lw6;9Y2ldD&e% z?q$+@QfYfiFPJiS(43la-VtL@A8A{T>k<-MT-z!auTYL+5__Bx@fJlBnp`J}Z{Qv% z@3SAJ%*(X(KgxUJL`bvgGZ)ME@IYC5kCuusEwplSPX%FGha z*Pq9v<7y0e{1^0>mI1VhOnuGeyH{u$)Ni2FWLP{yxMaag%zE+g?U64S+0VR{`nJP@ z1xeaEb_AjMM{f_!H2);4T)f`?1=5Mx+9+SbC%IlTXN{cx$>_G&A%$Tf*KCKWb7qA8 zpN8RZ#*NyRR%+g+)t%rzC??ygRShk-J|x$LrSsO)6OXZC&%mU2Xv%4INucqiNlWHu zS7F7>HhaHR)2)Ama!*XVsza2ri00#2NJ6?@_J+of%Q)#r^sdISqzxv0-N&`fQSb-Z z_s@yVy`lG+DQan^II!zSMhxe*yYb z)f%BM-gvX!Dy!oE?ji~VLX}E^)X&`)xjPSrxN_aR42%=sh+{Gm#M&@(cDbf(obP-w z@$dRzF)#K>5T*^2JyS!0hzCS#b37^dkJj*#tfWBV%+ERiBHTyGLjO@q;->Id5|v@0 z694N|7SpR`k%?{M6)0A-j4RU^EcBOksRjUWWujuXQu~;KC_uDx?XB@4|zqEe*1R6IaWmT)~#C_)ox{1mn85s z{*$Hpz^6h%mYdvruYTnpDe-@1XB-cys1{_S!NHNf z8JbN`Fl}j}_eo*S_JwmabE_Kiu6)>sy#dC#wk}0oRGJ0FHaf4kC_`14s188>0UxM7 zJU+YQN(vvBR8enc*XuOQom#k8eNlO7w{md4z_dtLKef6)Bt!GDL)Wmr;HuX-C>h?Z z)CxIw05}mZNptOy3VU?c1=0r2Sq?f?zY3SDpP4qNeiQA!CVF3I$USmIBRbWJ-v})` zP`4y4$>Bbn?D0xIFC&8W7o@8+aWsy{tbbU@f`qmsR^r-#ecppbmN|Pe3zcFkrd02A zT@;bU?z{LWth!Fj1*n(rPZYa2KNsscfDB%*fQ^0z!>Hb%aoebcAvBDM@-)M-6^+1t z_mcA8OZn4X-plZ#ULiV!wt%JVzs?)$<)P`#A1xE3ZV=B-wJU4NnL@PD!& z5YzQnx#GYbUqmKO6jR~Iyy!3~gBy)}{dH_?jD>|Iv*au)bWN61UFyzxb4`>UudWs! zwln+mHSk{L-yf$-yM2F_YwtIh35hs&Mj~OieEXxI*xyh%Ig%tL1~OEihxA_~L4MOl zYXj;lj5s(HK06KW{%S4-$?%g#yzNRT<4g_+=gb+)j^ zxGTAg^y4BgwG<{-zI-`948ylIO3Wknz;!8dr3WrUcPOYKNtJeCxqkzK6Tz4K(doUz zCr?q2Z^uNK&52?E&3se!>;lm5%;-dl#NT=8w7GrTi?Rm&3QwOGqqKK?egy8i1j_c9 zjE&xtyaPmg#4X!e&$rv{<)50jPptjEF~>U=U;yAUdgp-F5D(ay9%MRM{JidXN^-I> zxSO!ty!mm>wP7Sua8pGY!~fgM3jra%ER51<2aoP}FRxnv34Y6=na}I+xovG0L*coP zr!AL%O5ounQuHb5#3Tu^a`kyi_=`()unD)#pOO7B@kvyx?6Ct@8KUw;>5>DirNdBu zTG}g8#5yqkC6ps5L5ISC=B8~Y4t^8}?DV&g)wwKxwoh#yWnodvm7%*xk5RVyU@Zo& zquqoxVVRh!N02i-xdA^6B-yq7?Gj&&rpCq&FaSXhE9m8YA}BbdiAl$0!Xkos32k87 zlLU>s3eA!EW?;-!lc840`?yz5$Dr?i45U9QFY+)Xd|1e9Gah4a*7+ zHIf_CIFV?sw9X9l$OVEir+RP8tV}D1P6FSt@^v&a@W%D)rU2Z^VJ1OWv6(8fG8Mdy zWms#I=fYSkq{2scHx0^ddrWJ;;d5mOo?UNFA=RJGpUwQ&TwAm%p5LDm-Sx+Wl}Kc6 zl@H&rW_m}8L>>YTE2FTthXoi=51Fhu!#%2Nyj0u?z+(bCdLE*hJoIZSN=f;l zy9Ii10gYC=7PLV?V-R4Xp-Ba6DkXHWfhW8A11R)blR96c-s*K6%Q*${!pL^jmCDn^raXs|M;(p=Q zV-s3dPK#ckm+`H8{tOtC&6H}Lrsu%tYU13Nu~Vb&ks1#UMg3QH-(V!Ip?CoA4+aM~ zC@U#-o!<%#q}uDTtAz2Gkz59TU}tX%Qm&Y!~p!G4iaKYRd+35Mi2-rz}G_A+tbIa$S9BgQHxfcSMa&?d3 zb#HO>yg}X})^9$=#^(I}`?nGA+PSd)V+GPqGnhhz-t7@ehM8JZI49|HapB1(Ivx>n z(|4kypFf`t(}8u+y$GguH!5QG z(Hf~~?d(f4%%kcN?efmF)gAZyR=clq@LoE3kS78=!Iz)l6VT5h_&{gGwtQ+YECD@J z$Fl`|poK|2oqKQZ&7#;1_0K*<+~!&c@=HZwEOYhz?!fo+^2g9G;M8hL`qq9@jQZ}wTSbxpvL9gs}xIJT9CS6)mb~{ zG!j)Q&xOt{qzLhP4tq40dfXl^KyeI@Wb!@wc)~Y)L$xRj8jy+LdWiA^c04f?@UMjD z{r|{Zc2;G49Os2qJ`QKvh-jk5cT+B!w-Q=^8^%gmOz$DJN)&DY1miE>?4`V|{5 z%y}?L!4r1CN^Y4ii00jwpb_@9@Mp&IAC_3WXE6?9@d z_zkA5L7TD(C~DBdehqA`?zOkKUsr_<({{TGXO3%Ru#9V6-NdA!s3oqItj1HFjb_-< zp+I!YAQ$v%qA}PSy>?$A^MS~vo`qetr$>=x&y?bMWG9z(i;!5IttJo54^pGVXGKTsdrIo0T_84twYI0IY|gjHhNehzo~xMHE`6`jo#%7<^essZ)En=?k=Tr7*G9lK7o7IY5u zf?7EV#`B?uA9P|KmF6XigDHT<<1=i_hqg>>J>pvQ@}G!_@jPNrdhISq<>hnfZcXYm z$6Si0m>Pz2b=RdPv$ZptjyqL5l?;jRfvWc2pAtQ~HjW4j^Koh?D3H>a@;( zWCO7NI{ZfCE`9eQ&vd@ufUQuHAAJ(RV0 z^>1slT-4E5v2L=(CE^5hqh^*nO)I@Ul(&8jeT4hEL@ttfw4p@2iiOQ~2D0#z6#G&g zw&6q-$et7QN%yX@@QBM{x(Y|8MfO9PiG7s;TQ2%x4u8&>>3FD5w)%V^bzf`J9^To@ zE$1@`EjZptr~*wJoF#N5zmFsWd^vvXSjNeJDiqsHHh=o^8-gkwe%FxfZjbKwK=*K0 zm8+u&I4GedrT0s4Lp7cZEIDn#*#aPJD<*7z$7z&t_ol7de>l-OdSh*6mI0wly;U1r zWKDP?!_bwgJvFz|n@jxqclc#F!O_SNxIpD>(wbL%%t{A2$w;9~zx}TX)M-lGJ;NGC z9FgM*X$#~O^xSQh-L(_t=$fUVKfA2zdA{qBC&QpRA18lR1{GA7XTsJ!mCHJ}jShI? z-*T|nPN5Oe&@ffobJw2Y0#`Cu7wfFI-fw+Snv3xADhCPweK&x!$^|94F|hM292|U; zRS;CVa61aV)%{;GfK!s`P0dp3kkCmV{XA;gSiwsC3C{~$rACf{o>2bb+d~^}90-MC zRG++vtGbniGeHY-2M?oVKsIf}rQQ2S&m+IXr5HyzTaNuVrJ+Wyuks{Pfl8)++X645 zS$N!jcTL&H$Mf236hHyZM-Du8Pix|KZOm!io!4j4(i^axzc{9E0y93FvQ!d*IRFA( z?}z6}tqGSeU$z5L|4f*sw4fKbP0}?~54w9`(mDu;JRygK{;6Z7?OA)>6?Uqjq`~GlWx~6!Sea&{g)(8>r1p zNT6G%kF?!A)NkQ3+2{dlCxwAylw(J;fcG(4|A$iSY^O7j$SM|s2s!zGLag7+S=yG( zOV^>W;w85m=JBM}Eh00t;w1(1cFKGA&@SO$%QhsQ;UMkIl_hY_E{nMPZZFq&UYq0y zaN8pf6>1)Q=dx&Z!3EC8o(BiPKW_#Z61QI%P=?&75;E4LR?+RJ;H{rO@8D{XzWxC7 zDrn)P+n?g`@#kQdD?L#kpa?CBYv8$R3QjYIRS#jMOF*V1a>w&C=(c`NkBzp8M^%?@ z^X!^E$2Z0qaV%ud$(hM*(0cVgvNO$5&6&@g8mnG9v;!$1C=XUQAxUsb;$!rZ_)qk< zd{%|?&5{3-q+jSZ7;l~wJ+_Yqm=ev(u?bQNnJ4iwpT3g#ourfp;jf5?9+l!;f4EL6 z z>gi)BDD^_NlsrFgt~hc9@|M%0yX+F3;R}B^h0*dEF>{a5?ibIAOhgYBrqGC3r-I0} zJ8iX8q~l{6ErFJq4G7Bk5?}}ivuO?wl)=ymDVzdO8aIX|uRQiw z=0-<`k^M8ZkHa_g$te1vUSi+$gEFM;LrAo70(#az{S0tGPL_S*+C~^ zx>eR|(+83KRyoics0xlNV3>fl18<^Rf`a7(c}u5x?GNYB9npp&1=#pze*gX;fLTl% z<|BM+Y-*Bm4uWqrvg{-riMNcij9u|h^(g9@UPUQnnqkk>mid8i)3zkWF5lkFmm9oz zobC4FgCGyp>a5n;kqvcR>yC2Wq--3ZhMJ6<*~^wBl*0$A#*MR9LP!NVF2+j__(mG@ zA6=;ESY%&)qR=_#eBUGf7)#5V)5}IwL361BII7;|z~*x_#)~35-?-8|`rV(jvOnqm zLQ87~Dka4^6kd9L)~m>WWLo1zLU&u&3#D~TVMtq~sCzj~trRL7UNn`cQQi*;q&&`i zj8rH_mR&7R`~(e~{EHXK9AJ%t0Y9S07&wQ2bApD;zVm}lk)fP+)vxufEk#yv6;lMb#$oOq?l zmfGRcC16+P{!K+GD1uZXM_N5aZs~juq```&a8ZT+2oZB0XUY+PI}*f*HKn8)LklsQ2-2=Ug9puhzIwv@$>^f-)Q?VEYK z-NW*^ASs)JT0rroD>|%>Q!ESOpWsPQP#xOOyY`q{HF+*_OwuRt1iVO)P@~FD8ms0N zLb?2ZsqN0Y?j|;Qy|PaJw-C#|XFU;0Ppj^m|C}#DX0f%IaL4aB#q!S$aec#Ljga$a zH8$5jVaA`HK%^B6??vo!IVO#i8OEC&fWDgdZQs(4nSf^=ll$5;a3hlefAt<1&2^5B zPNRQp{R!;En3+I^aJw#n$J(6i?AgM=z0{ab%7#N4mOAnc9}G!V3^jxJ53tXj>lc*j zjqA~t!wgAV$ugy5S_6A?j2h+uBT+=@Px%eIjglc>#!+!2XcDw_XulcRqEFc4`;-N# zT1QNw%AD@AGOA2)7@kE7m}NutViTyel$n`9W`p+j50jY4D9mdRQKc{ivA5~3^4-i$ z{x<&-y~gjGK*y(pi5v#TiK)UF2=2^`0WgxHK7Q%+`pi!`;lrARennT(etd)`+q=pj zUY!f56EX!GfK~KUmv7wAP<-|objx$)v)Dg&W$yB)LGPmDpchfS^0oYx^mcKNFF%Dc zXcEWt$z+uG9qyQ(KK;Vs0;nHN>RT)9r%w16U0#SkkOCfvW@WV0)V_cboC`aqTnSi) zZV4)pWR+|UW%{*jLf`G>{Dwfgql>+{aW4PnGhhIn?Ck6;@oy}w{?4`e*Gj|0F{{Q~ zS#gXjgY`ay0POZ$S(8hz=?W#Xp#Xp>RfoSXk32p|eEh%k6uw zUcCyvHySCp*K>|k^zSqroDd?Bfh>O)7F$l0U&q|2JnlCieCn`Ac~5p(jw(k!Q9_ng&e`sx*(*?CWn9+2dB zg9ORv1C)%=80n4^sOahSZ99;|dNJqsj0t?J5L?J{kO8D|cO(;2Mz=ct+&$j|pD;0y zO#^v#o?!i3dO;4aQ8fGBca-GBm*GA0O7Ft~Z|ZPB>R*JGv`k1E?7=~d0Fz-mV2<7z zbW~=*^uKP0!=mcHCx6%kHC(|BW;1*4JcB+_|1)RK*nzN;0EPn39zJ~AicVlQ9@5_R zsE}*0fpSpMufROy$$w_MCRiYVNg2 z*e?#I4+QC`B+Rlk3{q~$nBiRL$zIww{b977vvT@~ z66|>dsXv;dPg|I+{ua0!Q+Wt~JhDrBrHW;B^}LrsY?64IF=`GplHDwV-}7upqSesy zrKdBqq(Ve(%JJT%guOiR3iF=Y)`}Po-1GZncIn^83N`##wKNKE$VmwCto9$UqSh=k z$Opxq3P-Cdc>9e%ezd`a;H=daAvqN+F&Xp9jKJXbhgexDEEB~i1I9_uzzK^8u3;uH zV4k?Q2fL-V02-)r+|0^2+$|y!CPZIq^NYAka@w1o&H*(MG%D~MKc=UG>2L32Y{jBQ zgU0o-T4hl3Oj(!NulwRJl;pS8B&$i(qh}&=#mnGrt`YlvsE`MggXQb^8NsZ1)ztx$@7LJF9>F~O@@m&c9LX_u4Ie_tTay5zU zG5SN#r2^a+g)y!E4>j~_=z5F3eDv}vk?j()8`!2n+K;RuT=f9DRYVXV+ESTzu&8m7ugQd!zX*~zoVq+vadD6 zZ>E20m4H3}RD08-0uI!kycL>#lMs%X&c?hIWFxHEv>kfUW~R6We=OD(i>~&}cLs2K zJd3E^Fq%j2!J1{>kk+eSzb{XZj?erH_)ZzPLop5oVlsU}-|$B;d?AJ=308_S&9x!P>fclPDkHzx+Kr%L2e8J%J2M{P)+`#3i_eN3sPf%zXk>iKwnTjU_iZv4wu;yY~^}z2UT5KP-oq4iM071(4&} zS~8=Qw5h#ItZHw$x+)1$V>6;1Y1pR*qR9-SxhFuJ$nQgq{#J&wT5&__evzW*wwq$i z^u|)I>)P+qKXh>qorIanM1q?Z1a>A?ZnhaJ#}8{vm!S`f#{#tfijtC&F5qLk_Wi7! zF?iWV@>xVqwZvcx3b>$T!g}y}0F=aTxFu;VmU|k$J6bT;ExCJapVYX+=ezToZQ#Rg z|A0*nbRMES{iOX#AVGj{xU>V=EK;)sdHKxJ*)8LFF&bBUMzo|ziM1{#uE4ijTEdxu z(DstP27AXS$GlCK;3FiUsrbqOR=VjZ+VcXUf_vEww{F_9Y_=aJoMGm`O2s@Z|llX><0dz@%HU|y1=Zg7 zYi6#hk?{FXjXIYPlo3a!EM7#L87(^&lMX)~fRb#?fpHxVcm*ct8^mjmkV3w+m+eZzdU zr^E6^Pyj-)i(k>3)B}PqUJn|y6z!KrFyN&5`X2;a7@A8+^ydg3wlr$L3#H*TAixIP z^S*z~f8_99QHhbv5^3x6ChteZwHmwOg++u<`7R#!mo(nKim^mH#6)4pZrc}u=wdvT zQ(X-ov?~VN)S-{vE2!I0%+7K6AI!grzxUTkcxw$;CAj+bAobH63;mx&r3`#S^uL`DHT=v8vRtg|0U{|31}%unwE6WH|VXojl&y=~L> z#JBwh@Pa=>tqT>YT+)YMC#Km}&~ed#v=Rg@5T452bm=joc>#O>`X9;Ylr&-Q?Cs3D zpzT6=7b^z7dz%A^veV)qlIVgS@Fz2CD~6p6JI6i)MZXC0iuw zu#0&4fQRsotd>?ZB<=^8ujU1C@h;2wIi<0z?Vf)iGy-){Zu$4ZH=IaxCd%`>M>zKW z(kzsNz>WQ<1{L?=GnY}#B8FQSs?JyvWm1H$+)u*}iM5|N1;}#fe>CpCO()|?$n4zm zE%9>S@aUDTotgQl4@H(jpG{78#cGj>=PMIlx6+qEqI(9pd$-dAP;8d)itWI5T%No7 z4q{vcltMAgOkWtTP<{LMEz7N2&y0=JfjdDr$pJ}^9 zO+y2MyqjEH3U}_@A#|kpgKERX;XOi^4+J5qDJoP+ZFZMBiC41(RNaV-# zkBCGAwDdxR*UIjTz(OBJ>-qg_qHd##-<;@b*>ogGsf>@r-lXYfBIS-MGo3C2HF48^vFPsKb{o* zY}5$ixjs=s=JImyItpvu=Bq6dd3Ve2`BA1kJLFY6e&r3ZC*+lj{tBhYwsK}hF`HbI zGOmGUW?)RReD_x%WQ^vfpy~yk2o-Az!gCz#$a}m<$auh@3w1~atUY|J79afQWm%Es zupmlTqi6uCwdvsc)2mpwr?)gxRSu@g=!*xN`)A<$EMT&s8vN4MmKXF^!!Q6#>gm%i zm?D}`<+>kNwH^35vwBZ#FE(N!=5ScG-N%vB_m0YlKZC*X@qGd3FVh6?oC)ZAp7>ni zRKOAH!_*`d>2|k#MqD|iHEBu;EDSw7|M=(U6$)|3Rd5%sx`;AuzniaGk1jmRB=oB) zZdJgSHQ_m;JlwSEc)@HhJK}tHPJlwdcTz9w7Y1Z`R~MRo^%mNaZQrIwPB~RSMFQ=t zHBsCoZd~wln^KpSq6YC|u^gZx=lPqxuhy}n$uIDzaA`qumD6jryu$HpxAc1oy9>d| zxbP*_{b|~{&-RZ=4;ml5F4jujLM~Zs|63po;&Lr3R~}_!DtdC&U}#Z$0RKojxI&r0 zz;+*&ld>G)(vXd;D?D{OOQ- z&yu==4M(EMWudtvNXS=9-0T1ckqlEG^w&>{xcrMkqxuGSTMGK}k6z9SAw5+9!?&_w zZlcM`c-^B34vnHGU`*c)9O{R93Yz}@{_>r_O+@h9W98&*RU3jl1LibJl*0gr(3ltt zHV&`l{HYofgDL6@?}K;t$?d+ zrfRNssb0eT3hlV!eMy@FquQS||*36H1ho>K{Nc}LM z_$s@D6w??K7%hOE#t$cOAFg|a_WB~?r}8|asgU#kfPgUm_2o{O*o_$uAbM_d6?4H4nuPB`VVyhj8qf-+Q|sdWEyyZz}?Nc%0jrs;b=Z zi@P$4!`*4`pI>HtGyy3aa+Gms5;>&+%u@=?F~Ht$#*4WA>jG<~1OVYIm`==3Svhzk}@7}Z5*(8F zK9~J`-!op*u8)HYXvL~0S0@)-vlW=#mR}VV7K+rX1Aze375PA2JJ=NjyJf)rvfO$# z?$KtQEMA{C`$F!$Y_kjL#}Vrm8QN5{twu5ywv}puCi>o|+Ixj!HyR$9+Kr|X`Yt}q zCS1RD>v~7W4&qg#N6L@&1k&_BUx0(fZ9U#p?Z_dBE}I|i5II+-JnjDcQrEvTk;o9q zRp7r>ly1Uy-D|lk?V(JZXLy%vVEdIgb3P5Zd-;lIs|Pc9$>rvnHOpCEQz!tK@yh!S zlSD6FxpCt$%!qg+B_$;s+gs^u3*O^$kZX3r2u)Bd2xe#$oBF+bCl76vT`AJE0T;L* zffIKdxH=^PYvS@jRZA<2-m>(bfPlbt&u9=uu;$JHOSIw?*lgGdR>H+rqoSw+B3#F# zjL@5#3nI(9`ua@p@-H9vW92buJO|@Oy@!9kj2d7favWu(I!O8a3_(+aoF2GNZY2b3~a#RSR-)P4fc#*(dFr2#a^s?!K?XFM<})h~=r zDUd-R5uHEH)cW4fuLDwzwQ+w=mTT8ihQ2^;1*XVVCZhE}u8vin67=VQa#_waM8?MC zRbKHi2=s5}EvAC5(!Q=eEsQc*$N;L}2psAViTdZBgj3rpUR|XW5ucDq^;biF*2Xe2X%&X)R~c z>5jc}^*M}8-<{`^smv%mQj%#Px#Q`Mm&5k+peNT+X*6`7fmo3#`T4rD@HC1=(&9Wa z0fps0PfJdo0rin8a3><5$ur$WfaS%b8QNc|Q#&MuCq) zko%v9eOtMQ_DB)$f^TQiVmD2rjyzS%3ZGu$qTv_dQ<(56;-R5Jo<4aO*cO#kZaTm? zY%eqIQa?czRd9d(sb==cH=kiD0IUG~J8@bV>AkWs5rhRR^R1dV2Tfo%_$F2fjHVYFhRs2-s67i!IjvOlzQP`S!&QYUFkWocg+k;Krca4S(GHJ|_VJ;8Km z#O4szR>?yxahlE#Q&8gqn_0j2()Mg=ZGT1dIsv%{6CF8sL} zv^h)ZxG>OM>zMP>Y)7#-6i=w-h*nNt?w0bqLjz9*5np~@e9kK#=eVQ|rQD_o0XY$3 z2px~{Z`D{hJP9yvd)=u8=6|AlAOBY=70CaVi3dgKzx})swv4&FP81|uGFg8wEJB>*(_cB0bfsu+R+{)@GCR~f?>!~LQcKN9FzwbM zrwbC&pS&l+WBbOZx$b+d292@P42Pv&TjPbb&MpYv*c5h?Rh#@@m6h1Xo>JDce?zCBN}vBH<$SwBMJUG&5k)2h|k65J;gIBnY16*>?X zVI}DXzlpr6V?2%Av-tY@u%OGDaYTdu^XEJ-|2#<&fLRkMGcz+>K}IiLz$BiBk8Cx@ zcGpMOopyROt(0FRmoeT+N=)Q2?YfCKC6zCh*&g%aDmbwlXzLhvy}Z&LLq<)4Wa;7t z?HuE3%)6HV{oO5}SWsqRvpI5A4B9E{v}KXNz~5mYSVg?r4Av9K`eev&BNrc>3op0p z6~Yo*{Ky_n{KH?A@jTx)Wc(C4>aB+%V2wHnVc$g+6 zvH{s$=$9|XJVq~H7WkaJFuoG~mvFoYtRPKbA}&*F*-AZqz%)DO6pV=o2@N$6=JaaI z)7?IX*MC}?^JY)@4=GtUf@ImLE?uYVDpwJInJa3oA?K0Ldl7iNk^jGbY7yNs^z8F~ zXEbfu+qgT`bNHdad^yfavC2j9hQNGvr9Y{-^?SQM;=nr&LQi_+wH1D*mY$vu4ARdJ zkQIZ9G|5p@Fr`>^as#DX*dKPzMc4>NlG=(en{mnJ#?0E9U9kmtT#Ue+f=uly7Xv28 zGA)ff-B&A>$ZH*&3~74GxE0p=Kc{2tEyA}7R&}Y6*RgO&VEOHPn04HofTPY>Fk>P zIPB-|cN=07DZ2oN0`su#Cp2`@@?-UcfopKfeJixX+<{)@qEnv6aq%`-JLxd2bZRB~ z6&blk@OH2?$BL61pdCSn`7hVXWWI=bRyRzjR9RBL$7n0^du86@&i%1;m?fKVHR9G0 zME+Ld<$1bcTtwJTe%wfDnSVW{c@C>!S9Z~k66$D*f$;C$jbQu8E4tBb60u9tQV`w+4ORKzF%>va#c2>K{Z>$K;07gI`<&QGeDIB+mP{$cvk`z z6N@5*R|-=_%{K#GVOM1sMkF^MrVQ9}$z3pNF`aAIlF=^J1htCWj?3yDMnO#c1xKR% z^QXzz1ia=nkg@3yVD=W^$Xjo?Alizd0?fnIX&7j7PrJ z5;1dgaIh3PO-m-(7-frOmEXGKVk|G6WP^qYB~f(QX@De!=u`nOTb=dUuCUNv6$N^x_JaS6+NDG zrK{S*&!;FmiJa3UVb~M@R4A@oDK{W*YBVD%=#TNTzx0OZ#`eHsmvg`3W z(ea@nw$eCA_K(Xt1N!^o%LhkEvB$1UPy^VQS()rnG716%pG8pvHux)jx^vcdyTCxa z=`T7R$-%YXinFe+ZlK&AYp_XjC7qAf;O{BadmBeXrYmlg_n*V`CavR%Dl&RbbfiO+!)1$fCp?G zIQfO`??Bde%3Jmi4WY$R#mvgE`jZoG-8Ac(=X{!wEB~D{RLFhF`*z+V<;77W6%+T1 zGooIw<#bM}tfx(z)&F~LKudoDW%T2N^U<9(P-dIfFafy(j>i)!R3c2H#b)6to9@aZ zb3Nd8{qW&K^)N9gp;FNCEIY~Of$a1b$hz6LUUojiKj(oQ>DHBso1%i>&Nq8hHqPX*7lRq91jP&YuW@UMn$1qFq6*V0pWQuLT=03N| zR!RJRw3v>|tLkceP-NHB+knpdzeOOvZKh!VBqKg&dv1pwfuf5#ugCo`(w zo5}`Pf)hx-*7O!~Zx-?@LDzp-4Yq`yY%>!IBB6WLsWLuZ{Dy3FUeOVq`BD7ngbh}Q zKVzpi@Q7|aVcVti4nD_9O+*&IEu%=YPA2|E+V6c=*I;>u`|gX0{9b0kq!UarSTh~X z9Odo84-MoG195}~L5V#%%6B?t;zS+M*vf)16Jj9a4NAyE5 z47;@Ku>||3zL?17AYc9Sa)Zt&A%?~u{4@uV>)HVh0r}jsMFD8RD=G5v`=0wGCN#S; z^1nxWUWXqsbjLU0hdnyaBvAn2eAM1PSfBWF24*Ar1crUrvHe|?12~zCG{^hb1l*GAM)L#`1eG2Hxe(}#}YgE9Y^X=@`h9hkTpz2qCNW7_3U_e(h zEpG?&5gvZJ^*H(~Joagr2&3K614kS$q8j_*i#Gw%0lA!R24NeA}4u6!mprTcnV-Z$S2H<>W8B5=g}~lNm?mfMt}Vt(7&ei`X+U)9?oPaKCHmG42~Ob z>?e^9W!9hbE>LWkcQG{h#MKhb3s4;vf-_jRAC*#9S7!>kaqXJ26yxONt=tyzqdvVH z=g{xvWXs8tpHY6YX?4E8 zaJq7|wY9Yu`q$Z7gMNp^#pz6~OAwdps?Ebk?>v`VYJYurZ-MS4vJscL=D}T*s%b3zoPS%g+B^=SI8> zGuJlZ1gOk%!`lc}ZEM*rx7}k`v;LJEjd=Y&ClzN^;6LQ@SL|UU%i7ZH2N?z2_vrZT zP2}P^;gKr}%uB%@cL_W+wu9{qyqis`TZgGaZHe#>G{S zzL*}o>Wr6gFRIO^r>A8V%k8taN4zpGD~XN5Tl9awP9HUxuwNpk{M5$g{mb3xqNB)B z_OBb8Q#yn5aI5Rdsf5#B!f{Jyv|8u9w1V-@$NjZHsT; zlB4&%?Ogfwp)8mgldD~+#5s~eVvlig_LpdAja=x$cnsxCHY}Kijw^It#cg#tunuf{ z@FF#w=eF{0xodpT#FbdH@D8{g6cOZSD=Pyg4Hra^i#09hBnMkI))}q~bYx@c%DOTH zt;~_%x!T2A8ZUpPzE&t~{c$3OuencO)y-SlLUGd_4G4!$tm?mnp&+`(&$FMz>YBfx z_}~86`*|yDWY|D8V{o0miEOTXO;__qvoh2Gzdx2*FL}wrULQ&Raj>P2Sa;7iR%^P= zL5vm$P0p9o*74H&LtisoR%p(lXDLGRdm-&|*f1GFdJFr+#Wh^QGI#XrUYZ4O_};+J zj27OZf|c~c$WGX~Ys2jww|tv-(hlRyU951JI#Kf(bl=s`9qeR|@afqg%Eyy-zMY?XVyk$q)Xa<~&CZU0arJkc1Y4Q<40ta(P&=9rleKu!a_jR`t$E6YR@Kf?&-g3k?DK`sGA4_MF@^|i}cY1od7eC@V zFsD*zD1&xL{uOrpH~;L}v-aF-E8Jk{mnY1;((i zZEl5}uQ+pd;-tzUWFsYW*+cQ!`(UO;LWh_Nbw*91=T>!|!2JcYKHiZ)IfMJgw?CO=vS3*J=fIhvA{Q>8K#b zP-E4=2wyh)aSPMP`pEN0oijTsySN^VS?K8h+^!nGoQ==O@a+3sr%;p>2c)L zO$QOiiL#Dw*F<$j%k?aXOQZd|4?#|pd3=d~ zgsvl3p0i~zg-V67=!H~c{nKz+^CFXfGyY2a*LvLGD8DyZHF_>o(7wUZw#qL;gL_h2XD+=1{{0kCARK$4+KBdks~2N z&2l7&`Qg)~=6src?j*;K9b*cLTbjaAzkK;p`2R<1^w_L!`n77M|7xV!?0n`SP(MjZ z`?YiT7In6yaVP^f%l^}bElnP%eV>2|m|Roc_a%YkERAc`EeSUs|0n38Q(_~?0MJ=bw7DmaCOh8wx4co{ET}kAzmt)L;58mp04SXu7r=Pmi3j3BW?|N&m29$ zg0h4EkEyqgin9H_hlfy1umB}hL<9vyN*YB#P)fQ>TDoLNlSdH{5RgW?hmIiz1wlYU zVCayJp<(Fwo!ig%UF&5%>-j@v=8o$+*ExIdvyWeGfhXjnFj7L&Y{2Wr;Nw^Xd_67b zVgx&py!L0SjpfAl1NjdDd`u!NmC86z`@o3hCO#$vEUw*w>1kJQsbdU=Csuha+SKG3 z`}^bVts@~(BCoU2Gzc>C8b)oKx4!D4<28+I?>$=l*pn50$u$2uNU3w}HasM!RFj! zx0az$uE+@=Pbx2?K)njRbTL!VelBbF#Ck3%t74f94yR!e5Z7Regz9a6IzOqmt>&j= zxFth@JqK4W6_t>wz#L#XKs;B_=={1Mq@=2M36krGUWbiYmEguVtFB~!t9{#s^Ndv^ z_Ph?nyrV7a-_0Gr4LXw-jPxm%-=(}=ZD)2PrurhIFoS7%ou$b_5mS(-hp6AEE~(3l z6xb{K6@1(Xz8|F?INTC0jO2Sc({7bSq)Zv?R`+SNHk8n=j`lDB7wHTJefm`EU47at zZGYSGiA~1i{g2(+{mt1; z^S!y(g@94F^f-&kK@v}JGYM`FP!!+u=03o+=oIWwz}yNv5JPVXB9^^fk@I;Yft*bt znrc}*ygjS^G?H3_U(C8BdPItOT8;+WPr}&*SDs-4MKJxC_(fE$b(bbncQG^N&c8mxA1J|UG-pt%ei|xF$q1D2U>Z%qGig=dBT>W|3I@NW1`w;==9M^e1amqe(l-= zm_O4C!@HVAXKG)OS@##Fn(;H-|GU%R28lJ~Pn<2w*#KyGh#HKvn?3Xpq7y7l>nD|* z`o+xwda4(jJG%}1<9Mj(zkh^fuLwjTj?y-l>umO16L;y{uc#uKiDmJS^njxZ<>jFf z{npM4pBj$)8M$XEBgd{Z7jMi#y{zNue>6RQd@-FBDH~CzsUz+ayJ-hM)z5b&rP(cg zSB64az%53BGjtf8Xq#y;^kTE($!7nB1FN2!(!vYaG-vPRe`L`SvtM(%WW?+tNh{Hxq&4v8F+U?gPn`ZcMc!6i zXm^H8Y{9=}aqdi29BRP?VB^|{P@2uZ_;93pjiOW@iVzWwAI5^pz$2UrynrNP(Fw+f z?!*Lh+iq!v>}*A+oK*yzlq{dHJMEW6&2Oo z++29a7wAvL1o6eySfhWpu_k6_-==&X;5ejQ^E*P&v7xlmn#;}wT(-J{mM_vcyAMG$hvg|cEo zO9U_Bsa~4VO5@@H6SZ_ zvW@|*#KbB+0$c2O_WpHyz{KN2+~Z5D_O zzxLd}t6rn?>%|yyr*~P&Edh%Jqhr2L2z?(w-3d1wgzV)`i@w2vkN~sek8hgx^Etu3?jfsv2Ot!zY3J-tCj|eR8h^kBz-49M&~jP**AoimHE#-D z!uO%h-B}n>L``d4K-H20s5d_rMZZCuHWhDt92BS)gOxj;O^Q;Bz^)>t)m&gq<*grs zRP11(n#vxqHCyu2^HT#NIru>hqL$Yh&;w0vvA#az zNhDXqq`(-EpPMhe0FsZGG61zftgK=4=W*6P@Y>=;3fug2lWvr%w z*=0#WJ#kM$3*$Lz$ik*ji^@tgNsk(}oy&AY+o%cRF*Ftcw!shi#mdNwe)=x(*3QIK zZ{{N$UvMwO=Iypxjgm`qMkhId|9fC-ZL{`YTUMOfrjEWL49oSWGz+h${KsGYbl5s3 z+41qi2NjG#HL!HU?xWhFo+DKrOu;~H4w^bUC7xxt-!ZWYW}_M9eYlhHGpbrz8L3Yq z(V{Z|8uP@{N=^w!sLrmJOdKy$bJ9!sZjD0a%S_O%qNk(XBI*y#TO7p>rUU>-m%K_H zvFq-QF~{@UIXv;^Ee*yBD)Or$J<6!J_cueJhRFye4~RVI$pahIBnUtFGw(%LwK z10{JC0b~Oji1_NqO?7~8{F@OVf#E;$s@f_#?RsZ$tHd1n9Hb1LY__3^6Z0%(^^iE+ zHVtm1I7{~&aC-E{?6>;*`g_4MGc$x3`x>73t!zw9C&;Z@MB`&)bC!lH>Dx~yI^_s` zPR(ZHR?Q2}-t{lVBv+yZdGx4JsGf>E8!|CpeF{h{?lJ9+wrpA%n%AtBqs~2+_Q|>8 z1-FYnYGcA;40(Ub2>qr;)(GlB!{Eu$Tu6{`@ze{O1fY~+BEta(tA3{Dv{2R$-No5eZer=pU+7p3c_%uBP zMsF~&dvY}vW`XxuDs~}FwqTd&A!-4-j)wKNuRL`Vt8j-pP?9vPlje`SwRfK#=+&?s z{?03|f7HC9h<1I+*1tHy3HBgYJKnoyV%|}0l{}|&z|GLkMPbU=%kt|1WIXZqdb<5- z!G;a{w6Wo?vzo}3M}2Qvnv!RvX(B^C?GFu^*qToHbKb4hcUusfVdV-43F@_+j>#v3 znu4&Zp|W4eMXZVk&P#69B`ygSiSX-^m;c?8%|LM`yq2-m*bf)k=vsF`G69Gq0QLNK zLw%Ntw?AFx`7yDoU1ZMA!cwPI1C8Hvh@v9fOcc78hY$pQRq^1i9f&6wbZz9Rjnj|3q#^ z@^fKR$j)R(+Jo}oh4FNwEr+%A#z;Y-ZH;}g2==7-p z;WB=ZATeMBCd&hr1qx(WNS0VCD4E4`fE?}pirJ(4Gq13$p0GF z5XBz{Cnx9nOEek_46wx=X1`_?z4=ZSXHg|-ZYAQ|TL_AFPK)@=ggEf4?c-h1KR$p> zFL~Gp>T%IHlb*1J7#0-lG&?@ceYCSE}#rig&&1k<|4nRP-w`52Vu7-V~ZDnNzH0P~b9neB< z!BTO!kuH&$pP&DG0+cVEt%9R3Zbah2+q5Bwk+2#I+6Y8`=QD!<^1LAhd0Kl|nLxvTPUFYI>c+uaz^H|A6 zps*c9HLDLRBmp7UF#Zrp6#*aOcUPM1F2@aSZY3ZbdchMPQBET6ZNM+$ap0rOj6-EZ zO!zBR2-z`QXI1$v zT$B!sC7qKUmqE;d7UeZuKAQ21%~>En_qxg!UaNUBB6LEHA)Nk;%M_@U5CBHsFxz&l z#$IPx<+9R$0-gee@Y)0bWfhclRo6+XAR2-q0`0a$85mU%Gy@4KO7hrU6OtK3PwWjN zrFE)a7J#HH9kx-pXDh5(gOlOc^a2@0G%&bBEG3hu*0fNvOyD!<=te9QFcU{0^O!nh zR8&&pE;}#OcLRJPK+(|qmB+MM)B>P(>|*I4pX~r2#E`|)V?e9}w~RDwPI!P&Hw8N7 zsy?2*dY?hay9YzC708si{!i!^45a4)S+vd0($idVhXJjj2^a=Jh;7~Vl6pTOh!Wk0@C&q=|9B@Fz`MIKH0jz~ zo87#I_FbAWL01CyhI=N^9wUlk_cKxpz9J7py`J1?|CXSjCU?zt(m;s~Vn06j&7Y|g z24$v!(^vDNo9F%-;w9?Rr63r$MS!(l{5M@H15^xMZ%(oAi9i(2~xjsNN*Wv zVNt{V_^nJV4n0D6R1`BOPxn5(aoOBYdf}`G*0CWkfuira%C8tE>jF}uy$snfHB(1J z?R;JBou3Wkz@MPh&!4SThGH)sJc%>Xt-3B)KT_|c7ZTJ)z zh=+eZ>5!jDdqTaj@W2MOG?nS{{TFn^V!ULE(Goj|~?Q2i8i84>T4mf~KL_~(~a3_AY zXthnrC!LUXr+45@df-nauxDM+(0W$^Y0i9*$WjNS2EIKmdo2wkg>+8dwkYVD>_$|9 zumW@hViqk{L9d==k2}zSRkX=2kW~s(|+Z>w*LwAXA>T$BW_19ZkV< z1zCt7YVHDILotlKKQ&eL_w{K+1*j_VP_o#5)Bwz%y7k?Mr&g=#{HX{qm%EFMN;DDV z&Y7@wK+XAn$gb=jFK>x)-ErvEPy7+~8c44USkqD4=TYQ-gNvIsqz++ptJrL%i*G>N zaV{1~Gax$&TpCnc&by!3C_ZR%XS0?zVzxy>FGs*N47v5Nk5BYr8b>$(l#tRfJ9Y^r4%;QaL+arU87|y$jCx z!!E4(nv>YQ;_#(~Rx~es#NTvF6s0LBMhhDP>Dkh|b|z9rojFWNm%&Pp*zS9%s+hjs zI5e{cegu_#sEH~FARDj+GXQfHez{^)F@pg^WZ)3ig$&`$tl62SN1VwSShR+~{|mYS zKF7Zt|KQXv<~;og;&(C<$z$zd;UX$}uNo%Fzh()XD#jn|1+8puJetGD2;YA7!2r$( zlcIjU@gFX&gKm1G%guZ=TWg>vvuT&v9h}P5eol7P=%akxfag6!3Poy5!XE~N|A%B} zidMussOf*wjIsX!*pM_63Sagla{wl=J5M|&j1<+j{NpB`xU5?_XP;o(GZMDbFfM+8 z7f4NSuu_g0XfQ!m>9-(i4deM>-~Hs9Prt61PAqfNJERt-??qcv=BcI!<-zD@kkjrp z>dmB)_^vgvA#5kanZU`1_)su?+gYEn`Stl4(${I`0aa2O^cHc5i47MrgfBv@j!Zel zPqH^r(8$zf8Z2gRMTzPee0hH`od9~z-UNTW#L4o$h*-#{HVH!OZEk8?gc}gJdcjt$pHH+j$PoVO#SzFUoZ3_Que* zOcGjdA~FB4snF+CE+iRV!D5?V<9!cz5)=+xD~BZnHV+H0ZATj39QImol{nl|GNq-V zv2F@wm2v)N4OWIxAbB?HPniX4Y|E+UaBD~_Sy##Cki*KK*~hX;ZQ|`)^43@()rrPn zK_+_1DaVST=u#7$-OiRgSeva!<63&nf*c8sD9?CCd*0(YIeDY|MxS(aZ^<8h#X& zo$8aiO7*x`kYo`a2`@y878aRYZ!NiT>5>S3lG|{uizxdEqe}sg?jeL^V{^oq5#DpV z2yts@tBrp*Ej`@^I$Y3TAy0&)!)kG$1U(&P;Un7n7V&6=9>tkJA^Qcz2=h%X#jMF|0(Acc ze#|J=L*D+mJ5~C2VOa0d+$1p*Pk4Q&?<4b6RGOk?v3$1I^5kHv_}M#3UR{fWurco$Io0& zL_}7Ajmg-2{Pd}tHBxUao65qjEate8T3?1raxv&J5r6$$osu_fjzux0aj zwT$V%0P$Xg-}pJmiiN#*H-c4tQWFFZZ?dw^<(7@y6Fy&j{Wuj92&~Nywr8A)wgbg- zKs)Dks%jZ4dU;jJ1T*FSNtU&lX^V>%anI|?)6a&khgmRc04hWM!Gl*of*}1xP=92D z@E>v6N4lu^?MJFQt!-h|DRXu&!yh890C2QRfgeoA_|Je6k9G6Kp$b*_Dh+5SxWUfD zqXMd6q&pC7RFX&crv>LnaX6*GI@If4PYH(4EscgM0B5NO1n}ve10@?`BNRRs=h78( z^yj^l#i#lqpF5gczWD}4JxqUM%3Rdd$oDEqR@#SJ8;b>bah>Zo>m5AlV2wy_ueynO z-4)Y4jv_Ck5ZA+)3cV9IlqgrQMWFv5t<~N!)($Z`XvYyQ@0x3MT0?TD-3g@zftM~e zH9)qEI-!)4f9hhT`*P3TGVZ7-?z!*oC@hpeu&lDdTVD-r3mp^ttGHpit@h|pLEC{8 zaqnF=wY+Wyq$v+-= zxx5uW9F|5O`IDh-SD6^w+3#I&Z)ywMZHZMtL$VDroD+tyvX0%bAH+71G@XWvL%o_@ z3tB7^+n$DdOSz3&dzcza%zCq-So69bBLOGmQ`XOmNp`?4yi9^gn?~9b} z{7rSV0dmPF_$nh$_Y5PNYUP^cQpPP28Ea9fiBY^u3&UFYvo)BfI_0vO3I)#%T9sLW z^s;R#2tg3KpEA*&eIBioQ_xuTMm{d*#Ie8C`{T{FsHKrx>RX$(8ks^!5`I-{-)Vhw zt-P%$3hG=5^?4Vo>F7G2pO2q>(r|i_@(pnP&%)`NT|fNy=6Camfj?caL)hg5S40hb z=O%o>xdlk6$N*;KT<-(_5}gm>Uyw#K+-^LSi>nh0o#c>~G;yp{laxc*j26f>{`Z9O_w0kUYgXn5GK)I$6aLakWtZkwDov=~Q5h$eyxl zkUj!Ju6EIML@QDCz?poq=|?tk?K8$pMr#9qfZqI zx@-8W;hpv?0%q?F0H5Zv(eytnjQWz@Hy7GfyEF@c?|g(#PG{(K{Ks&*`pWQ2#8FcK zYv)IEUyXv`6a)es`GeIW39mFze(UU9u5%+>J#_s;_D_$dvH2gOGCzU%Bo!*c5jwnr zAdbik?%Q+$m8>kXy7vwR9p*n$x)OhNXdq1F9SS2>@VTi<>OAFrs1y`fTyqt!-vwD; zvOx?x{gb24V1Pj9XWhol!7*PonhwtrMNrTw*KPNn@LtE<;H2w~Y`6{@hwg7ah0sou z>MvRPZVQYS5uqMQm%UJuTU9Z^Lrd1KgqjDl$xB1JCZTf(a~Ymd{(-@zrXH-OG!xy zy$xt-RnAC4DiAtzT_u3eS%D0t76qL2GquJW7V$QCfshYvOYT!&o zt;#7bj~VIKrcmU>r?K=$O!h%roo{@J3RL$6H^l!o^_!#{#FnWdsmS;#fi2jsFHIng z&Nna~+ex>(!N#WP#A*i4^TNwp&@I4G0sHYs3pDaJ&8^u^J%$se4nZ1gE+nz=dAcYC z(hogbRhbs(bEr&3nrSA4o=%cG_#Bf?H88wrv9k3)yq>!Hz)x^9dwf4?!XF=u(At8?8)!2t;eXKr=Xcb066AQ}d3~ZdM0s@;=qY}>3Pmw2E zNar^(Ufu+uUL6W8osy&d` zn=G@T8l|PR{%6komZCC}#ZUhelpe8-A7Za3U;+c2GVD&hfsOKtKS>sg<}o12DE-BvE;^OafI# z38@O08yg$c+6;P3n*^%}>qvT}&J$X(TOspU><$t*hl{6YZeiRo9`ttDvUe z>31PRt&pLuaMqOP>vRb?=+zjJON3S|W_oMi`IWIcl8ov72u|J2Y=1qF&4afXNftcJ zEbiO5J`90gL*nQr3oJ8Vo)F4|y&gMgUE(!cf2kOP6hDBR0F&gGHIYMg(a#hCXyGRT zkq{%5{tQDqd$;#820wK%a+iAMz1`U}>Tu}!X0bi8X{#0^?z=L6VW78?L$3C~XICe8 zBmwlOe`8ZC?~&=lD$Gbiq6g$xJN*f^0x?Kg#HmY@_|eA>gwc@B7T-9?QmKIC_0_GD z(1rQgyR;rd@GQ$PM$UN$aUiT=J#rImw7VWxL8&=ks9DpC1%#%aOqu`EHmI7IZOxsL z!wGdl){R@l54rxwN5g;jvgBGerqYsqepXZ}T_jdsZ3QtkYP;R8%t|YA7g z4j;O5|3LT7hc38k$xsdE#3lxKm2aR7=>SxQ`DicwY^gsLa}P*>$dv!Idmj*c&6o(C zsZUrnNKuk6SJO%Ei}5Qi5?JXG<~mlXsF+-#Iu{90LyxP*pG7Xkm&&j?ordc@Hvr-j zv8`503??A(`M<6v)OK?VNv+c#kP#cVL-W`7;2wfysqfZiBeYUTP}*r9egLreSAd|4 zTHxDTPfQYiadvhNKec@4dT;&X|L^fa!g^=D4@O2Qe+b{#v9iiE@FuGFH}{Q|$_6uq z>p=h+tLr`f7or=)5V`Y|hwLXIC#V1%2zV@k3xwx(A>szkeUI;;z7ZbTearh=u0~OG zs;WkS>mz^~@UudVz_ud;pi2pGi`}^00D@jizyw6Wwt~FmJ${1Nwm6J0H3(&0wU5Ed z>+(9?`4G4Q!j5oFHM-e*keO2d9FD!)0kls4;?V(aS1&oY)jSLmlooDW&iHukq5v-- zWQ^kbqtcCbWqTHZwXkGVip*O{)gdQUHwc1GeEdW*pW{o55=?^018F$*?jY>AKw(kR z8P4Ax0C{^?PJIP@f@Kx;mIh8SM_xhey#l?2yx`!VyT~(uLY9hq&leHNcO)^g?FaqI zRmplK4^*W=47O=^p(cQTF0Bn)V!@){or3+d9a+6r-2lPQwEvyV#PurbOCnP)t2>ZN z{#zc($ueh&OT)TLN1nGP51Z<~0aj-TPLm{=1PB`F$q-o|{(~(&mK89zVEl}Q^+^k! z2=PZ9_IxR}wx{8QK~2r|fLv&FNZJ)>^!iHA0lKqZ#sxHVTKCDX7JJpKX3#8e*qZ#; zdQ)1~K^I}kQC`Fr{tHva2X|3MUFVP3sMA=b=`&zEHXD}>@)dhC2I2|>&4-4i_KtYe z3`a+GdtEc_Zye6h-*Y)2+;&O3>L69DTrznHjiUjdo5UooOzNBOshAJ5m*Zkc_j_@N z>Ht{gcB5gJ0)??tG>5}MuULkBE^JMQ5NPXPO|bn#kxl90s$Vzn2r{Tba=RTe%$Jn~uw-!~*r47wW|&T{+xGS-FQp>tEOGlx48Zh>GP$b{(A{qgrC`WD`sL1zcfU7wr}mDP`O$enA3jl zPr=Cwv0wi9@gv=9m=Prn|MBzl1H7HR0qhB|cdfUHLqPOFm)8R+&d}&?ezyfJ;+$!l zxjAf`3u&T5Mf9g57y!3qwSEjnEA9 z=f&8G7G?jKTRK^6ZL`V9BPwt`Ht;p_)c#UxwyPmi2NDyD2Xa?UJxh5rAx3&F@1Bn% z&Nb-qcX>9OjlPh`seU&#A9{J}@c9YrR67?`+tUv!#hhxTceC%Qn&8F7lllpI63S;# zsA3v&zc-H_J$efkUE*SEzgW&P3e)-fL3>m(bUMyMYjZESm56G{!q}jjO7S^>GbR+O z{sItjx&Sui2@Ny6E0(ZW^8N=7oFXCVYn48DMr`CRdg_tSF84FM1daBIIIQ51T?XUi zrUEzTo5%mUQ&tuj=j#`@*2BJo;%8e+|0zo3H+F{%b>eX&hxHfl@}XQIAA$Tga*&Vw z^{m5|;_GNPJDJ5t&6~Z}1!v~k3WgP;PUmVqkP9zm=1^a!TY)w8KP|vW0rQrDPA&~= z;{ad2Dt)*bc7$ZRdQjHdGP2Y>0>C#NcGB7h&*!@{(a@4z0{#{6?J5JMYAY%#==iO_ z_-s{=@?m;^!0eBCZZ2_e-?pzopMuH2us><`*Tz6 zeUCYeyNutt{v@E3@t*h6Wf2t+fppx{Fr-B-7xcdXh{sN9X1F2FFZiee{M``{6>%J$ z>q@sdIy|t;)dq(GKst26@T(IdQ!Xf*1n3XNxWvT`z@Emlqa8ElJl zp6Rp08b7z_ni+P<*ILeN? z?K;zliQ&(_{$S)~y*HJ5{TuqBvm2Rx^@1f1Uxxj)olvY*OjiYa1;mIAfuw+ZL%{F( z;mR_%r6G^b3WSCMw`nsA3k32)oIN7A4fA$)cQ5{^X-g1I6s|c$ya$lJv%ew~sH^4F z5$ZNuV@_q$|FOWy;5S;Jb!Yd$%$r#B3g%oIYJ3&mnpiK*kn(yfV^OU7@|MLfl3Z!& zz||!jE%6CnC`#_8#=i&fy%A4YdmS9aAEf8>WR4!$RFADT6$n&2b~zBAe&8v9K)J7! zBlcAD>{7;74}*hEd^FlWUO!(y)6q?zCnH%7f9>2C4gCCQzicr-=21l>2fYDzUJjl% zW?c;Hc83wpU&+&}dDl*e?an3-6qrKi79sa$+)H|Yc-7jW8W@9Iew!Y?sN~hJ6Gt&$ zzrOsT6Zod4^__1p#=byn19!BCLp&ya?+U;NvG~hp4aFzxe`|uru;qtvi)7W@ym3^4hF$B6mRH*2>OFGou9JrJ%Rj#pA%ep@!6ACk(Xv+6H=GEij0=~KKa}319oa5FYULw zI-x^w@buHD(}#=2YY;=pIfKrge5R4DZeLA|=@_N3?5l!cU^Q>MXfn7=UpWNOtadJ3jZT75EA&Eg9bSaLC&e0h z3vb_P@y}o%U^l~;)phNc+LY5(vFo`dyZu)d!+Qh@jjQv(LX(BFW{e+oi1{Ij+KzX| z-hNBbf!vDGsqBE0M(K}X6GA7QJ2;s=hV6UqxsUq;ZhVgjv7x!zjyb9L`JS-?U8uRd z{)!U4Q_x(nq4`endo9neO1%JSyn2Un`0NS91Had{!?4fZA|S+K*G>#=`zp=2^zu`l z084O~z&2abYtRLBn?*hvg2l5XH8@i)$@OsKau;f)Kvt+6GWlRh5Ee7I?-Z zurvb#q9_01li0Wxle7KPta^H3SdMDVSj8qIyI{e+?c~Tvv+TA;=2FvzDnrywl6g(sZg{-Ut`+Oen^<)bP>V%{ za!fG#Ei?7%&k*H!kdy7N+{L}L*_@@5Xz!l}x$Qz}(u1c&vGH~6)s?$`0+W{rak{b@ zwrb_Fy<{Dt5Zj0STS{QddY*2XvUHK)zEhvob}|HBl!1Cl9)%yv52@dXmlz;M(E&S# zb$f6Cyvok$*=|295F4!U>Vu3RR~pl;)mq{9x$Uq^P}rfkvx8yhC;q19G2d~A`z0ot z-!Lu8=*nA$k?<*`V1W8K6i|CUD4r2FT0~(0nw?A**`UXrCyk9X8GSFC74;*wBZTi1 z%xVeZ-cK_@;amJEgtB&SF=@j$a;s})gZy7EBFf&tlvde3cTJ8XJFhDcbC`(V3qrfJ zF8a&!&o;e7uk6Rub!P_3q?DP3o&U=U_lRh)@|HIrX7?1B${v7OJwh}fvloY7P6Wb;>X5EE zzKz?WqI!rEvEktw?bPHXvNl;D{Pf?p-%`ES7e zi#+_E;My%5t~eN-R{vEK)-TEYz*yWRQ{E9a+qs}R?29&cwA%v>DV96Ml(M(2z4Tw3 zy!aN~A@Z}=47NDxA%zhia><$o9;pbgEB8!MF$fXl88xEh#o(GnXyEl@a;(ydrxrx)dB zG?}DwhP!;r8t1MhrohvY+d%N~#k~tR;K&FSW_x5cJ^2bdM^wKTJ?eTtRcLfUW9IEG zB%av4T8T3C={VTRyuHiL8YBkzP~y}HRI+quXXlrQ2xMShcW){zUfTN%iq!{oKAZz? zzfv6w+(vG~%b^Qg3d!I)8N$U(X`<#M7w&V=hOTxdoWSHzkjGHCl+^Fw#!qHJWPdSnFKlCs(PDlLmjh>Q zqj-OgGjG_JbGE#h_qIC=Q;z#|(g4BvYU`2uIAgfi)1ud4nj zN1jbc*&(=iwVD)I!rd48dn`wEG%s9Vgc%zHXvw?Uknm{sd^j`XcNKmWbvGb{0rMva z`nGFVn#8lmAe~7q`M`%n6`f#sFP5v_Ja(-raIUylo>Is=`9fMrwGPwI0)5!;59YyC)@WoqqFk_vP>d+t%AE zZGX~+y%xV+oA2S$sp}fFUdvZ3^ygo!uXH=&3GSt3vR3~uoC`o|SY%3bllZVLC< z%tu%$c!E?c{qXiWx>ouw(<3j_vbDkN=3LC^Cp_WyruAy66cg2X@k*mgJ0TJM zv2P;;(KFkX^H{Xl-jrK4)+?AHeRi_ADDkPGT~lw%lOlfSHAy)6OO3r8Q$46Mly2S= zo!kI&8Gdwr|GM&o4|UwH$7Yaci|XZ7$n0vHq~H5<^e|QR6Hu?lkESi=N~k?`y}S(^!|itWIFOZ0Ts)VaR7lrO-TV0Y zWu#Vul@j*T2tHMk@I`;z0CiuqyZM?A07wn_dA22%y06AoN6=gp?YAH(UtBMpJ>aJ} z6NoeE@Wo0DK9oY%iIi~JAHU+4yidp>`DP6TSOS&X(KB?RqKNiJgCcUhubaFlJa6I3 z<&SjYCJOiqsUjiX9VJpN-&ge(srPunc=eoDQFU$V%CciBRB|tS+|iRs2J_)`Ha^C! z{~4`cg^xsiZI(Rj&9xARnNAwd2ymhNZFaK`keflEh1s^Vk>Gqb za53ak?hIR;v6D3XZeGDI_TOh7}Aw!aynh^;lB7;Pe&BBl%}uHv-k*HuJRQPu-r{G#3$K|haFXXVEFHX52=kv!tuF} zw3@S8?+8b$5HT%q19^Lm7Pmyd9NN5^Omf^b{gFy@ZWC(s$AiOuLvwbZJD$Fe-9Z1sbp-@)B#-{JqD-`6?wu^r^x=8b zg&X)*@x(p5bfj7#{d5@CODl=8fjG5!w00*fD-xt^crW(zm&;KW*f&aZRaeuo(@g+;#mVa)7*2lphUmH%T8E zobg`mV=h=c$#x;{03r7GjrCK|21fnFo;FvS>eHX2*7i;c8-1#GHQS4JoWqV<%Oe8M zR2UNJ&oNM@`}8^2=L#W%ZBY9p%i@1>pw)xZpi1jW#GOCTb6E`10!A_PMoKSSCmvtX zYX!N(*Yv7^KHo@)+0l+fN$oQ)#9^c7#z0f$zl+5aj@v!NW0*(Ml8b}C>VMZ!{@;q#;f(|ZOy!HkQxpw^a3)M z`Gl*YzMBZgoWK;4rYu3m+^$5IsOSRzMyT}9Jp#|T^}OFlEZom|Cdd?V7VY$HiD6Ko zEO@Tx1+Dtm2?whZbMI=^1l!*tR=xe(zwXAxMCDMlwJ7^^loqYA{~1@h}kL_&u3+2S#R1v$Ur$Ly?aGjYd9Pt_Cw zmV_zFItC78i2=BS#KNvBK~W8rY^oln4hwo`V&|9dbiKSyPpIisb(cHpATCyBQ^ju3 zrK=A3raasWRi(K07G>{W$YSyY@YWL zjY&=zVCS&VJT%C(In$9HliLLOs=k0l#mC$FM>~g|#5eo}_8%#-K+Ey+#-sirx}&LS zQPNtH#HxnsC0r=qJ+bddWsDlCvunCq2Az0_d=BiPwZpDLJv}=8x<*Fn{8M>(MAVOH zh~idChAZ7|cGjkZ2{}b)TH#6Q;XK06Q7dl4iY|ZN*}+#vTH9zVu9f63K9pi7_b0mY zd6~Rom->C4fwWP@h0NO&u3zxKg8Hu(l;!IQR-t!S>`n2ml*2p0CFteNkom!DZEx@u zGZmQ9gnRpYs+8#)GtwfLn6ISKw=Fnz5^DNlF|jP+YzOE>*pQk4gB7klQSw~OSo(m5 zGIRcm(f)=r@=zq#KMl1yjOB2k{1URWa(i3tb2J>y7U#I_WMY2Z4TG-KtJ}qalVMkI4EVeMt1LbEUlfpK8xO!!GJ&Dn-eMzCP+J!hVBwwKzRZ{^z8Le~kC8Hc^HR8t zuEB@3fb3{5&SsjdPm`8J`9SsO>qyFa2`eZ46(BYnI4;e-L<(!#hP>i>3)~Z&>v_UK!yZC>{74O z0k|CSI%GIFBFF7eKKw|EGJ5nbfYC2m^l~R$SZ=S_j7y~0@2sP}>n#ME_CxbX1H%H% zi)c2%DjMc1dB3|a$Kl0P7{^(v48kzE1D=nz4xFngnVfL}i_*NfE;Ebb-elS>4U=L8 zdMbu4*l;~*Z+@mT(87X(qjnYx#TlK6Yh_Tvu9I_(?nFBj*x1$IT)V^yvF>R$`YC~g zY0uNoVavg`mD9+UHoZ4s^;8A|6=W*VyVdfm!C?)D>OgxH)=W{D2(XF&D|VL(weHY` z#3xD*QeKHS1^94yy-nD=P+XH+U*Z=_yUZ9DOnmPiY)bR!FQU@}8&$ zpJyzLAe(Zy4-;|e9+ow}sctk3>s~=m7@A`bcM0@9qc4}BMF?h(4t1A6h`*T^uXx!E z!6s397BJj&5NZKY*H214+_`yO5WEET(XKm83ZA~n4Psll@kiE`S=NCGv-Fm*q+AH} z*$O9*n6{dB^$ymSvo}WO86bGLW4by~w!3Y)lY2zIhy(C|Tl_o`b+5hR0!n$m_N8_5R zr6?y@>YgIZ^Iw4)%~1CBI|FWyeRcAOzf>4;v5@>Nvt!DWfr#{1^QFaw=Mh}` zSB?hoIpEYeT{D+?{;4K!?Izw7>MeM z_ov*TpOTKZL6H7G64Z(3u0%=zYoe>zR4{U)3(3V+rL}}o~AOBxFGS&xLK4USlzl$HGuzmwQZfv;o4U3)APpH5Zna& zT+-7p5=mQ8+uYf3^uRY`9j5OctioJMFC$qhwPUE2FIcqylCS$4@!`*eO+8rVmt@=@ zfOn@O{xhF<)nQ^yyZHE~9yfPu&!ll&H$PAF+h(JPk956MXO=@477_LmH6(?){~s75 z&H;R?sjojQSBHZ=2MJWi8!GV(cGa|B<~9RYQZh1rbw>l9fDlyPt3PR5kNYKft;wnO z!bsYZJ>&NCz(NFOWx1B~aYbJwK&BVd@VvNd&xUdv`{}0m;Mer;af7pw7OrAbuE$u_ z(c@j5oby#3tk<4F)g(J{uT|*$z!_kKbg*3qZRO^Bgu)lYPHxyAQmy@;Aq7>o3MZuV zC49U>wQ+#|0tSeKUtJ&vog+L$o)0QeE3g>V<4Y;(Ia}9?08YYe`I!tT(x1OE?ok&2 zkty=L5q*yen3sn+G_6(UiD~PjWLFbPKSVv)Zrel;&9HE=* zKU|F2-+3tp=JG1Qd}&(4`OE*(bPCkOmCxW6as>yTnQ5Sg?4up{E^qyZMG&yc#!$u6 zm%`Nvq5Y#Jw*Vsc4B&9-B4lsiBO>&d&t`8js8ml(jwWLmax?Jtv=Lbuzhm35jU27Z z4nuVBbU4wAky6CT_T390BZ41^=ZPc^Z<+_tVm$T%9zQ|kWDT?r9yDj>g+ywCGEE$K%>+4&AsXLPW+~;iof-M<3LP#ab=Y>=oLt27r%-@cHff{bISbuqrCG3;zdm0A+G@@s!^ zO`dNj+}CE}l_^scGn=M?{&FW#W$c?ly9#_>F?sID>v~9W)L@Hr=$AQe_u7>apq2Cw zbT4^5(*<@6LJ$4C&7Iq~p8%A)A*T=JRj7ndR4SdIfakxNbLA}nV9vGd&1p#o*7W=I z^-l4v_OZnf+jV7c@ukdZzl2LDxu0Fz5lhWaMBBHLh#7TSbu8UlU2iLARd+@I9VW^L zmDp(YmcE}6(is~aO;7(_K7Gbj?!Qg|KsavW)F^^9GFIas=vw~QIVf#q87YAEP{R&9 zdbgLOfjpGjIql)0r+Sb^Kw66DWo=0Lh(g5|nz)CsuRmpqNIR;y+w}$3hUB_T8r!Xz zUnIf5_5W8~|M@}DaBHAJTukW}Ca((;eB@15jdRF#>K=_OcQS;G@u|RbKm6eS`N25o z%7w4#d5WF@^Pd+9?_Wqge29#C1v`g$<%v?;29YbIAoHJ}XVfW~`A^sRQ5T{E{Cf4e z=p)R?eYMl244qPt_@0-T>%*c)RgiTUpTH+s{mhi!;7EM1x>b{xb{Pg~iLeXxEZKdq zW6#W5pWEeB(OvF7IMTtGbu~0uyLu-(ODn|1e=Yk-7QRz!ckJHQ`H#)ntjJI?-$>7#&PAb-O7E2SZahASt%_yT2XEDlCF^!_KUQ{3xxAqT z^=v1}qFAZST_>osUYN!ouIy+qa%8&MF_*0J3K6mWv;OU)3uWz zehryp3nu!LEo(RAu3Tw#Z|Se`u8c%vfGZ2)dU~`#NJI*P=8j=N}`PIro*Y zkQAOPi=x_qZ)k9YJR*8>=@3L%6zHDBK*u#D~zQd{>y?J=N z^{c3IsLS7sy-BLKaScevJ%O{JCqcJH!b9rpPmo z`7;4Obr8O$5nyh>tE}0o|BcbVS+uYLs>6ZL&QGDX6uakZqt5M8dlQBFpB6w}7jqVl zc23NrV}X?W29-w{HSGe2{k!RwNpK?XQ!hVzT?-?A>3o13h5wZex_&=KyPcGB5u}oW zJL{`lKLLjqM^c$uKx+-Q3*kN@HPhNfoL3dk z5;`?top$tUAJZuiZ-{a>7UNQn9{X@0Wzi8m%yKWn+n@lcn)(xR9}HSs6may)DYs^Z%gh z6yJHPBk)^;AJQ&f&CT9pyb)PhJ;s(*b#kPaQTzJZu5s3cz@sXrsQ5&c;fo46U?>)= zsQ3Jvg#mWWE@@~AeHw0YI#AjS_{`Fljg7qSN@Ze z>e^^%_O`lDFj`-v&LhaW*sYbU%>(q(ot;%`;2gQsBT+ND z97ZQL_Aa}NZNo9$}PMH}lV#r8V4QZ&=E{@Gp26bn^4aBPa=|EL2$4 z^StvS0fh0x!A3ya6G`eO!dN(WTU_5j^}vsi_Z=5XJI*0_-_qqSg*mF$tzUG@7@@>1 zpeNMdh;Z;tHj=$ET{Lcf8u%wa@8tYB=CP0xvZm~ot@)<*QnYRLE&4yOi2o+MjJ!Y& zR$I}FG@(&Zb8oDp-3zbYBQb&j^X+kzwLF{32dgs&|FFHkvcm(?gkTAnRX3_VLwHs- z-u>OsRKuKh4tVJKR>QNJeM$nJ>OI|rsnq@fmyQxw)rkeVus@2<>1TQXPvt4nixeg9 z2Fyk>0smw{P2Q62VrKThqxY zJiOI@DJLsy%?Tn7Ia4yp-|qXB(~4JqTfKsRpUlPBVZdFsA}0HZQ;o{7?@47sjq(gp zar2?;t1(CscK6oA6buGm{{7k@fqUd@P+T{)W3p%*nzFu^GF!?sm)33h$jr8SS7J51 z4LxlGEUu*FJ73<=WY=Y(VKXWb;vyb46xyTNNX*UAo?9K3In-S@V0%_O5U+3rJAVXp zcRLyC2RjeblCc$-J3a5J!sh?t8=Jr${L>M4ALdcfqP$FZ%T2*bm#smYDF^bI861wQ zMWZ?rx8=h)UX2Brj^q=^r*h}+YnPV-ZEKJ>ISDf|Iv1cj7_6{B67(|5nvpBG0{u9e zsXC=B$+n6SO3-+BgM>?Q!^v?7m}l$3+AQ?!&+{1TXP*?V{6DU~1D?wM{r^TKEhIaX zib5ze`%#e!4Wi7b$QB~&oTg1BDKZM#WbaW{Qbw|8WbeHW=YM_9(er(N|NHfNo~NgC z&V7IG&$!0>dSBO7eS)ncL+`ZKueX8Jqp3CNVr!v#&$_2F#ko>zU;zqLR@JG!bh;r# zcBJXqptsL<^W}Bxx;hP`SE?c<-SIyYq^_Fn-ZpfLXYApe^QeDXS5`)(Mw>^CrVg>c zr;)|wjdN^ef^q2f>&X_)BoXuOT~puckP>yyc_>l&L$~lM`<{L5oLuaj?6*wGiu1|XF&}L0I5KJHynM^e;278(FF8DliYGs%Yy>95oSFKTE7N^yv-t50 zf8qRj*GsB%YD}2FukSo*2ZW!e;=pqiz$~EXEhgl>ofaw8kXDJ9vn?HEiuOyVWJT|q zhBQw~e@r6m4bs?HHe4ubI>nc~C%kmDxp1$Zr19G;{o^;@Y4$ejruk8pf@h!OtJV_q zSb8)xiBi?g`f)+bsvqr?%+=eP4y!de1(^eeUhz1C%BAx!=Oap5)}<>Gams3sNqd3C z_yCdLBM{GmEwe+s-%)EQS4`QybtDxeNq3{1oT5m|snaFSZdtAiC&nT8<51N)xr64z zX^)aN{m4FaADj_GP>`~evd92(m3r>>UhejeKM z%%434hu{?-6@{UTwkI_LI)x3c_!hPGP6N{MQ_niJ2^61P!uK_ZO_`d9uTke$w5t~$ zX%*+w)!H)|cW6M&*=$2Rr)4@T(IfiqrC8#-dKsyxuy<;)-rvkMrj}=_3G=DhV_i+u zy5VcjUWAE7U(jhZBRL*hB#bEx=fL~RIZ$bl^U#W?Wwobt80Fz7s?Bd zx9e#9URc;!W0rZR=ko5c_SFdW=3l4gXMc7%PbPBc>q&^!ro;+O@%p@=9fq~mFFhW0 z;Q5<3tro2k@;x~5uPNGTeNQBQ05}Bs@UxfC!t3tQlEyqdv>%V2Q2;?C1&T#heq`6e zx%OmMAIH`Fcle*VRMYC~vq^$C-s(lCc8#ALzwlT(r-31O@$PI$h0$fB%;akGI^70? ztOYf<%t=F^AqNVoLRUvgP>#aOq-WwRfuO{283mEwlV@HWRC_wj0z0=vG~485 zaiP#ZJyt^X&4pJc`1!0Q-;6Zw&Wq)=c!V=y&RWGjfjRPPN!)25!o)aumuYI1;AHah zSDVz7ogmbA0Ie_*;`2}!%xrt>4FRT8VQSEm@=I0FdKDDn3W|v6xun&9zy?y*Y5A$J z1Hu|DQo8xwOm`Mg#u(Opn|5czI>X6VEXIvdT-J*YrzoO+9OKk~_DoyMd{#krv6{*4 z)8c%Wt%t+i#E#17v0_|`)?J6Nx3}45*DkCL0|8XWzSpnGtRW&*?sRZigFdpaUw7`+ zYzbTLZs)wCdFOnR6?<3;7{ih)tnft4kna$MAu#sv#AEUIrZ!BgOx<&-u->}yn+M^L zX#)R6{K5L~oi29?a~CuQKbyofGEZKzvJG;#1A~-}!`U^uPzjtJ`)SkLfdGdd{01b` z;3r3)KHE~M|Jl*~>x|Q~qsG#iBNgrYSUEp@f2AGvf+@9_qfaKE2b@OM?HKh#U*BB_ zhIskwuwjAAk`=US<3DnwB6#2~v{~g{Z}0v5xJVn~j1S|#RqQDRNQD!{>q?;pk?GLb zUdm@p+@N;k2gELCUs46zaGK_qT*lS6PuGO0YkgR@`2Kr!P9!{&2O) zJkd3uVr7kZO6!>I{opFUiMP>dvVj^?HhfFkF{5m53nI?hsSxDwK~f)&N>0LfZFt`WTtGVgu*gXzr}ni zxZ%x!kXkcR7Iy6he*x$qnzos9k_F;N+l6dZF(|x2Up(mL6bOh}I2F6VrER)l^3& zFInVPBgSGXK-w;D>!E4q)qQ6jj`4zOO3|OO@#tziCXm=%G?mmCoyRW*c0ABi&Lu8# zHYF4(%W`h`?VxRdfU#^oC<8n%K;M+8)&28>r`ag8{kXQEKAqNuGtbmVfw%Lkj8@+D z%UIP|;dpwDE7Tf^Xp3?ZsOkG{E`fq0lhETy$%rpDx z==+^65R|_2Lp!r^Kb7g}d|QuH)LvFSgwc0X<4dCbjF@{SdoRV& zsc^IDq?94tzyU~kagUAuwt!7D9I{N{b995Wn`r|eqVUO-Cxke+gg86hc%WKzZCvmd zC?0)-wYII-+ifCS$Hvb86a#m{=S7%XIxw;E*Flzeg<9pSsLRYefzGMylsT`7;oLe` zu6#&L$v^MIEOZTeziN#>fN0MAV5qe?4N*MB9Gd>IoiKW$WroV0<*{M@h#`XAh|m2h z{3G{HWD0xtbpxx~mh8g49D<2f%d07mPL|oJ0}C6daw$OaZfSQ@*1Vx-qEyW(VQHj} zkWQ_~>7dZm^}4lMif64gTUc?Qx_C}rgaE*$wcPFCd;o{|Oxd~sX`kNM>7z?b8bj1m z_t?0k%9t_g=nDStHzsGObw0WFp}T_54BNfdfn?x)l* zxStHTUJMjJQsj`nKd;TP$Ky04FXTW=YnN{ljkL1!&#OpyXSGnuPbFscstk{YBM<`2 zv_eFDpr)uhxz$P(%#S~scs5uVhf7$!@7Xveu^WPB8lWBc%-v-?V+!*jdeD^MNMLbV zH=OwAc&GE%dgnWyaEMe*92Qi9J7JTUK?GcMp=dW>ip2wJAHWYU5&doRBdrsz^o?^S zLA)O>qTwyBlRy(H#X+w4kB;Ywz)Z{+6>R3@i(k!bf%seL-0~5(OhA}|!vmemE?l^u zctJ6mXSYgVlbQa}<`Mf*paUTPmG9_6_gd)mr9>pM-#2qbcql*fK-+Y}$YKiw@)Q#P z0R&wJG9Xr~B!I;7B}41pWPt`Exce>f01AZ|dh$JCB*-i-WECT?9N z0@$^I3v3>^0LY7W1{L3RgBJRjd@6}kyxOCeIvcXuXh2{n-t`cMxO~MaP7{}B^?cIV z+|sAugzhgPO*ld=mxP-DYF$yG5)~9tAxhvvXT1~EoF^dg@8Fq}7?*@3OhR0|`SK0R zqOk(!#&)IQ1|R1FnOcjP7r$30$}esb4e&iDUlL;gm|OM;Xyy>!w-My;2o@lg+!V*@ zwR&e%d;LKJB#y0rTI7nKc2L>fJRuKVi>}AEShIb6&g6PD83N0p{7ZLl-+ys`KcD8= zC|MunZ{{-BM^)VJ*MYgCt&TegjvargUi1MwAl#ZmK^o_gnBb5nHUS>@0!p&Yn)px^ zk{2&t(<{9I3bX|wi zU}{A!YwmV{K5R_>4v=8oK|GJ(6$P6M{#j#P9ZI8R4%8@r#IlCJ;r+`|o)&wsKIA5h z9R?!(*?Oegk{1M+e30`TJg=?^bhPZD;Dq$c%$?CJp(n2x?K78m$nj96_FkxIaldr4 zZGqc9(!MSL^_3umEx!X3n5(4K%83BkNmOwBT6p+$i7wX- zRIc3BO!nr-jc?m;xw8pGW!K^$8{^7>GizNbitFZ@{wW;YBd=PLyHW7gylBt<sM2Q3Ve12@FH3MC=BdjL^_9m=G#L+G*9#& z`Xwj#rGD9+qd)V{XItm7p0!M%+5s_6Vr1`rF8Yu9@oC^vhw;#kl~bvs;YN1{gKH@#P?DGr>@&unTbVNC?~NIkGeUfGow9PAJh9|}8( z6#|g{0x_S@%UDQ~VS>NgXYk})O55MWiy)b3_@34eWl`!(`(^8O7_4Xl6M-P|3c7%c$WuPX(F_ z&@9^&LwnShJC-C?^`OTz33djXsWj1a>)vQ6EShQfnNkn8zQDVCUEIBBCN*$n#No$Q zA9e#5g1KX-tq1h#<~U881u{v=<9uQlTOExPX$sN5Ha?%D?!C(KXAd^*Pbm@6;b_5d z6S3YRvplmrMkI!oehn@8&wg`u*b_VJuNgL-4_ht7O?keo`;dNonI@#jkf`synvk)k z?c|i(4SWo!+j9Yq72x>1yQjoA9Qa}jHkLaf@(Hz0QKcIo9GphTIPbM4pz zktg5%gbm%y?j%s;=2l&Yz}R=gO43P{3jZ+18^$x_qTD%I%h)Dx>Qte0qUv-_dsZ$ zA~C<&iMrP$WjK~D@nP8EzeB@>^)Arfw)RCb;91%4U()j9EphVhQR$;nr|rtmJ{ft- zzxo!XcbQr`A3n=}ta30Yi^)nh`bC{Wl7GX_qvrqY4N#& z0dlM7R#sLZk11z|oY?VB8=(PM=Tb+HELrc7Ye78L~s41gT z#uU8;&_5IynW`xu$u}=0)>AoIc||aaI+x)nRm1@->%VF=;q3ks%L)h(CPBDt09FFT z`9b2^jXlA{o4^gvZIK{5(;4IcB zXtXpH$P9+*D4E{MfvgL%U`6AON`e5jG=iO5+;SK3I=>B65Y4-yl|-VzGVjw~{EA`; zC?ljLX89tdaYp6yj{f#>K9+15O^Sj|(@>U5Cdb7cMT7|{C@AZOTBbiAb9}L7A^kN+|kSyNb5+Tou>6g zX`2vnco_`@K_IceYBKA6EP|As(SifIuZ^lhvN?qz#40`hd$5r0vtez0GjEYm6JW9e zmQWNl!5gA8#Uv}N5yECpEa3l*t#&Cv%riVUJvY9SNgMb}=@1IP8j z(Q7(&&>Qiw@g#eS&IY)fdiioPuS5*~z7|G!0ZA?BwF;Vt_S?Dmmzz?Sg3x+%R42|| z`oz_eus87#BVY__5_SE-X{A|U8Y)0sw>iZv`_EL0TyNr)-9Ec$8~TIiXGjOf-HRky z@!&sYQ3+ER{`(l*t!S!GfdB(LHU0i+mNPW`j*b)^JJ5QzO_A}o^n)#bz#)AKGv~Oa zc1TGFjGEO4I0toaV4lED+`U90@S=c^-%Kb$_pRq+F~yRw_Nv`jvf|CRE)>0>mYsR3 zP_!G!>X4;2wlO2?s;A`h#N&p8)t#5c`M69J{BIe6UoWG4OF$ytfZz^J$$9$B2^CD( zymHIVQ5#Yt(>ZZRjaerf?lMv1`Yu8t2q57;NTAI+UZN3U{e2EtF&hl?VbZrhSsauX zKY5p(BgJas10$279i)fj8xJBqN@u7$iS4gc1p%>n;cgwKRoY+%BH7$$BLJrGzh_vh z8xZ4#2O7U%HfDgeX7JMfT5-E#KP5fpdZXs+{1$}KfC6^C0b@`&Kw>k|877$P?ZP}z z2JPlGtqgja$;bS?J}-?SHtmg=bC9dU&M6O>hj(;EF1`3|(Fo7z2296(1i!cn#f2fJ z@ip@Sgg#KnwflNdRE+c<#HjP;HxJcq6s-K%9iN8C{lR-og?wHFroyA@@zNLIKNKH9 z7{`oRz9(Z#n`4+vzafy|c<>j=IpbXFs#Qce+P`N=p53mAXgdCfpjCRMWnUUy+>P}> zL`d;;Qpm{<86SOzE!qp=E|RCv9z?gV&Dv8+j+>EhKCP3YRJI=l(gGm-i{hwd{nj!W zJ}K;K2VfGGyYZQlje{s7MNgtI@a`NOv&h>dZt#{jY|K=p;-njs@8w=&mUhnUL0s^% z5a!hE{|L&NXt8oe&@oz(DSCcWK>|8)O#>ef`N6(K1B6__j{;0u0iOU0z!z-C`lBJO z-M+V!f^pxzxZGUrrlzKZ`1lu%KD^c4Q2th52lA*Cevkf;{LfQ2YMRy?(F@d(V*mXN z#uhx#?f~lzhkyb2UX7tWQzD`pU)+y58!A4_=dBQ=}@bmVvwQW70Uoc}*rQjjFbgRdr1;!PM|T`LfiJJL+%%1^rd>C}m?9!0{>!YPSJ3hzqS%+pLg25+x&PAogWr3KR@UX3 zA_hfnpHI?jr{ZU;OTNPVJE#zGddK%p{#?7``=vFT*_Ezc>S8aLzu z-v66VhMwA+syl&QgkvO=nDosFb2=9+?w#fF7MTS2wLb1I^W`ya^EDayray|K+QSVJ zWzUfl}lG!xuM%? zd)$jZMYZqVu9RDCW&TUSlGl0VnNzrIcipj^PT0zF@bKj61J5OssqDE#LZV!VrDmcp z>72veo%3B*7ZN@Qs4guv#3t%q(OjCFtn=zx-~=~g%a+pPcls;+(p*<&oxl_Qpeq>Q zX=&ND6<@iS#U;;*Bi1nQjmSV06u2U7k91+zP&xrh{{I!AQx_7 zO3=40RxRoC8T92$J_?(iZCU18x{h5AY0#7X>%hIB^LwsGw-@D|#w8EI+Ce7VXD5huU)aX%+3%kTX*~?@L9pbB&pe%WgAC7i| z@MWivFI4yx5X>L`APF_&jeka~oVfYr$?(WX8V3ue)Rv*MRG#fd6<-%%E_6#077tz5 zzws9CK26+tNoQ@(E?#H%I>`tq(hpByhbPQ1<7SwH47k{coNOEZ>=J@vdnl(61mPG?&a%^^!T<>)fiRVnc-I*e_Li=oYAI3j)#ePC85t$y4PN^9B< zg*kH0JiIIzoLF93R8%xmH035#E4Mc8?7JP?U*^9)l0#HFb20Q+P{U#LLkzohd}W*A zR$+x?nS$Hukvj}McnQwnJhe%FO_}f;i0^xgc=uCGtk#Hy0Ug8TCZ{^RD+FK{7P# zY_^%&t2=Xnj;uu3s8=n85=1^+>%+=@2AHX#+v5?c-inNmN?OVX%kH8P z-cm(s?%osJ7uaLKkSJlL?$Eu>5PfQP#9)ddt_adHRy`v)IycsWaVxOy*_H8 zhsmr(%yjR{t#xatn25bS8eB6oQ4pTID%B;93>ECsA=rHNU0rU!B7k;U9VJ79Jy(Lo z3Y&P!ri%7I*agkAdAGKH+F*`!X4mgv=h~=Ea9WND)70Y)_K{qR4)^_tzK4I|x}dxB zjp*GgsCTAkgrkE)(@i$)KzuYizFpGBXXHwADF4{tQn{$d1-=;RrLNIXyJ8tyhhm^f3f6l;q%l;f@EA z*CKjeS3AfRPS5AAl+Eq6wgp29!yj%RmBq3gC$d^9b8Y*L3=I!(bKlF;eN{7{on@vu z-k!yeN}3MQP~eTz{*G(>JX=5ztWmsd#shWDp*k5`SHgmIo!?WDkGDigb&?9j*zr0F z>gwvQ(~r4)?>+d#t58-}W?RMK`0Fko*6RefFK5SB{VUK!XK8|!Io*lWSe3OS(NJ@! zgh(CiO>#b1#E{Gx5W=l^TKgV{O|g)QlRY1EB@EWGTa9Qqi;I>1SJ1H0Fk^7jOHcLO z;4Ffi_7qVcueCvOGE7pO!p7%~h>05EH`m6^0Ubly%F;TSxr?q)wIzAT6e~S(xN8H> z(viPXi*4n})=#@jv5|>M_VaFwj)Jm>%2d#udM9Y`I$tG9R(`yZb8{Y8%F`A6HgHcD zppBVQD%xMRC$Zk-=pA_JzkBHicd#&)4Qo)8$&ODgnEtigI$&}~h9qqFhhn);FNTO7 z+gLClid6=18LV6v4E6!KV3qa8pmpU{by>}-5e$i|a~l(7{aZ`X2+;nFNFw^ZgyF?c zOsaEY#Lqz@{i!$?t3Dw>iC|&PV2s}ZPS`I`_)Qy?k&!W*p)1G?1yOy@`Y=^26)zP@ zsZnG5Q>-IjEnhS#Ac;3PrPmMtsD`B-0VU`<^8MIM?3A>8rDJB3DL1;SlQ}GgJ=!c` zj@_(Ku*!EfRh|)EKFzwPc==bX9Ak^VizO63{ZM?G5~HVYkdS=0d@=a%&F}tUuzHmV z6A||N%BjV9+9OgKz26zkL`gGIC=2TY?Imnw2-9V@0D<~@;%f%(5ynmAeV_x4)ZmX$ zX57XQjuWgu$MKGw)LI5A1@rTanB(@poBixhOq;m#d2RQT8S69U(J6~;7tw*os$!G7 zscbAjv4|D9Pky3(u}7(to*qiuXv=IY_XkC&hs&H&ll=YU&B@#6eSwzz(T;;40zAwg z#Qm7*EjOxac|437-3c%YfaS?;&nUXYK`fo4!NUPpi=6u73; z#Jp}OrCBr1aa!`*B%4rRO6`Gt?4Ex&&yPcQF#+P%b0&`7SSwi-jjCXshn4K8Y>J4k z4^Lo)zrC~^D-1U5_4@4eI4BKC1I6EYF)vO7&;I#fyh+ci?&A19vSgO0?BzM=y%pa) zyF6AlBjMN;ybOEoM9Oi4$6n-jjC%^g^}?zF{>&ont_oFo7x9hBZa=TOc9Ka$e%m4m zxLcITlwmp1)#$*p3)OY^vzT3N!S97jfk9=p!QbT^=HF9#>6rUa0d0Ad(9}f-cg5KM zymhW)(U=}LCuVx0LUpB8?D?dHmdnA8o10@m0)C+ctC|`t2v_AGF8Z4LWGl+`lZM#4 zOoM0dgjNZfQ;-FJIs2yiYQ}$F{H6MG(e#n6!lkxt^1}Oi^zsfataxRU%`TJT@I6@M z=fX^h-+G)L!~gD-_&w)|EC=34aNaXugtn&<$fHoZzMfQXK9ZJ^L)*z$fyAM%dtn3%l zC~`AY|Jve7_f)8Q_eJnhWPT`Gucqv!>F-oSQ>kD))7yP1gztb#U5?chs_eB%FFD~tRz0FDQ`%zhJ5x(m zvvdWuikmd)c45Y4h6%{RB|R2@CrCY)GWQm2HXSy>p#H01ph6@rWO@9FTFzA@JL|Oz zjhmi;g#U9d@BDVx;kp3EEp<@y>kOTYZC|;wFDK1aq3E=Xe z-JfAlaekklP}pd>ychp>fnRPb1xdZXYtfBLGb}R&3R{m>Ao4Bk$D)C)ZYDo@kO?vv=UZ>0an2JOi=!Ur>2po)o^ zp=8_KrYeF$MlonXFHekcf!UJDkZ+Vv9{jdLn3W=QuLu~Z39gzQs5!*_p`=89vV^#C zo{j*POZh`8YQ8$=EmR6~e{ImntixSc5^<|!z8m#V>e8Az=_6zt2#xwgWJZPvs>WLL z`nZp$=fj5&kKcjD-=b{wew;du;ld8`TJ9FDtKqfRLV@RV7)xENm$?zNDNgedqnHkhm|Dn#(ot}{FJPUI+S}Xv(rW~LkfUBq7!Xp9*YJkLzV@gW3$hQOB*C|LVL=rzeB}UIs&&k|Y>yn!l& z-@~LO;qh6pP zm-7CjN7fuK{gq{Z_IC4L7A&!ic)G@qai5R5M=)HtFcV?r!aZ|+Q=Hg$f97U@L}q{J zKvl)H-oORJg-#g!|JbBy`)V1uIh4=Y<-I#zf=!zb+$(>aI@G7kKIc_;pX|SZgLVU4 zSbA&M;%MU58+!2?{_5-f?YUzk$Kz|4$aXE7ln*?x`xv2`t+%@SY#_)9Xt@HLG3e+r z6qVddK~0-j@d-6<9k1k6nZi-=8x~RUSj9Tx> z$;si#N&lJtswzm>VuJ-^prERs-(-*cXB>1Yg*SkN|M=;4Z!31Ubs4%7}V=n;mwGwWi3vIRm##A;uE7j zs%r^r5?B5%Oy`yPlC&J$(aMG8ciT<%%=J6<7sQ-5l^zV{MLU!Qmf>FRf;L$LX=RUl zqTF;Q-q)$jS!QGPFpp*Fz0 zrs~zCzwbx1J@M^ym|dqnV2Eh$dzWC}C&|3#S(YW7@{sH9?&b{Ey{B?5ib~;hdv}=&`FaopyD8+ub4UzUiCsb?Or2-9fhWhrI+r5Fzay9U0EYu=;)X$5SV%s+aWU z{lCVpoOeP)g-q!u1>xO$*QlQvxq9f}@y%DjY^$ja*<0ec;yeC~^a!?@N!(7C#WoZE zG{~6pMJJE5Mrs-O+h)2BO`5RipgX}rB0c3*LK`MyXXZ$#cE}KU_wTC|P)Krr(C~Na zYwEHE=af}#Oa1cwg_xaqp;L2DmKQw+l|KhtqS>oQnC~sYUM;JmPx!09@! z{dsDBq|tb$uL4#N_E+7w16Ha%{h~yNaY;7kcvIWXSat7EdC?Y$JklCqz7z}v?TJ#v zzHB#2!^oIjdxDJ`Q#Q(niZ_Vgy#jQdmHt!!0R;{KP19GFMJU~fCeURfi!_0d7kvN7 z;>5&+-&+xrJBw17p}>tITbBeo1DBqanTDEL-+#Ri04+V>*$JbBn>l#Q_bzQw=Aq*G zGG&H{wa%uDz9m8F3^H7&FtHt9^&IM%%6L~8fuGF{fIUdsqCCw{?Y&F&a{xuu$`c9n zpQnIXb<*uPR{A0Z0S@c@Zq?*zEY+T^4Rq;yGBc58Of*cGE8Afhc~&OJLEUwJiqmtQ zs?4iSE#+Q^6nd>+kFi`YR4x>zE8Jz$Yoep4^YEM7(>h1@86iuj)e)xh#O-gdE*k8_ zrWbhvrs9@1?YCP=fUF{`-F3r&Q^mnO7vSH@;`hI=5Ik_sM>PSoJn>-DrWypZgd181 zPJ8w`LdDgfs`Op%(o#}JK;wqzLVG~p@bGZ-gv|WUzyC-WU8LWXaK0*25o`XrQ+X}@ z9_IQgu8Y$yN?7Fw4})&jv7AX&w~Z|kIi%h2WJ{^)tqsGMnZ(}By`%?=BPUGE zET;g3(sXN`Rrl4V6%{>7L-f=T01#+6>X>>@b4d@px@tt;qX6H_m?`YSe8WYF`|85Q z53c=#z6_d@CC_zMBqp7bg=H;!d_>(XyC90r}FBBm`7oLqTdYP&1CO`h+i6oqjr2BN~g_-ii zf~y9`4cB>BSq)0-Rfakf++|w^Wc7aPOGh0ZNRmEJoyG`B3*lt#bfc0eFJnz*T`bfgr}x($=|F ze(8P&;wK)!7qlG0)OE!~UWd8dQ@V=2ik=cc@A0e@dXze&Ab@R$WezB6$kgvoNK8rC z@)@Fvo{H};rCz4MZ;`XF9+}~7`Qe|f=v{yuRJcs}p6)Z4mb2I@EL>Sw=!PpKmUL<@ zIBfiBZ=3PZ`tjY68+|K|mcoWXD)&c@YpX;qXa2xaeHB=5j6iNu?ga1?@UX5fj$i}# z2LjjA4}zX zT^7er_07;Qw3Fo=_!c}7>huVt@})?fI7K(L*5P72H@R^!C8zh|=4m6q-unYQ&b#0V zfTBc(Gt2({Nix?|={kFQxS$Y~ZxFwh(wQ?ZE-nJvpAGr@TN{{J$Ag@`6GN-)TRl);e44|LBuA2IQQNBt=<&CG!0Fczm7YjZ(b4t5da}?#+qOuI{w;+T*DWj~5l)2elx)kpBkW?tTyhV2oa+c?9p@A04Qc&~#zz=95iX zS9Arr_gY}t@Zfv27M?3AbLU&ZMnzzLCo+=16R+}wSj;*&`MwiD0?E~JQ55&-UtPfK`S zSF|3u=W;p)JU5`QP$a|LA&a@MEI2&8Z2>(xG8~*R4RFE)^a~}Kg!K2Lv%hQ4o=Tus zYSTQzt<)G)7Q3zS)ur-m_xIG!vC=~^%$cw$S6*)JJGJkw(>w}>bq1DZTm%2#*JY80 zcn!t0O}x@$%=cxN+vB%-WAZpdwZgeSG;j52(Q^?l$qmLwzc+u1CzvDL#j8!JmDAHU zP>6wNQwKu%`Qp|L6ZL@=mB%1I13X(l-8^m4nR{YmV~Qxp&HYh5LXLa89LPSi>3@kv zAv#~SqC=!=4W3O?%Nw~o{*7_Bp(<-#8?#MaYfOjb#3{a~gO+XH2sGa<(McC`As|eGBMV&#_adtj1s5PX zN`jIA7pO2g0oe%QtXCRt;=~x$uSrsibdwL=mn`BcRaM~cOD0iJC3uI6W zuNn7t3!Tv23y-(#d1%j$4-R*^Lg=az^!nEni9E3#e<}gs+qt2-0I1ks#aul7)YH>x zJgtiFpJ_ln`WIRZxMm0do>+EdS3uLz{$;4225uEp(e;Fk2|n;pB5rN8qt!zfnJ+Kk|xLX$p#F_{j&3|L?so9U7~4M;`gsnzqG`PdpQ{Tx#WtcJ=f~cLk*MY zvB37N%(`^Ux;Fo~4vIv0d3r)xisqwUm_FpG$Vl9!a~(EDUq)B*hv&kk?Dqq<)|an( zyhJjlMNd){@!KHlcB}0@fNIEG06Hx2E%NmscG%w-v0;DaOp-x~`x!a{7%GJWZDq!W z@Dp_5uf0Op8rVG{t)yW8q`%^BvbkM(2>W>FUyshUj{!V7AP*qe1Y~9|q|g|HGxnlp zz+&z1QCZG%{UW3$6x8WRA)2~Qb=s@Wmuo0n89nI6>EdpxdNydhycZx5f9T>O48`1! zZvt5m`0`flBd@@|=nhPP>}`oT@%n}=H>J8WRv4wF&p1LeOJx~l()*%&3SWWKabkR9 zXQWq52c{cGc4F$Cwv^uLgR}Hj1b1|({8Jeo^&<3O7I{qT=@#J4(nnEN0pFr83ZHAF; z7CjPl5o<#pQLkoGg*H8XMoL4Fpm6FynHD2AwMt23SufxI?tnZQs)gs&o9&=Mq27mg z?ADA+yk)7MU5OyW_w{_>k&M1I3HLHe)An+guUyggHTVWoD_wXcL1Sw)f8Y4BBXyb-SHdkHDJc_;Nrj!P6H z0R)y^`Lmuzb$Qw93uyY#WqN8WJJ^O6;QzEXNxWGlJZR*(L#9mt#xl(^12reLve(d! zpfl_>c)77?sfUCGeY8~XY7>d6q2*T5Em z<*Fce1H3lKF4Ev+Pwrg;pn{E_5PrY?u8KYaq)C^@u|I)~rB!yc+ZALdWQF%}5v)sm z9YU8h9Kuo-6ue5&$v0ZcZE-oBjqJ3uFP zg!p<~07uU@2*C6&B{EkKxnd@3DS}HR_P&WQBYL(dHQ0E0P-pE>aE;%MY2?ucv`+Ic z|2?R2$*x~^mzJ#>L_U;V{g#5D98Epr^Nz}dwzb-Tr8+ldvQ4UBM~6uq{7edHz->!g zHO@5?Ia>hnUYPAycGp}Gn_LaJU<5xTlYdV>>@jzrE3m; z*Ljz2kt4C9T=0r61-*{YMi`z1JqP>-HywQpJFIaomm)VB+s0P^@cr*)u8Q3dxKD7S*@6=v|L!!%Y{OeGlEG`#h4_i$Lb9PlQZeCl4*j}8FBC<4J zeZttxadT4UkjZ-baSv3iH90fwG8!M-4B_<6D4L6N_ugb9cxT1{fzE)AK>-(2ogja;q# z`(UAe#Q-Mi2|w|G&HmWQrhhS^Rw!Id%xa~}M}!Q^gcyLt-h3&Df1S(4B+uWb5Uyuw zwnRSRbzb$arX+Zmg`JFPq3_lo*g>+d`HF<@qd#J7XXI{T zGP(&32QZq2-MeDtI`qF*6x7KdDZ7h4j$HW*JHns;AqTSADmVBjdzZeyWeTiv++=`> z{!gO8t0)Ryr$8%rwjEm@56tgJ7TP8)dI(+(vtP`naOxfj?8j|vd|^{1$-p0V z+YJAH+msFoARc?*D5(&oZn$?>XR(qjg39gxo%km^@y4xyX;94XKHP!$98C?^9)tEq zyYMgMhemt!umHXWo=pJ|G(DEXY$i;DzU0e6o>lZ`Q@W?F>6jBz;iIXfSDM-URFdhx zkJN<&59ghJoaD5ne1o_D{rGE48&ce(rb8PKmkA{@@0NA7Ty%DmQOUHwL?gKC?hntwJqtDy-d<|E z+*DiawDg1D*pYat4?!64d1=~zcR=(o&KTnVk$bjzT$pLYxl1Co-SmL`Zoo_-Qy$=F zu&;pb^$BB%dt4CSzSrEK^Tn#`CauFCWDb0Vbiw0|w%WwQyDJ&Yw6!Ei$rnc*Cx^KV zEnsJCeof)=xg3hzZI7`+KQT=U;)H2U?CKZNho(pVJN+yB{^|Tg2@h>q+8}6)DH)nO8mcb|L1DwkGUcF2Yhnt0p`YI;Tz-B zl#=Bw?u1*ND}M$xOynIGl9s1Rat=6GX5E${iMIdyGAsMo@rStG7k|B8UM8+Vm@w#M z`1ao2j`BrEtn}8-kIr!wjr(p!+S4{S6&l8FZcA)GSlOxft9mw!+#rNsI8w{|(-IK> zuLIm4eW$*X844_G|K~+l<|%B>l*^|$p8!W(34V09snRmOE?l_yQ2P!mEp%MTWU{EJ zoSdaNdEz&%;=NGnzU!#E$WQ2W#@Vx6DdE5T0Khe{fILW=0u5(0Dg*)`^wLYTl{-5Y ztG)vfLUjur@^ykZ+~VsZeu)Tf3NNq%b;^sDy4mwi%N^hgt^xblXm0R_!@JSlp%T{a zH7n?L=(?c-@%>Trq@HwTY}YL_@b5G-bX`CDGNh9U5I4?%_!Z9o)>ODtdIy^ul%^+L z_#0Bz?N1U?PYCONGu(@pn3w?mqU#itP!1spqZ=MrZiVRTwJxOyl4}Y-ihQjWUeDUd z>!|7A_x`3q>7HBW>O{lQjNo?<6m{LYt2a3v$^T%TMr>|nR#A0-rQap<7GmWo%`h&Y zi+pVjry3E*)F)V(adXmhQANGi&Y}^W`&IzSWaO(}K~5OwtSdeA>(`LS`C>fB*XHgG z*n4jwR2qRxljy!YaLo>V)l~C8JN^J*4I7J&gH^kyPDwNYqvB!GgbF>@Gh4u1MbpJ0 z23$qBZan_aX}YL$kSpT)YVC5hNh|G3qIHqn{ZZ?0H;!YUrJ_FKPdv-(G6pQGE@; zXSXb;9^Rs`sgopo7m+u*Z$}9}d-kmFwT_h+J5+=4oG78zyH|ZAihTCr#|r&-Yj}4f z^^qRrO7%&H1fZfHnk$w7Sa-6Z87%g&kp=%dHa5Z#dN*2{>_UM;C$OUWhUAG4#=DE8 z$xMzz*${LU(96&KXm=ueqNhY2I><1?A@YaP-O4xsk>=;iVZx1|{JAX{xXL=AC6p8} z1h`CHC!V@~7@~b`0prMu#R)geZ7Q_U2f@iSP<5DaJZF%z=JVIZdScPY$I!lyp;q7Q ziw|e)2gW$T0nWdVP_ZPM)5{S)gPL&A0l)Fbt>xf+q^Al+no|vMzdjKn{r&ylNLcF^ zE)`Ar^{giMc%QNx^zF;^`whUeKX14bcQ}xMo%+0ZjlgwHgI?;bd3Gk_op~bLsHuVO zC;~{LQG4cH+xEM$72waHctzT+>X(uLu8*$&-A6YRbv}dslSA0zO8KDEMwXjbt?IBv zY6EF2)gu^vT-&zaRKK5??l^SwUeoQ>>4?$eT_fXkukrtUF~XZ}7p9RuEI@fvo078j zmM+~3in6gs0#pp2&6SjyZZll^NB`14kBzjq(406*vF*{}n;xIeEYiKKZ)-GP-!Oc1 zJwMSd!F*(N)iotia73!duGrB;ctE4cE!@KXnxPyZXggm$xzh6U=UxQ25tggu{U6K? zTFyRDRaHF!nBp6-a}j^l4UKQ*!Qfj#gR%D>oZcRs&PRDJzM(_N?Jm}nhpB0NP(Z;SY7Lh|J~n-w+?qvg zN~l__@nmP-3CGFKT!ay!_}WgP!cSF%yv;G%^ET1&ViKX)u0N$qlWuZ}v(`_@jdA}d zrguF4nH=3XqU!#qk1fwVDJz=*H;gJSma{6D$c{@&`o0#y6*B=yxDP<6!n^}L4qecc zEDa#j@~8m0kj62lE5^pgge4r&(Rcr;lhEgsGmuxk_U?+~X$0qvr4$I>hqTz-#dh<# z>`jfJke85hagi~C31&^u`A^VU+qI;ebh#3Bp{<7K^bGTDHQXT>bUt~>b2*M6ee3IU zr|Hks{UQ-77hf>^>;hKp1KZ~7CTH#J?DSKJka$}KEDdx(YHJqeCZIHoua98<(V>Ci zT5xX!fSSDzIMurF=cGuNP3vm@mZr+iQcE6;N>60s=~g|dk^q`g^z8cEJ4%mOlyO^r zR2EEmk*Hk08t4JERCbVbR)y1FcAmKN{f*-K%;gWj4W6n1VnN7~TS#aqf~dWr0?3eC zYWN^jFZ4!x4MNb~9Gfn0q;g!!_;LZ)#9eU;mf;Uo`Z}F4b8F4lhM*xcT(5+3+W0Sz z*jvfPRW~`j9ENUVuA^5YykT3G!(L!h-fw&6S93Fy40VhNNa`6#)W~UcfUK82(&L{b zN1_9b0BQAyG9=>A$-;Q#XUq%)y{lmR_6L^`Zp#1+#hTjK+RDNkW`E^-xU96?O11jn zaL#b}vt6uv;T*VFl&mkNO=Nc{K_9aZA3kuScms+sfj}vT5~iGfetx0$MF`U~fox$X zVC$DFehyl-taM908+sH{m(3U_HLWd9NLDSkEv(|rW!_FGdosW5-EjjqIN zz@A&!m@AyC^#NwZ(6JF^K7RhFj~{tfVXmP!i$4X`wm%N?&L1UuTtyJw$1&e3wP?|s z-75FsB8tKLTV}W2NrN1dN+24MRtK8M9zoeK+POA2JzCa)HrJ0pQYc3)nvmdJYw#B6 z;sJ=pL9e`@-edp0b8x1j8|}b-XF$;q!nB9HFI0kZ$ah~HZ?gq;P>JY>x@R^$l%qPD zL5yC_aEk0JMn5)dcXfs=tOPN}v#fY+oVrNTT?6q$nQh;`LQB8k4D*THe*aTNoPTQC zOd>dT@7~SYa`Bzy39I~(k8$xMggqZ%?bPH}{&V;`c`gbrv1+t7zwu80D{0Z{<*LJ^Ba$j0!MBgKU3* zPD2W|EqZn;KfCLG2SR{$v5O1z=TAZN))^=laXA0J<7F)^=0F}*ZxFQ=(4T-Aw2e{U z?9?;FMydeZ*BG*uChaE>6bN!yuYL3EN50e4JiO+uej${mRAEt0x9#0R9?aq!*ZGuF z7fFY6-~vVN_vkCtliPQ8eg0D&D8k7lZlT=?4K*&mn5L@B%5F9CS)Q=Qu{Skw^gPIX z|Nfx+d=%GhhjpX)#6+Jd*CFW>xD7%sfRDy-?7xpJc|2(E4rjzLzfHb*qG({`)zjp6&U5lN+7SqXs)lZ}Wty zDN9Y9<~(0zKwND>YV~AF9tgH5z_#_;P0;>Kg+foPEuGNh0wvN3PF&p%9fnAo34rgt z2;Pm|+Lh7@Tcm%n!+OfT3u0aGa{ju8vU+_qrOB2L&Qs27jMz)Lul)(N9S+!F!@2aA zC8gL_v96WhrQTIT278VgXjbe|xQVFvT_YtO78$DaKTAIrz$UC?Wb6GmeO;n+R4q7 zGwgh|Nsfpdic7gDPLUg5vBl7^v8eHr6py-F@r4!^ZG*5VQUJg7MztIVb~I9YGWQT0 zJG->ZhL^f4x4&ec=ex-Vt0S={NUH`^nWq-LZj^O-1gZPH;xJFX=HYJQYX#*bCmBR< zMuK-V1D+B8P}Om&ajJ5*@^w<(R7WD8v!>>tFey`q?me7(W5^6tuk1$>6n3ZFpYiY0 zzsrpOe0>4y4HU#vT^YQfFMZ)GNc4xa7~qN&?vketbACOVaLZuk?p@WPV>I;)vMWnR zKtLM0srtVpeFLiVZ_AH){rdItm;o`w_Q&!}|6IDGNsAk3y}5Mj_zttgh+d0~{2B&T60!`Bn|7}PK;5ek-8dwzDE0{ab5%hdt0iuxqD z)i6>g1dOT5egMI>=0}_Ogan?M;Q4r9bmXt_Cwi*t>-r-6TR$kp?Oxvm_y-VP`}V$KKniyV61fNmdCVPWI;9B`Pb# zvB{RbxAVJR=N#Sc|M&BMKOUd^_PNh{yvFsq#`9WOb2XeYi=0|zz1*$KbmArjW|XA3 zryP`5OS(J3s|SfgvH z{MjdZG3YpM$c>sIwCPA^mx2p-@dzZnO>*&3iiKlD&%rt~eM3P4*c|4#dMJW z#^}p&5auhoDTSq_6ryU3rheD%CJln%aV`JRFx6Wb5kXo~DhI8gu0I6i?nms;Ov6E3 zZwF+gVz%~*ZR2uNiJbgMh|f70)#UiN17l*H(y5Nu?7u@Zi;j_lXv&5)hp_D^C;?@R z4#O8H8bDl}S(NZS{-vbDf#d6Jv*#Du$l+ryCMG5p+1){|H z-Df|Z)Bs1t`0>#UJ~awoMT{ky|M5luH$xFV`ncuZwZhD zr~kF-we8S)MxcPaG-7(~#H}BZvmGpjT9FiE3BDw$s?K8dJm1FEIIrNA$zYaT#GZrn zZjWlqzcCW?aUMgIM2$`R3VBZU2O&3kQI$Lw2MWD$IL#4v^>?Ryk$jEw<2gJ;Wx(PR z3<~p1>jNZDmuhdR0LPd=?*r#9_O{vcll`54-=Itl!&^9-&;u^joXKVvfXL7E1YK6~ z8bkCe-9M$jxH-F=d?KvXAD8y97%^} z=tl*-#vW%a4CkImY5*&t0~q)rwYP&yUA)p1eSc&j4}{{7RH0q>_h2F8^Q|+n?mF3a zCO(x5GxYdtV{QyG`&{zrBLB*3#nd*mj7{DA)zP&!-%)aIazf}z&mMihAnznT<%wh<)si}0YrQ8~0b*<0hZEA%g^^y0Vrfq#v7dIhg@T6GD$>lD9}{7D zvbu|vHF38rl=bPYlw-NiGO}v5=^o}@9-X;SzAaLJt3hMjQLiO)xevD#H0Z&)s{iqrE2bk>z=YJ5c&JR% z8IgJ9;2{`+Jg4jaRuIrrF=VS#Q!{?z!w)7uELNRnb)*ECMONWTZqFx6P z*Gv$UO{X3@WT*nkoUwCYfvB{(gUVC+(Ba*vELdpm1&Z1aK~DNk9Kn8!PS(DRBzm~nL9TYfAuu~^9YJ5apMeK)@BLF>=}}Zpb*5DfJ0XTymKFd z0sy%mw#mjj^kA;Vo%i@LQBhG-V4xM@T?p|4G6tg$Ma+7D7#EOv+sr26VlxQFxocZ5 zv}Ar?b6^%ee!2l4{&j!}yVpLo4u5tOokNEi z((8h)mo(E)Yw*tY<-N^0JwJUk0!X_orm%5O>Fd;mWo1Hqz{sht3(nqfW=-KKwMKq^ z{zn{ic$H(6-|ZOzhQ?78H4YOX5d0wmq8m*BdHx{@N7SvgkOk{{ zPGZM4{qtuAeD_GN8|7oZ{0=IMFeBgw_BBCzHqUtQ2EGH*p55L&MhY6e(<6FKmdnSE zI7XxS_D`VUH-DhRGVky)pg_lWm*brLmq^}Anzw6YdgmwmUyQl9Tc7KaHC=EBO68>h z4*^$H9@f>>JsI#5>j}<+4o2dOxiqT~-y9czaXK&}$myULUH3qPbI?ssD?MeCEiVw& zL4rO|9aR7FSggdw0-Cs)OG?72{<@FRmpfaS*iQ0+*w}&BOw_40>rYP&jUEPE> zQlQPAND}XQDr@vT;Ls&?llRox0hr9btD5_B#q8~Ir$ObpTvOe+DwgTpHOeV&Y$67nFjm`AhN~wZm;( z1C2md9SFF9n82NUyD6i`Fa^MkGDEP<9yiqOr@Px8JP>M{8D#H4cAAXyTkP68e*Q+X z^n`}4rF#4Rk7gom9urSWNMYt-0su$o$Ku?~>1F|O^9M{u0vK6{ZOi*hQ5}HT_yhDx ze}D$Y?B#wNf4pH$JHms=sX2@_-UIQ6J5zJ#Dk$UFp{SnB@YEX+Oq7*vIk^Z$s~5Rg!pbah{6ZiWCuui{Q*;N;}wU3HD>>qplaqyf} z|L*D9jxTf`w6dMQEq;zaaFDWtm<$P#=cTCg=?ja1Dqn#u?1#AD%qJzl=eqNTr6K+IL~n69<$zjUWc zWhwSb^6%10ko_Um1F<+C3xo{TA4JcxwruLqb? z)XfV5+7UF$z5h;yqXy;$u+DhK4CtUNh(L>lCEsAppc^7Ym;#cKnD(3!xLcbs+^mtMNu-Ju>LTS*`2!D>D;gzfE`@u#tf_3%QFjdErzOUN9 zx0(cf+odUz^~tqa+1X+h5V?BGQhB-fSeLG;ToZCi^txxHr4@k^9%ftq%ZDp`!jmyN zIavq+3&CRcH;Wy?Af$vB0b-{cNz+X+i+C`)Uh67j>)<#b+XFCJw2`(zo6mUsPH_W% zJ88S|RN#D{)kjcRB0AG*R1V)fd5hEwP}7r=5kN1sAizvz#-siAdXy5t!HFaYr0^Y& zb>F23AaN)_HDM~JK(~5`>O2TJ4c7me^xlW@-|ue6H(iA9kH35=eIczN=Xl_3423nx zSh<)cl~FtjFcPEuZO}H@4?!p@P<#rdaX#DrNg6TOWUzD`Ts(mPj6r20iCA}31!lKD z7X-CmGBAj!kz{-Wdew5b!SaD&aLzs%fX<4Dwc8eLmEZB_v??HI?7ON`0=-~B?!D5w zqTPia{5=J=Py6z6%xfrxJ|eY%zAwtj$-z9l9~k?I-Hh5cdNi|noBMFKsRY0$aw;3S z;y?pHI{I$XHDDNGhm*(vmpul6&*a)fw1DR!UiY1sVIoj9Ll^+PHj`_b+S2gDd4ym<_#+Jx(|LITmdwXRH+J@|j#55pM8wwz*YU-Ic2SSZo5j>?g!j zW`TZ*DkrfA;t~6(hYA#(?SC`-p-_52$RCFW*@>D}zw4__(DW&3gVQ++Q>gFu1TyyM zWN-VLbrWD%f5_cUD|O%52tk0mGh5wo#lk@8Fc*U&1>Uf$e-ytP35s;A7uq{=Bm6~Q z-f;eVsa2RpH_2I&2Cu;EC_Z1w0aya)+?_z=z5t}g{gmh05?#}eh_NhG?1Z_wxe>zb z5H18VgpFbSmM3TaUT1RTMo%@AdD)c0+(H7$w$ott6AQ&P2%r_R#{ix&hEnd@Blh6f z_=3D3w&gILms3-uDL~r~6#H?!wk=1%-V3wO5Kpaw;J~n?T(EyT7!796zMNT+d*pcj z=PeV3(ZXS|`(>OnUF3`xhvPC+r3zK3g)|Bp5co^$Ft}EGP5}aD41x4Q7WE&CND(NH40J4j zCpaZfBQ?K>bSwsW8k4d*9;uM@AjixWfHRi86xa)BAY1K9;0FLlf!78k@RFCWzpN0Y zjg7YH${Zi{O3~TYrwU+^_1*27#1z z#VM{pz{srFtu)zEzEktsRusJ*JK#0@nX4G!ay|Sx3ISqRm!i5{N+m%VyFWhF;a-~K z;5EW_;yn5>QY%kf^Je2=!3@o`78`DxH;2e6Z>+s0UQ;*>=o`(yLcmYNyX90n9>t5I zsD58nh$7}l@7F%K%+C1q zH&1M+og$cMv4#sYhsWeO^}uh#b8Xer{_LL^x=l=sOGLl4?f9HI{5py%i7q3=*ep4N zRqh&>NL4s=Ey)7^iV+l4c>q$~DJu!Ai=_PN#w^G)p?GhQuZLG^?BRRBzEH}2p6i4W z+B%TJ%8fITe{X4gr;yX~EwxfAS788U>LTcWBJ`#wI11lW!9U=eEb6?W*q*UV8?$n% zosUO0e=xTis-82>;0pM6Tr%J4Z@#wdQ1za_0`T!MHa527NtQSqqNpRBaA-cvunU`C zy%=^{7@)n>0-A`&x^$`$P;)e~|NZosXaJOq3dZt2x6ju*`;^nPqzl}0Kox0M`D=%` zo_<5h-tG0A4~}Nka}yR8YowR1TzoBZ6im3MBv0BF?~SuKI46>s-o0<*kCsI9?^g6S zjwbv`r%j+=B_&n^+u=)Zvs)py=D-C0;(32g4pphS8-w6iaLrz30iQlXqKqfXTmGS7 zb4dSzxrd=VyH+b+-Hcy-G*8kQ;J1z2WbueVadMxvUZhDgSKsonze z2=;=?q1lmEurQQqkjx`fp{}m}C9_~Eaklzp!46brw*%V8`Xi^-m?N4C@}NL>OtJWc zgo&rL31D`yImhP!-4)r6f3qjiTv3E>_J>}E8YK`MZ*`WAmCyC>bxe;YDy5}S9-|AK z*iN*}+4jA~aF|(jonRFxt3=pkf!rY zrFZ1-TEqm770h2Xmv2Hz1Me?f}QrC5ovvu(Qd7_%9E*uv31h2BQbm#_mZg^csB zmeY~)yT$BoAmycAXk|yO<5PmM#fU2rkI9~vmpn%5wmYxa{l!ka`)g`6 ze9QUqrrWed#W1-mdaqhEy@uVLARW@wza-@D_A|Gu({thuRL$qGtu;h%?>n}Gk^_(a zj=T%%N(7cycbHMLNZs4(fDeq2AA!Jk?~&*AHxbcIKR}VEaa&AgV_eejMollTv9F7_ ztSn0}u|?*ZTbMm|INczYkBcAQPNDM)7imR|;AzDRj&jguqNcuj*F>v9c+^Q5=d@dL z#vT)y_S+*gH7%)!&Vj`W8WYg21MiYz24)r`W|qh6EiaJwyrau`y*}LFuimBQSGTlk zLy_qGUqfqfEiHJaDEF?W!5}I-nvs{Gr7nT-Wl2M3<-_8jj1LtfEv1^95buf1?VBHx zp>ZJ$f2UtpmqXmLDprYf!G~UO@?2Z^xI-N>)mm$5644pF7k`G=GtlYuyL!%YzVJt9 zUZ#Vi#L{&2F})~f-<7$bW6|#d)vG!{f;|BtE-E$K{@!=Qo?*`Q@NLcah^7FX zIgBH9RY@^1F|(xx%iF-+?GO3C#R#YaMOD!OZgek!ma!ec_8x&waB|D(zR34UNflR& zXy3t)k9WRs_7BS(WS4fc(eJRI@_y6n8hhRGB|#{%VkQ^e7MZJt-IPQyIugMs2lv*k zTeGus4!a`e!9YH~l3jvoO03(mhZS*ok0G4FW8jQ6*-t3`QFx7-Q~cq>9fPt?k3600 zkErDR^4=cyy4?8;e%R9S3hre^+lPXK8BHIY{itBFp8BOh%z+t2NH0!ElkFiXh;uA8 zV(Ew!)a<$tTf-#{X1RvHBLRilWP!K97%4u;><{-|o--ow;=B2Ebh+P0ed^a@g@{X-qZ*C6thB8L|8 zu*xYZmAZXtd*I7hs9?gsCbp*kmX(#Cl0g2+={9e&3zQePo6lXL%Yergo1jgoY-MWB zp0dQM4ymnTDr?XH9PYu`-FjY`BH4>9w5dmhuQnC3t4s_HCckkcSf!(;ij&A6t(5YP8fP0f*oYH zi0wzz`{2RU!R4fc{IetXuXu{PIXEoquqSCld=Jvy$DlcL_muO>3GOrFPXV4GSsBuk zac*G!WRhQQMWcXILykfCHp=YuE~yVph{#Ss#T$gc;B^82cwKJK{RK-cdi}Ipm-g6~3882uRzX7< zujQ4=Vs62Yu8yz!xRLl{;)B8|Iv1b_QMN(K&kkHL&mORb9zzD2v(B<|Y|W)BS17Uy zg&H8uhZXR_xB0t{>g<3j@V6GBO3NcuEd>OF^s$AcTD-@|Rt<5J^yks)0aaD_8FWt-^psNVh76 zQuY%;E7B%1_Ulc08yyB#SU(6gg5!i1_D2}t&<|f*7r5p}kdC%!XlN9puwR6SFb0_d zGCJ1Owk!hpYF%k+62&?1O4|=iQGFK!K8ms-@7A{Guo-ZngM=S06L&F*1XwRd`E|yn zZz2$*z#sVN+Y8>3jl7|1qt`&Evp{wMd&?!Kp{pHW1J`01=Uuq@$z5-N6;zmLA=N9J0s2W%AZU90H1riylA^h=J}$4{n*6 zJp=?LORMV7SkLZSYP(f~-RF!>Jj&sF)be4)CE9zH5&8{HfB^kgjP5|CcOO0KSi-4Y zy0jHKb^JPi1y6DV2$?aI76yPtroBrEffDYUB^9d2tnzZ>+CGJIf=1Q zT+tRZ`&~TMZm3LQABkXa&SLTQ&zy#psopY>`?Tfbyujq1qluQbIOXmMxObEH*;nbh<<00>riA@0vq<>fvdLXl*$ z{$tWJg*!+~-RVWWwZNay9W5d7S`?9#Tj>uTVWPt6X)uG_VDonc0oPnIDq0yF-=U2Q zg;j{vf07jtc*4&0&Fbq}y>yybMsqdn{vHTkwOS3`ou?E^GMep5ogxeXgt$$`n&E2! z;Q^qM1}&52$>CGk=`@l{M6M5zv`!HOaCF%`_X9U^LQAjscS>nhc#J50bwAh)^Mz{T zAv%plb&ChIBMda7RxL~)guLcf5};%y%%H9+paWo4`ahw`e3Eg3bgbXY*&k~b|L&># zP)UFQ0yO&^VZa8|3=GN)06v`$_SBG6TdZot>c;_Q&g>_j{f2|6s^|&l)@tWe z^mwE=axfrG^<7goZU9yJynAw}NwBmr4~4r3b)cKj6%g>~YRbBgbVRjzHVqR4tktzt zN+{A!1}zMk@_AlR(iC;N{_tp7%k??NB;tYaEl*1E`pq{CSJ`jzg48 z0(e%Y|3W?4SA@xs&y_35{QG>fz~IEU=CzbP8%HoZD8A#J-ulklY;ZW-;$p9~!1;Gm zsPZ3YU!O^DPq=HROBGU#4Ms zL&O{jY8c8m_{T0HcPYDMrq#w-6ng3n4jNx!TwRx>5`y!*=KE~{dPx)=bCxAT_Imit z5$Y?!9eO5a#4xP{GvxDR0)Cdr^&=NNCFobY2eQi$Oy)5S%2?K9Ze7lSc7)yvdCZOm z12WQT*9<38$f)Q+7DQxAh0o_sOOsHfE<)*$WFP;Rx%0+dI7N3Vk#6$=f&Mk^xASr1 z0Ti_c!cE$b+kx*?Ub$S}y2I%zy%z)(ci!Eu@&E|yNQ_DtTY34n*8NthKrbk4NXTn( z_7r4uc7kVG+q#lz;^)twMF5FZb$hOC!go3T=fe1=9k2-pj$$(_hf7fb+#+hHAWT>H zn$16JZND9O`9U+w7gQYv(9MwJ9bA+=XybW9ZO#q?-3Xcge2;MLw;+p zA(aRPa-a%%5YT`Aq=-n8b4z;TVRDiugaCg5u&on>L|GfnECsq@PWx5fE^dqo24utp zWoR}04CxD{a};)^D#cxYgJP)=eVKxTq3Bo?{+)ZEJ$*pL;~4i_0HmS%TxL}W6Uj2m zR2~Pq1VWH)!C*I?z^yEKK>DLcHwMJ#!`G{^1tnRjc=%DHgVl7l6-=qB{>Zd$Ls5}? zT-t9BC@<-0o(|I|Y|i^-+#;+{mxOCEhDdwg^_(ty!RtCPpS!{UCeOuPfPgk-I#$KT z>RRQ8mAij5(V{R80Dq4MCl7+{gHM`OpYLvQOxGOObGCFhX}j2)=sw(NjOzBGX#MXL z$3CKI?RZFsWtuYJv*b$pZbWYrMjNFfoJ%c$9#DM)RBgEk`s+1@b>zNbdYsQ8De|-R zTss6&i-BW`6BSyys-e*{^OEM_$NK)^Z=4I4KWNEDRI6qK55$ZHRdio|i(T9U-b+*i z>x;Uk-cI1mLv9CJFJAEyudWiq5yTz(e$0MT_1cC^9|SBB3L(U@E&EF#@Cr(g05oU_ zNrkhMl^DjJ#}M5K9@B$TrZOWT68kBOKQ2cX{NMosiBY|0lx>Z0^M?w6POQ6r0iQy`Yn{$Q^6c4b zOT8fTaa5Ta5EO5;KGHodKK@aspZGBd2FSW)ZvF_x2tcs%Ze%q|K*--1;F)p|;$DnH z0dEK=;yM51!80EDVt`y&5zcc})1BeZH@W!1pyDLNMITj}?g@uKznzNv;OtV|10Mxia>N%=O01WONs5h3DKWl5hKo3n$0D1V&U!$xU@UN7> zM>m)Z*BbIkN{34c42)Yx=&N7S(|*=@j15=*w zP-T98no=+G`-E?osO~*A6t%X9v$XUDFS(Py`qirdj(V>!4op!Sp0wOVRJ*Kk62#Bq zkSL*Y<;ja6;88R)=o3y{DEaLX2Q5$-!yk*kaGLIvv=Cmx%))A*dTwDT%as-}dCzDP zx7!80Q9Labdb$vKfE52@XSr7UJOSWQkU#&FLN^h%T^ zkXtzeh7XY<;?R>{eXj1uVTUnUGc!dn7Xk1Lpu&qS6%{ z;Cjl@gmvgQnYf8#2D|IcV#BywDq=;TaF4)$Ms}S+3pkjPvHd4{o50nNuu6Hj`{k8s`Q9Ntp>~c{B0xWmjlK13ZcdM<}bx9zv4BA;6vc-3sOICBezn!0uO9 z{{&|wdP@NN$avswNUAvR=r~m(9lJcj5CM^)=TOa2qm{>=^1vq&$Y;&Wu2MNxN~c}{ z(m%P75%f+p%O0nsq=ZUa$*sgQVKPa8A%@28mC;8&WhE-TD~3DIeJ=t}ME;7#cny+R zs(${w`fere3hO!xhYOvD1MpFrDC~!YdsPogMCVr?|K`5WuMyCDP&NG8>c`+PP{=}8 zXL}+cZn9Pe&5zHqwfis+%Ji8WZdvGzAgR!y5*)_hBb2*H!6o4)8BL_8H^+e15q$_& z_4jw0%Ct!ig5gkzJ}PZ96|NM0xe9VcP;Ej;l1sku4SfM!eIYlP+C_jP?uI1~(E%uy zX6;q?!a|*ZmM5r08_696FQ7e26etY*Tc=y0c^r52iWu9=4l|AgpUm^B<`BPkHfX8^aJgV5pAQP4;}!2FM{yt@er}V$-174laBoKe&cWhf-*JLO*o%Ze!2G! zyLMCLNNtAZu-;6zQJ_sz>571sS%A|qUAvi&0~hjw<x!h;ij_7K)Zd~ji zkXmTQ%NDV3uzR?f<;&kH~mj8XpFKLb7#k&jP^=#g=(uEOuN!r_~M-xcs z+VQ{5>o{)85^PpH2Qq9-L^TO!=~Nz-g`efwZ1~ud6djXTv>iLP`o-w_`;sj3z{=hcNjn~LW`09$1PtVN9pgvd_c2R<^ z{WpiWiPoPnC&%DPi}Vg*aYwjUEBv+FSt1?w^@O|nTUwF$}O*2C+lY4?Jg z=!xiM=o0+J&xU`amQm?wNAO%Ka6gwid}}ZI;o|9B5A<(z3I2+I2x;Kkh=LUvnd72Z z#8MB#`coSzKk=`A*EUAHF!njP=^50FpEREK&Eyz+M5jtQ6;IB3{#-d87`7C5@E|@{ za-$)usVf`4a-l`GV~LmJEW`8IQOu*64%cz#g}3_! zs(~G)#xaHNqFgfG+a?Ox@Yl;MtsS2aOPfQ7A!^xt!T*er{|z1Mqqi;n=MN7YOw<-q z=c+!59w)xv@W)|8yqj=P1e@89ziu%Utb`-`KG3S#K_#EJTUQNDQ~4rgFDxvrO}^oR zRBP{3%Tx#|dQDs3xuLyF+-Wd)rV&t&mo9%qY_XgXos9!5Q~msx7fmlnA42VRP=wZ_ z;-t1U*(iMoBF+lOMh*um-q4;WNUhL`+U7t-oi$pEEX9=;x!bu4f3?mIj4X4z4voh| z;n5V-PC6|eyjV#ftUNI)aCQ4(eAt=WW5=6@i^N5n_ei^2C?!oD4oRm|rO?!q5Nvdf z+n7McmU(|6)Vc#f2ow5%ZBDG4r)A(^*gBqM>{QNpp`eD8TZ?4&XW*5kv3u5{H{jnU z4~V{T%WqY>L;QOjRairwLDz_*R7DQ%5Dbrh*n1%dHpW6?daz4b)g*`Ecy zsZUPPc4574j3$Aubv#oRK8pfR{JECKUll|o=k@dLMgM(=vg1z%!EpY-@6t;vv_y1C z=sDFfCg8o7lhs$8%PV8V^aGWA@SnC~H(xG3TR9Yl$FFir(ltAtTvPlhsNn-)%KfNy zQM?J2e$`H{rsI>?=Pq-TmV!F2nMUDDg#6T_nQ<+2YeF7b8@mXmm;)uuRgw8h3x$kt;MiNgL=?p2i!#{#;Y8BlW1O+*D z#Mtqw(l^^?AA36&;bSQuEtdQ5x#{^zHplLdJ&mQCwXT#p=GFW3B@^^Vg3IvQtyQ%7 zG8W4^OlCCRCyaS4;z%1P-7sV}{)fnWE?_u#mmo=j5fdHoTS6a{*aW5|zF17Rq%oYjT#b z&XASm8(q7O<%R#d2?wtU%QJkO6?o#KAy2JzJ^FfZ&B_^pv)=O_8-_J~HZbK@HT=%= zF^wX&IIU#WV}_r)`7pmEAjxays6=W2m6-?J36r6X0yZ&l&&Kv}7)Z885a<8zL=R&U zchBJWXVVkeC=TVw9jk|;K~@yPE)#AKs1EZI$DvjL zO$6q|S47@HWnp>FkFei7u~bd6ekWb~#ya<9O)d9){ZNQ@mUW;0*qY4xFO}zNCcbmV zW`NYc(#SfO8@u+G(%AY}(aTY)2THhNR_6AduTqQ=go&HID?L$|O1OLs;m3Sd8*X$38zuKiyB)eu#;Peo))QhG%?x0lHgI{xAAZX7OSb zy4SMDmR)Y#G`;54Q&oW@ZWy$1?0AkFQPC&SSnhu*A>>4%`;aQ9Z>6={t&g9vT*tQU zx}5>4UZPgsw+^}{(l+LADE!c^skyQ|E@!0W6_z{LolC^qMt^J7y=Su8YxweJQ`juA z*Xr?l?|dH8{7q%*x&2ODOYwmVCX4`Q)&yX?A)7dpdvGkWw1)OG%ThGBG# zHh|#>=Zd10>jnB2x-t|?e~KFos*dyHO_>^uajv4$yO!ieTfX(MKPgr%IZ%wV<$VcS z4Rjfn4QAfVAx!ByWvoBB@#E7Wd+p|_zMz8eDjM(k@9}gVE!8M?hzfG|%xz+CKS@lI z$WPoECRLEBc)*CTvz(5K*FHJCn%7L}2)8;F9kwG_o3;Qm8vLG-4ZM)xJ{PYgrq1<) zDhy9iwIwtpJbhN*4D;ici6P(9MS$Zey=}urUo$T!(oy@mJrV!+?R@xrjgy@Oa#uZc zUg-XYYvN!ce%z5Uvla823a_zk9pN}mq>6akRjqQ@j@>5>?j(hg#lH=#!CyDCDBq3g zr@r0&GR)QCgMJ|adhqKrO;s=evJG;{WrQX((re> zV)c@Crsz8bJWEqZBi2ki$SJFLAx?8UJN^Vr)?!FSROew^Gs7Z5O$})OkNaH~k{*q<$aXi@u1i9T%a+7Mj)P6w70eov)28%~G^0bE-5MuU@r| zR|wIjm}4ym?SXkdw04&Thm`4w12^}${1 z+LM6u-&cMe(T`i&M4QOb)wj3_4{52zHa$-IOK@{D2eWh&$&JPr^;d6yx!Zhlq*JE& zU4_WzjEW3g z*>q5o!A28fU3XNKVf10)Qc6~bf9qfA=59|Z$A`~v{{4#L1qxk4IM1ozZVUdkPDfQ! zr)y2~h4^>=GC&*0Cr(`k^tYOz?;a-N(4I4LhS%emh=uNbQlARZ4>ITe)mvnKbul7c z;EWPe9Vji6l+#$5to!dlgZ&kKAeEaci5BrP1JU)<0_7z_4M*3YKj6aOG3(lZ5f&zy zJH(~QwSUFj9yd3kN@Tpp;4XUVU6{;2U6xxV2dqWDu!u^YY&VO{(+ShBUZUN|Qorhb zahelcjPs-E(!K^#`JVV18Q1g_mFlG{w0nF1^X;Gf*`(oHjvetMl7d8dYvVU2;#{E~ z`f8-s>TP37U-nyT*|<0W%(lDkx5JBJYbr%!;ij2?)UZu4ZGZieRJHKc2-kC-SV>rix)ZwR#~F1LjhEV{h!rZ6SG|x_D)vHV6nuf zW4maK&;Q)<02w<>i$QR|yTeV>MG|hLB3~*!4qPd4OpmQ1BKp$Tz)CFIvU@d?qx`2W zXgkTcY9}`yQL@0ohj@xMm`p{LS5Btu(^PNz)$gf!$V6O93qGqYIXl3SO{z->3|86v zo3eplXyyj`_<^TvN17XUVfU}5YA=uUeAG+?8HavY+`js4rP~;Ysr1CB78xz&`P07Z zKkRPbkM1JATcyox3$_AX|N86F25eFHa4doyB-*JuiNY$KZvAd`ObLhSdw1NXayVk%Dk_8BVjyZ~vJ9!{1aJNRp=n6&Ff@JqFuZ|s zo&}|IeW-5(j!9orJ{fgZ2Y-F+G8|&=m~DU0q2FX&S24_u7exoY;cn`J#-o)gMn6$X z{S;nr70j|NxMJ(c=6%@a$3Y2nS^x7(p!bkGPiy_r0eFzaNuUT`ag?7${{cVOu=)*k z7p3_Fcz3-u6vlwyV9z)U^D4!L1hy z0J;!ap7n0o_Bx{V87`lCh7C1WQN{kCZVUGOKAf~~V(Ji}YA-A^S{^bMxVYbFS!8OU z$r-(5_dkO0fKW>rNhHTny>(8~1pS{ii8$GvI?9(qsYc-j#xo!8)heMzzMrfWBz zspR@fVUmwj|K+oa9a*HLhtj953a{bBJ@0e8xs@VycFg^lbrBaAIfMqY?C@Ph7+<~T zmOgjf{d-zP|D_`UaF3@Zls&q_fAg$VqMocQXwYgswa=J>T?gg z%QPx+HH1uSPDwfxc!h1C#^Qo`l9qB8=zTW6%RJ*z;}d{*k7JD5bS*>3zL zz}Ovqg*Z$*Lhv_!TfAnC-J#1H{qjL=tlVDJFo5OMb?x+D?ZUxtNZ4s;M;YEE^!}TOe??3 zu%fWq?$vznDj|l0Ly<}RY?VoiRrOL_ViS6^O!mLfm(0d!5iAxKysw%a&q1QRVppXf zH@Xj90c!a{Y#4B8fuMQilQi+S@jp{}c)iFE6U;kTr-1vCr2aqOVa_TvumSc67%T7p z8s|F@)Gyeuqyt{|=%fD~VC}Z13r#JSyRx>d5Tz2fjZI?f>08=5I6g!gG(QxTs z&H@I)Tr?`Y_`gS7n-(Rjji}&hulohd7K&%=I}I^F-&efAAlUWNG4~se?cp2BCPy|8 z^3kK8;DRN~cy^PXII0RN3h(`4bnx(YtEG~nB``CWO>(srHCQNX4rOcq^M1Z`-?SG| zV>=$jzlhqJtKoQ!!eO-}#2-<<0RK=s+mFDN(K|=v_ZB2k;fV`0zzp4U;3^@SgX25; zN+9oFZ8YY;Z56?9j26Y5eNJw?82;hKvgFTrzX1w|cx)<9@jauLD83J3#fGQ3b9C_g zxa~wR-v71yKp*m5jFM-!nuJYS?-O>Q3^m~Os-viu7~;*m z9A0OM-VwQ4`M7%$)I_pPukqLz`>?V;>HX>d$!Popjq0{yG0jQj{?4(2!Ufx;^r<~G zX5qS;S#)pYx!E!d^7Py2&y4KZN`veZGxHL(Gm`iJ*$KLKvR6x`ajAv-h8p7R!h$&0 zU>KS zn26Mohop-I!kb0f9~$PhOq^RL_r(6LeSej@VfZhr4`w{rbsQm<&YgDzmiL371LM6j zCPEtS(s!><&|tRNM)}O<)m!~LeYx?1H2{Ai()q?RFpbxxIoTx6{I+n0Pzt}{V_40Q z-O>v&sF5?oEO`R2V0b+3^c+3$aO`i}>DLD0G{yAo>H+D9sgEq|W|oMi3m(7KZGjc^ zF>iV7Iin->ziw`H@4lJ`BC8<$S+~WxdkO)(*kU31bE8(KQ{g^p*}ENKs|e_4Bg6D> zoM+t-)2(f+-ibxTh1}&ST!%Bcw$z8(en8EEo`~j*F15=n;fpz-lXdI2)nOME9CGse z_OEN5(H9baN7WaOuiCKZZso0|ou5ZeN$>}H45a$4GyMK0Fxsc(wPVQydK-RmQ1B1K ze3+=4Yv3`L&x=IqvpkUjb1Y^L*q^bqJ(Btercefb0ImlQPC1eDJ8~vepU6s0GAj%;vf&Rs%vRxb^`)NLNUmyY znSEeT%}!?)azKWH*M6gvREc~CV!XnLmANs~da`{`i} zd?;ujeSdSDH#BOoD?MrpDL}>0x2+%xs_iVe)uDoTsK#!`WR0pn6sUBN*}kh3Dn_6_ zYiv_1ZmZ3gqC%WPL79QsDg zGMkbCR7csfKFdkA&M?fP5~=CrOa7Gag6g&H*3~QQ_!`+~f)8n=6n)cYYcMMc9O;Cx z)Yc)-K*a;C5b{`zLJeW_HOtD%&gHiFLD6b{l#`JKmC-t(MpfI8JtR6CK_AOx$o!zY zDE;bmm`W%V6?|sW@LrzwJ;RMZadF6|3HW@?@8iPNe382fXpitIa54^lg8p2rrcjK= zYD72J$jjYyXdjl$yGVE zsNhg8Oe%tYS<)lvP`FqS)o(lyPP3ly(Lde;);^bJx0p%OrTTo}SbeaB&SfZH{FqB6 zN+5^$$>9M>94X0{*`u9-vDF?53>8DY?gh8X{VwC*csuVf9)l176mQlfBSM`4_97vC zwzEl_a%vNxC&j;~_JbZ&FksY|hQhk2pfbnT++#U?Z=vEt?J)ujy$EuGPds(@O+_iV z;Si4QN`NM``(k2aU%IU5-$9B|NJZO#UD-lqI>gJVpEo>7eD&(pY>#MRcDtnaw5hkq z#~D;26(yY?aj8V5b#Lce?}3n3$Fb~6Ppej(X}IgnP`mGklq6PkKc%=!3Hw{xhTr*c zU#~7R37aj>7fo+EiAR8@Bt^3RitC?(Tji9Y`P{gAHxLjql}(ZV;`6JzVioeQ=z z#=6g;nL357EPX^1g7TV9{|umZ(TWF#nEi9@5kG~pLh0?2D4=uQe1+}U8)i>FFX(<( z;XcH}HFqJeV<$nYV}+8m%%{v7ZMm6Rx`jdaHw&nIrH{cTv8PT8(* zfZU%%A1O8JEcS(?0%F0FZ=|)w-Wuu(zR7bApcD@PQV<$R7tQZiwuQ3Y$HvalcKXR# zo^<3&2{r;1qC>UN#(g*lM|Jzi6b>GzH-^)yoD50#dioLJ;pmKC=Np0Y2rpRj3ZN9# z*AxrB5zc!~xg4mRgF|lNTteBDo21lIzbbQ{87=k~KXz4h^U<3Vi;24*wcpQ;c(4%B z9PaK3fjksF^#@n(6QWiQD$kQw01YpLLqgcT=R(f;?E6}C*e2)`H``F@B@*E5{|U-U zvjGW^@<=G%>J(&4{YzKpqc15h-0pLVWyufUW%#H!W4-CTjsR5&oh&`ZBN*fb=Ssk3 z36c|cH|EC1#&$wY7~Roult*)G#6S_1F-OBQ2gRmuc{xu9n#~!u;D4UvGAEZUSP#N`2~!QvGrxc200$9Wxc&PxK@kNxOp8Ew#0jr&nmn9+HtXmtGN z441=?GmQFeEgmo0p~~hHAW-)SeO>66hzcS9dlaJT-p6q9nmgyn2Cq4v&_+)3Z}BG3 z{GkDXn4q8&Dm?);?|bjepj1!UuOW9i1npyXTvKo5syedHp2=!43-s6+10+`q2?fI`K`g<9+X&`tdS*ffl~FR)_mIA z092I89|H?BBh0x@L*@?mV^G1C4Qf~vadPlvf=mLO*35Bny_V~ z=;G@apQXvhg)SUuv$gUn-mS-G$wQEK(l-TCEoE%?uJI>f;?DOWKJuhgDc?|I`r&I1 zRdVShkmIOmC>ygTO^bO-08pLIFzBtm^m2YdXUB<8N*WIA)cRane(&<|gL$(Zk7Wr2 z{rnutYv+2(s-WEP*eLX{`>CG`KYkw2pUDxTMqL5vspJgJu4@m7x%ySl`mY&%^1u~Q zYKRWT6AhKKDo_dVH>8rS*sxRXuOG6^OzXGo37!ZyW5n7VNqWDE*{wh1X8`lCfqW!i z=g22WOZ^3EqV=K}Dkm}2Hqw+S&U~K}+jRqlUemN~Udk!zx8jGAUKrk@M&bB|KWOi<#NW z(p!k*fD_*^)#?+u`M;E-sL|X;IBM+7lTGynU5Eow* zeeZO-bFO9WgrsSKn7th=&pn``wCP6iwz&!$5O+^pS0ts~PkooxF|wL>26&3nh6 zI5sIrAX+gjvJj_l*otu`qFfrJtEZEoX(I>pOb}T0c;Gf{`899TuR?Op&Uo|53F7_$ z^$jNH7OXeyOJi(9FT#kofWHoe8l-^6b&`~>Uf;^QSoo7eq43W~Yt55KgbIh@HCo*RV^@&SCd6+XaJwRl^8pRv|${<@pRZIbR-r^)A5?$adrbL9S>P|+u6J;kYTokQ(|_# zcbj?or+D=QHg74{#!PDi%L&(n+D%Z}Hz|FjXHJVPk-!a(N+ zb)2|9(wgr*I@8LCo&VO$w3=d%%v8SS$sF18tF=&B-{3>bUr?IN|NN<~PulF=x7@WM zkss*Tci_l;q1l$kvfGn)tQzD*DH}GLuopkL$7}YNEP-Ts?&S4?-ZIhN{hr;24K{+L zgP?O?cG3H#0)-xBD|(S2lfKhzhu7|DzZToXxTjJ2+H!_l>Q5)#1^|>FV!Sy^(N=jto zT>n&QpKzE{6_FwyiFSYs-{>_FaBuiAfcUS+{d*F|1!BD2vRw0OsG-YHx^rG9$FD?d z&w)QwWvH`5ZtL=3?Z9)A<~HIHy8JU9SQbPYXj`(gU{`2H~~o4AJZMGB|PU z;~}_~|Wbl+wGi%_5HGN;zeeNG7*Y?=V?hBj!GG2(rzxY_9<`7%(8uUr63M8h$PBUwD zN2w#{O;Luv_-AO0aIq#&;kGcc*ClOG&Cl}w2N$onCb*xMs;hO$U{IM6 zHF8Hq#b6y!qmHOwRgiynqi+f_l9Q87MSq3hl6EhgXqzdRVaoR^-fj8^CBBiw*D=gO zHaXPC)X~;uB|iR|qG}m(dJXM;8vR1$v{~Pj!D0uCuM`=&8qNI}093|olH!zvfj#}Z z{z4SJVbC3Y1DgBK)rsTwk#ZKS09tCWxlj9Xh<}3r-EaL9_(Zf*JEwt_l2dj}uA?WS z*%7-M9M_~cK<^-?{ADo2eNYRFXQti=N^tW8h59`0zct)$x2+93LSHuddM8G~ z5{?^^wtlS!)Z=r4{#3jeK~sGvDlC3JT(XViS@XK}=U02$`PeJ|Y@^|rLC~Gnz01ns zGzb3qvLv3TiF0={P+H{qE;~P8 zmOvzm5VAF{j-IsH7I2hjs?b@6A^q&+8_Y&=!(&x}>3aeSdDKIco(R5cQIqGA_s zW)N{-hvFhUuC1sUv<=jKWXkWA9C59@5Khy#v6{Upm=+csmuWmR^4WWSShi{)C#*h; zB36kuF#9@W(As?6=TqkD3H@z;2`qOA>{<$i%G2^v*p}(_zd8yFqz5JIRdw3T zXimEG5CrhG6&fIMY9#6i_fF{(SXw~?^+AY{f&m#4CbvY)|BSugnhIThZNU6H=;=v& zt=6$F?^haadDiYOv#;_MaHfrkYDF>K6!PjpO4JA#OB*AWCu4nDCjgW4L0x@OQIbmr z3-{TrHlXG|eKWnwLy3tR|Bt;ljmL8B{)bO#*v*4R4H_vFp;X4^NRiAHMJiO%K$-V$ zB%vfjg$897QX;X7Bo(0~QyGdBnP>jrbzYa<)qU^(o9FYq_Idah;XQlGjTZM|riK9v6XY>48|KPBblF&BIneCfB++#4{G(|aAe>MG+)9++_G zs`{8PLawXs7ybB21EZ+t@@Iq)t~NaZ3s6J3L#T^93mJ8q8a$G#{Rho{pxN)o;qpB7 zKr^48s818Geniow1eBSrZwchG8nboYlLDygP+*GUM&WWu%I{|2^cA=%V z;4FD#pJ7msfHD%awbZ}z8J5i`s#<7lqWRi1NjT@=L$4HW$dFNsn=Qq+J+n_LxYN|{ zv2~W%d$<0J=KD7@%wqOe2yGq0`j&QH+q!xAJgU;$^;%FVh`X?z9j>DoS?R$tQL-EC z?9R_VrBr7B{T#;|LJ03p4y5)oYTI-O(H_~xmTa)f&u2otk`db;MqP|%Q(vHlyqkYm z4gI7#NOEhK(gq90v9Bh2govem4bPSG(JA7oLR+yw)Z@mN_srjgU9^8qy{kVbmGvB? z&Hzu*&vnJ6=%HNV%2VT)%vu}m=44maq`vgD$CH}&!R*XYhSsHbH*cs=Pxbm|=<+s& zx-6m;`^@cVqS2q!e?cBSp*|y8Ii=w;_j;1avzt;@@=4~2KHzK5uXukZt2f={v*+fd z8>}LBu8NYz)TN0Q@RL4Y+PG*a^-e?``jDs8kfsjs=b!LXPGdCmsbsshGw6YQW`dZ` zDeAgOmJEe2_m?CtxrVNnpQ|LCI`qCeJeyiNCTu~U%U4vVQS4zw&0_9a_8IIR^z&$+ z%(bd8@$fO*nC`pLw))b~*iXBK2BfB5ibWWbLXj#SF_n>M5JrWPUj6uM=QHWD%y~xI z!Pay;nd3(dV#-)Akg+oGVxuDLm0oP!%_pfAymEh!(n$g@$ddDvy z8S~AI*)yfur(tC3^#`|X*cHWnU&XcW87AIXZgZ8B-@4>egFhX_I_L{I;vD0N{vD(< zi|>_Gj`|lg(1#(~YpfZVaB4RU_18t$aBE8hd9VWct_PSX2)I=zrGopT znEQZQqhHfYLu>_8{AzMeNa@UAz7KEZ=)E9)>skFQ?`*L4+(t%M)Y)%U&&qDQeu*x_ zh4<3eolV1ygk_kA)00`TEMI~Q;0N4PkUsB0SD(8zZ08*fiD15js%n;& za>VIsoR@OsivbAos|EKeb8h7+#JkP=)3$)GLUf;}BwXii(C_CkR-bQs4YOz1$V-CG z|Msj%_EiN1=Ca^!x}yva>N{kDKG1}(w7!ijH!41u^)LIpJZ+vc(LvA3Daq@&TOq@{ zJ`AkSdu{P&9dA~$-(Pw5VETiUpM^85zL8}7?le(ezFt5f&| zW4@eYSD^zkTUq zN128SBR$CWq|}KYYDp7H+dtk~$Eg5SR^UDTe&TB$Qd3`(@n(hMwpq%`k_mWy`Y?#%(ohK6pe`@Q^t2o7W4RDV6mGWlHC%he*D(akR6zyiGE_Yxh zYmV&f=G~B(nDq_V50L1?Dqog6B^|AW`>Ds-021=`E52KrSG3QGGoyZ7;c)ox*B~P^ znBVtR%gcn;vN5Zw9}IG)3ph9ME(HQNv}Saz;4-{eny?Z!99 zYdmw1Ydt>aVFTaQ+kbB1mwZ&~W7_NwSTp@>=K$W{8&7pU#&{(;`sMt?>TZF&5_M^7 z2%m3p%iy6SQx|4@rwceY#7X}{IV6&=^v$#B`ICF~75_MHPzSCrMv)2PSIf~DCf4-( z)b>KZf%Ff0nX}I~PlmBUDD}UeKK=QO3ADUbgc7FjOAh7TWsv2ed3a#_N$ItN?_cSv@SkE6{S8SDH;frR{Fj)jv3|k>)su z2!nA`-kZyQm;K)f*9!`wjIi#>*kMjBCo`V?7_B%pJ}NIahGkK;GbJkQ*YHPBz?ZF8 z&ZTtzUGe$I!(J)d9e01Qa5~0!1h33eZI038SKHJ3xu)cE(?g|8_a78lr?K{%?}#L? z{);I`ULLR$8{71{>%mz^zgA;w1Mcx;{zgDUr$cC0e)+22v-CtHmvc0~bEetTwc>LH zo!2^NW>sYOEIRSS)vxsr5q9Bv%YLnixe{@bB&|@iQ|7;X9Hg^~?+|Ewb6D80pm!y$e!FFw2+9b&ybusMEx-Rx2`5s>Sn(1gSVY^C z5f+N;k+R+N@P{5p9G|cjWw#8MbT$~;VKg#zH>z|HY&beCoTU@t?9KD&hV;@9gI;e$ zEe8F^SBLkfYga)^5Abz+bw>t>d-j)8?rr@g06~rSYazh?^}3Q$!<;i!EXVY%vgWGh z-+n8q#Yk7}8FI3ENs0ASJJxlhAUG|8UZAGQyCL7!?dfW$uTaZ~SwZjaZ2YeEO95OO z21_e*gQdng3eD=Us#7iCx+;B>UO_qr0E(JC2pmHQS$b!8D$jF=ZwO(z?IMCkTuw)n z^S^e^REL8Z@YVeNv$7z@_u8x03jS2-=^1R}TIb9-p3T{as~=^&F5>tcu5kf`zujL9 zhJ3HjwcAhtMJkqxw7%30JaX>d+?K&se4lj2uHu$bd-BNvSj%~VB5(Ym%_q6sWh7&B znxn_nK18yVOW!b`FiVkdy9(}qvL}K0>BgaY&!I^?SGYfT=g^&vV~ZI1JgeI*KfgFx z!n1p;dST1!`(1z)$t{GE+V$|4sQ1REcA)bH-A+x6_rkMp@F!^E>}*daw8a!{u1RKt z1e19UAwyOEd)*RKmVfZDATnN_G~NvKKP4jVg1cP zU3aF+{(k-FIh=P5I8@OMjF(5@6V9VcUjMH1i*&{fBi8c%F!+<7`DAySME>m}4yv)sGSVz-uIr6kN9s zC+GLWXG@z+k$XPNt0#DWE2=3+$0&nnH+_{}A>QLoqs~)$S9ZO^mY%Lh zFAZ=o8<5zXqUO~1F>?0fx+;k&pJmt&Yk0-<&_N(ozmUIY4@kW`-x{|=g7h_K z9)zcIb%yhx+L14BA3J-j=yRN9pVwGUOBYX`lHm~TQ|+*T2KWwDHDe5y=Z$je zhr$)l_4zDw(1~cJm9z{Eu~~gnaat;f zqxba&CL6R*qPJgM;(6Hc`Ily=&I#n7crz@lnmLr@-RRCT?Qgy(ZTz^Yy(4Fx;_j0t zx6+s{7o?-g2d4MRMG)j+5tpn2c=rhk2PM$L^X4(d2bQnmFnwm-FQyj@<Wu>9`JkG7@H_8hKrK)+c5i2vU z4n4u+yO~c|Yrib^60>I&SB7kK;n{OK7SZXcYAy89Z)#jJjWu{ziungqN2VI^gioCt= z_CQI2+>L)QHXr|GAM!=Vi8_l7-6_0VpDD!@o5?A1m_BP%f4Ynf>gKKC$f|po8~*E_P~r%CoO2k`^*N=aODo^M zU*;_SZ$e2>Xe};1^!}^UhVfpbKyI=&dci<)~tHSbR7+^95J!MKm#avx+)P0GDpdNW+*!o?41oqMK4>inD$ zzH&TTZ z$5Y&r>KN?Di1Vo_^b~bI+$vPWjUmhM?8(j)sRiRw=MCNYt-7P&!Cl4o19#Gc1^MwD zXqUG+16h4cQ~Zi?Q9wX`hKItwLlZcoA3_%W+TWcinj@H{eLjhqle%o;Hz^$6?Y)BK zvJgeyFG(%fgCTcn$>Tf6GH-UzRy%~HrL{YZ@4UFQ?^TzFyH^Hx zG@cAk4+z||(rFWO=iso@M<*5eWq7zq1UhW@<}NPk!8%!b9QGv>s)fGRijC>U;n&A4=u_tv7@WxY9>aWyRtp=5$ZX4&`NAph6%`LW=J;ee<9;!abC0T* z*Z96*!(j`aet8tZ{es|cUl8!_R_aS!@!&^Yl&!?itBr#=+pzN!kI)a>qi!?ni&JgG z@t?s9FC0A07p0+wHb&gomjO>m;GU76TH?LRqNK!%a-pbmlgd79sdE36Qnhs;wKbPUU}fr@oe8+JuB9$&pNR|p!24lsv_SqF^>M> zy?c~O_?z&%DXe#?CBrt|aE z$>r>IL01rL_A}1?ch2Mq@pg)vF$qbY^0$XNTvWF@5dUw77U#Y_mN9*@Z-8X{E>3Sx zNlzX@OSZtZ%o?l{v&- zY1Zf6HQSd8__+;a9fllUF`;O&aq+77Bu{%yF|A8SV~@URH)3yins-;iYUwf}iGLz%p37;8zt9xU~XYlE^i2RS!o{^g%DDV=M?OCI`d*8(=qxcPkn z&b5VFzV|c!nBOk3iCKiw28YvsaW^iNM`1SWhcSl~^)&=KXLk(T8J)!n{m5qmn`kNY z3d;U?B=c^FHN^hN@f*2f;CITHz5r86204fRd0POQoUY)k!_#!9Ss$DEGuTE^NUrop z=t|jXFNUS>{`)YO0=<9RD|#GzhpwcC&nZr`OAAYOoOEBNQ8heMn0eSwR6I5hh+@2e z^PFDkf!#hzJ#C^k&;E?iQ=Q0Q_$w`aAFur$c!PY+6#2LRTxJEg=B?vt&IAQKGBEQPuq~#+M4Fm*U_QZSbilf1B07s z$@eeq|LsnYG$I~Cex2La)8jyWYi;}3)gQz2 zSz)F8gNJxSUtc@E;bzb2n~Y>l^LW>u6^<|4$7+9LHBnG2&ynQE4lPr@)Hg4(_e{p# z846*l*J-Pme4esqPlKgiD)&?7^QjFB)?CoolVII@=uO(Px_h6szq5JEpa;Ac95=*y zkz8u! z=jm60r7j3R4I0gCA)R~VUsvF#7Rww`VSLAP1@0)GKBly#e4k`iZhkT8yo-m*it8Lr z>c=CbLg&5Kd)asC3|E-`$Qaj5h7c3u)24_)7C%dx)_ zq(A9QU-$u=j@qC{i$V?KU-z$6Zm~@(1rkBo&4|G@ra`D+Zvh;bJnp)xQ6#N_Ln>oJ&)IeF=Ry%9o+^1_?1O(q2I{rC>CG2BIW zid}`Cb=?&;?bEOY12E5yrM*bC&XJSHU{(-ex2#YT`W!=U$4~*Brk~~Ty6Wn4n2Yut zki4lveeD?)K+73TPdYG?%Azr;bv}wTrcj|GpmZ6i8Za)1+QF`4#nF97t*xJ9=wYvz zmIGA`W8kdGbGIprF;-(;-!Sf)@>lx1VK(^OcUw0&zP|r8mWR#%ymBS`YX!m7>}$7` zxyD-*w00!a)zzUC>jcdMB_yk_tfk?0tMmz0@Adb-yI1t(A%JKJJ*`C*4~h<+2hK6- zdudcuRQ0!SuCK4kW&jY@n}GoZ+X!X2*r~UhT4tNPxwc$*5!b{Up<#9>V&Xt&l@L$k z{r9;RxLDJKv&vZp5BBS;1u81^e$Va|-_ma5G{d3!?J^7)s_1UY_K+<-eoJ-w19yOK z#TGrPyo7le+wE&M8ih^njhq{poq-aCavI!BLrtmKJL-G2zfI(9g7cnBnR7?$U%9k* z`SR4N^O>tF9*r+xEnDR{P>Mk=b%ehg=xB>NsNvcQ^@OUV8S6CnNn61(PSjhqq0OnU z&Fa;hIk?rUN%lN#-}0~51PFwED?B{>?GNrnb8hCI5=V2}xtEU) zIJE73xD~yxY|(UCVBZ270I(f32TP*!^6~_LLf<9doU?jK^t(SW8PJ8=;O7Q!oLbUP z3kw%rRT;}{p8Vw$tfV7%`dDUL7!~<;B-8v3^DU<9?l`8M?%<~;{3Sb3h%WakKtb-g zhma6zGB8ZRT`z9WCW1B7_?rwA{_3^LV=K;687`42CJ032TE0C_v*Y95tPm@8?E0Z7 zbfmi>BZCU&X{y4s!!KsNEi9ZuoCVA&6_grdzE})!lOGa~S&Wn$!g=hVDZ#^l9>1jV z#PcY51oUpsM}TCn+(UsSO-M_3klyp^97f~OT$Y zC>w16NIiovqQ`&!J;WqCK%wWr6wd0Lg?+MwmF{RJFk*9^G@s$!V*wm&^G@iSto?HCE*MQO&|+49oC95&nWLDX;fsxKF3L z-ZYFhdRZs;E#y`?K+mq);X3Jr$X7h;FMDWK+n3P)I@HggyFQfJ+Hr6)^Zlb z$i%4m4^3Uicxk9VwYame_T4i2ASnLC%b_yK!5e*^)3e0dDPrJO#({?=6Q@s~?(#+f z1Er3m1lJg&*iGALqBl*jnYY3wt^@Oz^Yl>PUZ{Xd6i4C>D^!HFC6#*4T3zlH*u9$_ z#3W%fgDN#rpbFTRa#LpTP>Rs3I=w2FTta$R*#a!!U+RsaRn`u;lNH8)u3K6q`_LW3 z#;5>wy`7z1v>j^4XE?RlIQe|*e*Fo323B^rXDBU7`icU7cRJ5?Zj-mPbfTi)97D?P zeET|xy(1IUkZZr)l95!Y5-^nMcPrDOnl}AFHHHT`JMnwK)Po7LXhxsoJ3q|2vPbs` ziKMSUfxAO~IlePHMbro|tATYkjXsqvKD7GVm?fO+Gee^GyADkqG<4@U(edY9S|3(% zY$WIR!Zm|r;sH*N`rb+7w=u^-JMC)JV%IXq-`Q~h=bmP(J`wRdA_voriivAveiL(*rE$iH;O>yeZaN2I2U7mhE zTqkb01GFvP=h7(Z7hju_qnuENbe>A(k8w;{*rk68 zZ+a7}7vU&0LQSr{qUU-d+5UL#40?H|{X0484jQ7~dB|%2=M#wZ(9d9(fHOSq1z5n1Bj!T{gQ}k`@6a$X;c6oVwY)xpXI-~1 z!p=wSNGeBtLX^r6^Aq5Qa#Rx59!pM6RzO9CM}Bm_sXjPjJiqhmULRGM5D~Tq?7mfS zrm!#uXaSRR8G;u)h0>-a;R?H7cvAh|%Q|Xp{ra2kGZf5@JH6^gK}%W3^)eUKawfP> z=kBqjM(|LBi5thIUVd0n67b>4U6GcCXM^K)V^}ZKxszQwY8rH{dn&!uqs)31Y`t@N zhh-~s=n+j_Y5MXyT)m&xMjS63Kgap}I%exinmGV921{SXMd!Fz{O zwq5DgyiT&43R_frmVBgwl-SyO)BuSE+|m<&j!r2w+0F%U^fZ(|P6Zs@orbDoteXj@ zoi09H`NBM&n_5ynuZr;uNlmpAm4P+qeC?$vSP`t$PEkd{%7jqwR~H zyHDSiHv@%By4J~>9v7OSoYvpS={mcUroLgmdY?yNGG>-F=sLCNHk8ym%A(r;-B*L? z$Bn9}C=jC=d)42+yD4?vQgWq>TIFw9A6&=nCFA`5(#DI-qVe;b7fAdV`03gD5$@3r z-M3%d_ElqBEas@iUO32nlBGeKrUmOgW=t>Kf1s~(1?uWvM%5R_i9qBU=FP~p#Sq(< zQ9>9h+*eUH37UnfHYzY&*81kpddrW=b~fA53&g6}DuW&6R#H+Dn$4BI%C#E=?u!fZ zsSPq4kZN*fwCj*3$8FuFC?*W%kXk-McsWNO94s-gcEE_iCG|HXmWZ|#&W}!RH7IPM zc|o&hH+I->w{J*qz)ZF-?VcT|HJ(bg%_~1?5knkW*mX9E45{|$~UaV~DXh#vv6qFR( zn7_|(ogil1`n|9L=4C-dzr%gOXLjGz^vc4`qa@9Q8JqhjrnA1uc2P1h}WY-m7&y7*|` zrX|sFpy{4o`?k8022|GMKUREghJPpb79ZnNj!!6KG)C9SGWjRFMlvm*9KDL8t%XOM zE4DoyezD|Q_)6Ikbg32 zGDxY%5PG1T!x&7F_t8d1F@dBd$yGs#=6-6C;Nlc$OS8Pop*qd=dW>Tx@7S?pWVrf~ z!#jR|3VvmUgfa}PQW&dZwEAP**OKaQqVH}C4L%c9;&*Pt#BpV9b#>LMi!TcLyKo+x zKS$6tz0xRgaB6CK?WjNR=IyRwpha%5!nzQW)cJ zB)s-hZf&^MCH0G=EhqJ|R6ZEd%%GY-m^Sr~nQ2ZPK2B3$l4Vz**UOKl#Z;t5Myyq9 z;a=V1u3JJq^Qo>zE14^4a~|hDcGi;W_8DfYc{{D>@krLj9Wispi2WTLa-Mq*r ze4~)}xADVHCpKTyQdd_mH=)X`gfIRUv%ShK{LYS?I+6Nt*f-x2icDy86^jaKFY9NC z_m|9xB_>pEeQcOhcYrneb~2&alQ#vaYhzwUx!Z=uhvx{ zy@r?nde?5t7k!#4is@@}uY56PV+Z>*2c+h#0WYIsDE{pMneFS>uLrXXau(Z^8=1fN z*4&y}^cFc!L&ijpp?<9bmL@rD>q7Ip?j9np^an`Ewz-;=n7QHJXJwt&khUDw^Nzut2TU90$}^GS|*^j{2<^vHNkckA98RU-stmYo^h_HA5p)`PY+ zYhrEIjGD1n{9~+U>ixlOQ<-mn_Y4k-H;pS?_mELOdBSy+%ym_-V@XL#wYeF8j$trm zJ7wD0X@@twGY>@5u$Y~H|CP|!+htc0w>$IFhj+pC_I zqTpZcTj8#x_{P_2_k|V4GxfZU1Y#T=Zkl{?s&;#^dmt~PH<^xP+C~2es?i#DrmlYF znuS_nd1`#``;3hGM4U)29s2wN>K=ny0-FwKDT|TG6K5(n}c2MxBS77h8T8wRiVPWYuC1Ia`;gT;TE1*e-Aq` zS&1$NIZ_*i!yBkh7bpCGS#Uk*n%E6TF; z@uM#aDC`a`57;x3(d}&NidUUg(n~{J3tLcFo*%K4`_L`ko1iF%GF$(CVn6F`?@DfT zhF^{BliniOrVgnS#-c$DR!QbZX|f#&_$9TwvaT%Ts7@G#q53_&AM%_g_HQ`^kJD#IeNBzajwI`M5iFt;&(Y$wkp}w&UvfYQ zZ#u`wOl3?4K)-@lCn8+5?=gZi$#weZee<|2xjs^VG<*)Rq|#S>pJ38x7fWMYv45*1 z>?l{b;DrK1rXSVV)WzMRpjN2`hkaxf6BQ>)i1k$!Py4X6{=?OMDO{&S8O7Z)!6-Ff zOl@)u3ko9i1*p{Z^|$C9Ne{kvqBvbI?qkm}8h?zwJmWBpYIC$5=H_YU&FDPbYp-aO zH-mep5Dysv=d!|*>Gj|1qL7XW=}$Zfsw@0?N9MrC`?0l%B7~Xsc#G*?*`b8ycjg8u zDWW|cKR(3Vy3^8ixYyvUXFs8M?001(wTglsY`?XQy+Md5#PtI0VfUgyP+*2=C-32y>2q8!8i= zw^=UodnZ~Pn1C3Tg!WY5^0=}iaG8}cX%XT0@G5?xcI9*h%O@Rh$aPn=VfwQ%5l{GN z&I2p=z)qE(%pE>5LNdU1z$UY&r-o8QsX5UQJ`RdR!&H8#e!Z^bV)=(D{)aoKNTB8-{NS78OOzBXB9 zE3{oMIfB5QcJjgaW7gI>*9JU>bLamq`e+@*J1=Ww{$Z4Re6<{G9M*zX);`fVN+xpn zqJ*IDotV)qgo$V&=C5h?IqGKZcGSZj9W;ERR{WmG?dW`9THv#2hk;ijdX-$D^D2>s zM)uF=np8o(QhsXFoZ44jICzr3*kygfU^+MFKasZBXMko4LrjVjtdgVZOOj-JKMVEV z2wM`JRF@cAOJ%SmzzZwiPmPPki6x80>}{_fd}i*qR0 zD3Nqm^V9OsfPjF6jxSfU>inckRi_~ssU10-_8N|zi9>6%%3^zsZMTX(F~?e6OiUVg zJ)2s>KC!Yk8+jOR)V`{4!Gq|OUR!E^RBdxzGju#f_i#N-52t1&JyF`~)J3we1*0f4 zU7XGHJ_ea@tloab*XHyu`@m+g7qH*H*aiP-_OkmXw zet&tvR`Pb>foh4S!@D&>WUnWx1%=yb1y5SzW9>#Quk>`?dY!w|`!=P>IoNl9^4Rly z?3}@}i4#VR*&DcQXjG8tRAEtza){*SvBfO=eKtBdK?eyu#1&z9uD74 zpe)tXFyM1sU>^mwl=_;KB$D>Rdb4`FcG5gW8|j4Bj}|7F3jVgFB)P1GD)-p|o|oor zG|ms%5^4^8F&iPgF&*|#zCTH6Kc8|AhIMclcZtePay`knOlpFUm=vCgY&c(FlP2-7 z&RsL~?T*EsBh0eX8_tgQSg_vREp)xROb4sOCf`Gd@s3UV=d&4bL#O!cu-1>ZD@E^) zWoU6#LGd^QRogm>9~K|pNc}5KPlgxnUmBIt+j*rYbzfs;CJmZTFYA6?)||K(vqu-( z)D`PJK5nIUeZ`Wu9rYMa-~MW^qJW%Dop=&?SVrOo_vgQT)W4?+aKO|3MBFY&t4}Vf z)?rUR$kcRd38QR8!ERSH2T1-NKq`m&F}6RQ^kfX{MkUkuX{yntHh@tDnF%SaR4tCd z)P4zH_Z&td*RCHyfrij|&KY`$^) z>vbE^I&|Z3KueA%MoXmq)L1VV)Y(!i-+v$W?;&i`d_(!=t(#p)O!_W1F*o=M|KI{$ z406T7;BM)i&DRA-D|H`o6H#jnIM4;^v`WLW`&mg{ICAVxll*61|)LQsdEP+)Y{+2 zbMC^uS86UL$2)61SC4X`o*~pD;W)z5BqrEN^XR=a4a(jXVcietS2be#3KJ zsNLy%iQVOQ#~vyD+{?i9~iJ$Ay_K{2@+2VI3{$a%ZmnB^ap&^3BLNC8;*mpB@R%q1{{v{I5!_wAjr4GNDdMG8kySMsl=Akc1dzZ$w+3!7`{N6nB zy`y52eL%PZ5KfhvbpBuFE*Z=5W8^#V#{r#Q)UC{6Q@xMFt`+od?n1;q*_V)IE z*F1)~r?d|mXn*PBj;+zM`#(q~+SD8J3tSvbFoWFOT=ir_J-x{Ygh&4A!i1c!9LaRd zv}9fkIl-^2_+l#4xU!V-9NjoL$a)*FAL!0sfvZ@&7hihdqZYpapQj}_ex|x0A~{o%p>1Nf=_|4dda2tyB%olb9KO|#}NSkRGQ3-pV}=Iblo zrLMXCH}YvnolFn3O@_7q7F~-3egAMy+`xGRXM0asrt;)tzL`SYr!;>EpY%DBZHg_n z@ZK$U3Nq$@L8`p)0<@=~`H$N~?zir1z<7nEbVkga7+tv}LGK z*|rNqMSp*Fd;PDZ;@y$|d9wU=$Q?x9KLqZeOcOdcI(}=(w*Ml%1pQ5pdGip=Z*0LR z|IpFU!7Fby@6+MmeHwas+=$;lpY-kiUzPUHW+2G(|0|`xmc(CbuQ_B>%+Z=$@*a(; zPdrlJ`+#|ou`HDz1$@G?O3&3d5zJbmAk6H>l)>M~jifLubr{cWBsv?b(dzab;Q$E@ zN4Tf&g>iSE#v$Ew{@ExwaSHnqa&4MTvDJxdJco~I8$elr`E)DP* zfqC=hZPC;mH+AX$bG9wt*1|Ks1$fch8>`P&e~h<4a!$^D`4`{Gk~@{dl#b4_WXuiq z_4O&B%sOO9+l)ouUpGP|z4R6%gdMfOC)gJ9Jxg3&U2kr=wT?vgK427&qWkbDh31@U zc(3Gly#+wezxUY7dB4<-^T!(z5#r=qvDrIHq9CtAb6{wq#!}1DX{M&8ZzJ^M_PvkL z2crhMU`EJV4BozpUghkJ6aq%gpFck&rlShk?n?EQSg-!3(R_?XK?!nVH$EtFjVo+yET|DP2JiAJMhMEO+kah%Q8#8;`i=c zM4B;_Go_ExoNPiP{`%{$WoTVm{yi?+ohD`&AXq;#uWsrIevPh3qZCEk*6&kF& z9!Hoqxw?coZL5E*EoJiE{I|Qho;waaoe82eCz90h-YBg1JbLvnq?BVj5NmODc{qaV zvJ@wBQ_qYRnt_7~f4)FW*b^Ie-tDK+QM6R}cPZ>qwy`>d$V>Tej@})ZpiH{7zXCnCh_RglO*UBEs;<;_y5Op}1($lJX z{dL=bd-$DxR~GyC^gY=D( zHxzCIzQ(w-xu(H8+CKQB9lypB+RMj?O!PG#EpzC&Q|b|H#;13OFW(KC{yFkK6@L#A za>MGs{3um)=uEqBmRBBf%l&21^|7#s?jU6)YlvRrk4u3lX-eqrtgU!DT;f&Hb$nPy zF{E;|^F17#{q+c+9?s)&&o27=b{POBEZ~sVcDIcpDFleU)_g@4)!%W$ED+aqPOQFj z^&ktCL{rIiYhb=DCydwDyPIFDI5DD@NFi9EUv4_ZX@JuTy;4;sbI}Z>1?}aIHu6=+ zI%H=X*A+i{o8r`$fI%IN)^{KCeNaOFWC36&Q|BPKi3CSgw<7KFe)J&*K6q=M$>oh4 zV`*j&NtJ3?J#T!Rj;NF(vi&*^ZkonxLNQP@=N8!HZX2x3^m#tp$AOo#YZRF8DZ2$z zdo3X62rNmFl{fX5WEuINsr(J-5xIP?&|EiIVaHylxd@naG*&H9cz%~_W!^3$tR=<8 zMk}@l-C3XM|CkT03+B(yYEkm$XTGmD1QKN#&{igpAycwPO_rSb1g&K=ocZ`~ZuD97 z7Dw>mzS-8th|9Cl9zv~3JpQ@rx#CDcnRA4AU7Rs(>-3ZXjP_A<2Yrs#xduNR5O1Ak znbKn&-xewEH&~;IlI!iCM?2}&H1!KoVmjp7E&!V?i8z!XVedc_&%5eVD1+{fpq`eQ zyG7I^Vc=nn-ZhAUA#bk-!jJGuD)L)lUSD5v%r)Dg?g*Kr`+!9lKWWl>D=VwZSFSvV zn5MX84AL*YNbrzM)$VluM5tJbzmA`%Q*SdlYpQdiDFnsaXrq)5K-_pc9z>Lzg0Yo* zLa?7^TQxK^ZnY5>ZSlUGAoF@LOD5M6nq{$7d75gVCBEETTOdJk`f5l$(l>%K`^G@( z({Lw}4JN(a9h4cSSk@y2nw&$cIo30*aWGK-eckCpu&Ah4_bza--&> zgGWu9OnFT>8uxM)DCJ0xluiLz)!Qg*C)w1xd zojG09fH?>Px@J>)qT#irqcp^s*Rj5Z+a9DPSXCGU>o+AEPM6}ug$CpC=Bv&p$(d7~ zkJez{NJ+UvWw7}Q8W*;D)biT~wmx8B$Tj2c_6CyHX>mx6yCLbc9*MiKs)Mv|Y~U5m z&x4Agk4nm4%a%p_+j0#%6+k!Zp&82`Q3GVk zffF-a{nd_)Sgq%8x~e zPqV|sC_C{~dhOb^WO=Lw^g6s)$oade0aFJ+`!t}`-afP}tH$$ES`K@C{`eQaz2!(J zMg06~Zcftuc1G#&R2tAw0kq6HjQ0`=Px*U-A2JQ3YM{QojvvHsSYeoyRu*LWOb1pJ zLc-lYP_%Tf4HZDpd;tt`(k_35!A&WeMjEU}+eT&sjroE+{joKkkAHAl(8`m9pPtZb zA2kt#p}gW<{Ggqnt%K-}evs^{hOByGMdVA4;P#0I^`$W;>$}l|{sIiaA4ep}sjS(` z`V;ws08BqtJ~c3M+e3F4F|xIzYmmT}+4IWxV*C9_$Z8SCdxM;d8;=6V$AhOww@B@ZZq7<|B91@2(hdrVU18F}h%ORT< zYGfy&#NGcsIV6K`$TW?-3T+pNAs+z#pF`J}e13Ym;ew_893=03;@G)dRFoo+4N*J~ zdm58%gGcGv26ZFd>rfhNx{<0rx{i9l2HED=RaBs9b;A4M!-rQ8bQE3m7kF&dzRr?*EJ*#H2TfFTU>Zifvp8`pqKnHMRe~84@yIqHPD-h)+q0>46OT_|*=f z4eH~3-~63u!>hP##Uyo`7dQ};*ZxZyFrO=$iFq zd`w8KI`aI1T z6dBDzS~z-MKu4`nU!uCxRS3kfV<}F9Bc2zakF4kW9`HiRVL(d>*qar(30Y7<*@M@< zy7Y1bPBTj=b9lV1#6~Ql?R%j#l^k`CygZNP2UGacJB4VE8!&%NSC14N4eEPm`xW>K zqNEA$%fKPT`(Z7cnQw}IgO%5$0deWCR|YLc+2Pt=_){J&^<_#iy`^^brX|~8qfI9W z_7v$om$!9&(@hZs$oLITb}q*=@iYY3;T-T0a|0eB{d@}ydcuFc9cjqiENIA7#p6g1 z3)DVC@)&hty0zCA8r(lOYxSAA0huzBnD3kJ@QoSUa9YBCR)rr?HfII#5GpZG$YZc0 zHNOjfAtkxJw^=~Ws|Cm}&lczr<3!_}n>)+;ddl>YZI7L9p&S|@j2AOpVnv8$l3A8H z34u8~MiEeoKe)z{`#=Bx$!GjsSAwP5Y*1sD1r5A6dpeA|YW}OevUw!N|&kvaC>y z0`*60?Y~eS>euH(?e%m#mx}7wh={sEC zcOJlKzF%Elg0v_Kfu`{`_2jb74Im(6lgw)l1sr4}8_Eab5!Fbu^_Zc6C%-egL;~sN zyKQhRUdS+tt(cp&IL2`M_GvJKUxqz=i~;bJdRMS()zTAMet0(tjPO!8O|7B}7hV9^ zU?v6>=^u3XmLK{S#3`??%{nQRVkHGjkp`S)I*L?oLBG6(;X^hxVUFK|2=)OpRJs?Z zQUf#hF}Vb%TVQFdfjuJyq?GAK@$CtcrA~c4A0PbpX$(E?jxxqTe*$ZH4)nKa5rU)UJ z2Sbv_>MG&baGn4%>rxzhZUzO-tbHT~Q;nHf65DlqB9rQP5YA2vxHC<COtO84RCRb}U#?5#=>bYLMgKqUW(L_0r#A|%$PN6$UzWR^96@O zv^QAxwOZ=8Ku&f6#Aux^)cf-+3toXa=dyPQAR4-cCrsayjqtIS%Fw8oU>k_UaU!6s z*-dLEfCkCKqe>fi7w6~*;X7>kK?=Fq0QH{6Frn)D+WKS>(4s=R5%6g#eBzL31I&We z=hKtcAzV_P4W~)5rPG%vvYDmG(|9Q1_vg=_zXesd{Q3=8XA})fllJ>EkYQCFU^17$ z_v?X0AgLcl)YnByoP55+RWFGME2zee*loqp>M=CI_1;~f^#kE;0z_01GHSm~6}9B3-dgYBj*$>L+l(M741vy6jj;Lgamno2 z1S%mXkDRi|_ae_Fb|lIG^*N5Tg$d+US3bfGjB@9Mcg=_m$G?T~Gp;s0J^h3qe8**o z^KIXykavxlnaAkG7_S8|L$N^(3#*_4!1uI`AL}p3mY#zJrDazJVbk> zpe-HEUc|UiJ5x68D&QBKz5tF7i&+5=KHj3|8&&@RXMFi9K=2+YY@Ia&Lf7d;qsaqM zt8Fqs-7YOBN3EDopbzL)tP`%B#?*o`|_) z($z9lw$p5757hImLnaLl*~GUHWO|5flA{m05+IJ22i|h=-Z$4sC_UW>N2_eQ9!Iqa(`U*`0?Y@ zXu=M1sU3Kx9%3FyfvgrV&;BIQc~zUp4nZOg)`S zV=20YYK8TPj|pTygyDyxp{W$ZU?F@B6&V>&YB<}va|8#CvF~Vfvxx#aib8*gu-MC( z=g$v+M0){Qy|BVB1p%z6{|@HJ#gU4{w>r@?if z21UO4@eu$L3Dz}PYWIdJ$BTW47ZV%4XW8(gtP)>{7zOgo;6T%q=Y^^pHwt9$0Ibmp zA@2Gn2N2@9b8t8_Xotw(I9gw-KyWkIZj-_yN!lntl8zzR^P_mG_(r%n;H!%$8<+%ZkL8}<3WgD{gO#Iv0Tw2k+(Ar zrScKAP-x}lj^2gp@Lwu0LemXlzV(2$O9u!^?@{yq%Gzd*tZn95v$_#PnUyuouMXc* zH~hi`wO%q~x&nc_lO)U}kzV;D6Zhr9P?kol>+hWG4FOIwy(tz!bId7TW?tjB2A=RU zJi<6H5%on6bzs|2S#W?zm>`H>j<9#aoBYQUgg(ASTwL4@0y-UhcnhJYDcS14e3812 zs6%M9<~{)DqJ3%rrj>*BTyTBUV_#A5IhE#sBQhi0P)y2HH>FeCo0KlIA*I`X;b=yA zx>wD%At*At?z3E~WUHU$448Jpc}y#eul+6rOMfbIz~Q?y|EP21CnLz9v9RqWBw{oa zl@&&PY3r4tWbN|h%WG6rR3Z%GMF|B;ayHnujH2>LLOh3SHwllPZM%-*VPpdm7WC<8 z%f9b>l_*kHc_J)~6#nW(fqEYhoup`0#VLW!=a5;~Ieri_p0ICJCLeBp7D2qb`zIO$ z{r{%=U3h_Fi5v!gc2w;`G!Mb(fs(~u>BwCX>&pB=VM(s>V6bqdb5u)a)c zFE!nun$LC=B3?Njh5aR7S5-*A9ZOb*E=~lqF;{v!enI7$+Yljp$%7b3=nIHxc_B;? zS%O$%65qaQs8`T`Js)&cKPjbsEo#A1iVa{SQGgy!y|xHA{T!Kv@+cp+qJ9P7P%(K~ z!V01*MKi)$s^rVA&~B+Og%@uOXzRPfZN%&t6n+lkUi}6Rp-4T}Mj>tB3f0+dpTkU`WEz?cJC1HPT>~mVq$85N< z=e7U5_qgR{pXDeu_wCmqiP1<4AeA7177QEYbrJi zB;c&JTTr>Ar75sa-mx<;aF4uA%RAi+m@ol(`uKgI7U%%6L>K5mumj2&Tx&3#C^VV` z!p239=28Xe!2^{qE?R+_apn$lESV2Q2xtkyX;zVsL!q;13uHo#ca7!IHEanHMYl71 zA`RkQVg1bw&<8px7zQ82qY|M2^@(SnOH+bx^WG4(zL&3truHHLlfQ{-ZOM|Xctjv! zGWVNKV2yUQh#T6sgd1&=mj-ilZb$#3y1uN)36myez|@3G+=?h(kUUj`8TTM05~Zm` zMz42Akqvrfd^vhXtw%S~Ks!{C$KgQ2?@GhfLAnuo7xSh_wOE31QOG27SDMl2LRLQU zE49pl2s4#$yIyZEf?|S1c{K!`=9i&N@Sdn+0)b+F{PZK$^1v5dJ>zcZ z3=l#iROY;xCtym^7IJ;x;dI>g9&Twa^B@9@d4fQPY72M_QkCnn(^m+9f4T*+r}PDP zuU(4k@>#g;ieB`qtFM_caBja{>O(UK7ZCM2B+ttqA>osOT98JWcS_*N)}^q$=8KC* z9Lltz1QrtX)ljU#c0^PiD1&^ z9yK%WLE&hBkR|9~0^;iB+sZn1o{P+L{9$3lCcwdejWUJoqThp=mmwP|5O^w{c55L6 zp8mKC4?ynLmzFmuTU&&X?V~hlf~E&k(4MigKvLb<0fAucI`X?i!7@{_WeyfEyDPo> zTMDGFY8zBJ<9YBj0X>utyt}I&m_~g+C>&xLtAv&r^5Pdi{ z?|qS1F6|x|6blCZ(Rx>@X8}zkbyFWZ z1@+%FRdb7$*5$jIy+Any$;0zPP)_J(*;Ov)$!;4$jmF9PaeFuqUK4b3)XVl@YdDe1 zuhURgmzJ zl$Q}R>QH3^9mU8ijtX`xf2xp>%iFk9~+(**|x0zfI+z$ZQH^ABB1Sk_5c%NK^;J^nxnCey@v- zjb%*?Khg{wg~@Krz0sQ$J1WyU5e4=1va1IkBdwD-jvJa){vn0PAywp4p1+|OiE05S zw7v=NZcf_{rnS$dju)^KH_7M0!x3%s<^UN#nW!sv>}K~*4IX0Lw}l|i1$hI0!jCqt z$qioq$PRz9X+3F5tC7HmfRrEs+4Tw2ZB-+(QAPvTRx{ED-lQa1rD@W@21LAN({H>1@?|7C*5CM8qT3ePe=CuY46&@YRuR6au}v9WHcC?hDq#V4C z6TUg4!FsYkEd;3}^EQN;PW%Juq8~eUGA#5p{B;7!FN5-&cGga|jcP48yF!a4q|6m7 zz~)9{WR%+JQF@p)*^u@DDgPpoI#RfYaAq6Q2K!$HPW5;I=m6}VIqzD@#_R~befC2v z!cDOi?QXsT5w%j~dXrEaLWKyC;YuBO`A^J}u&qJwxtBU=+@2xS#3p0>K}9mgPDo z^r%Q;@kJ^Cm}llvy9A5lYmhuXgumM}{+Y0`zW`ZWU5&d?uSR?C-n~rtd%gR zGKCh;=&oZp?K0py#2ZJnK3rmWO83jB>tgg14J`E=tmcAF;SwWj^?+d9_eo#>agoRS zgvJ=)=ei&6X}?4}V6oILV8AGf^&F&L$*DU7f^i29^zjI2i$xAQcI>d*@^Ib-1e=t+ zRRD8bI&XZx^{tv9Y;~!iA`;0udfD^FreO$Z5Z5U+55s?@K}g$2T4_o9j1eyWaoU$P zF+p&-s{MW`fk+79`;@%k5wkRbA#OIRl0VAdfJ#mF((f(EJazv1bxI`+L?OJeWf6;N zumogz8T2|B4BG7QhfF%)?hz3@{gh?yEBk5 zRUv}0rmj5OC594YL3}$cH5>lh};q$TR3A zE-_~Tv$HlP4dI73>q-S9Z3xj4wTl)T;Fg;)ns~S_o!4V0;w8YvV2Yq|lnZc>agGmh zUN#0f)Rvle5#=!mXt5}>`W6?a_sDesn7^NGZ@f3yrz4X1zR%;XX4IOPJWg^jv`(@g zg(|_Y%mAh(s8H8oVPHf=5g~uRbP-Xytpzr9Q~}Aj?+589Qt>RL2l4^~u^NRs5D;I# zZG=$=(DfjI)k#I~-2pu~VtoS^HS65O9q6$7-ZyxHDQy{6#W~O1irT+V#b5Bp0Cdmv z?=&@G@iphS_wIXqdl}8(CKDq8BukFGg*sq-hH%Sa7m|T;sN%TiB7?ocabwBk3*I9f zhu`1TNJd5x`j&t(+1b?sM$=UN7Qj&Uc0jfpZb6C(!>D(S@rN)sL9Uq_8F43xVo@3^ z!S^RL0*EXT!UvL-u-LcZPwK1(7t%VsSwL5y`5?8qmOs%O}p9+46MtaU^ zFx|T3nD&hs>s04@dmtcg%_wbZg0(!qR<^re<7;(GjKEJNK_$~f$SvKB%bhrsjGKS1 z25Z6Sn{!ej89fBAXq4%#Pm%}{Hda5!WCFpzHdJKWi488bw@`bQ=w~oWUAD|w7$T&bq6yd3au3D+L`0p@$T2bv+P{g@ zT7}$bb7y-~?S~Ii30|BfaVA8KY{c$I2HPQ}l+AOH32x2Az(b|iF&+1V5SY^>vIDf{ z%*9SNWUytxZC(4WPcqXmA*bb>mLOdwmJicxeBDCaAHjYQAjX5}8=At%hbpY+7tyCCJUWGb+XLZ6^2_Fh`-o(^XAQoXsBT+Sybcr>Zt^=kt;o|wcX>>@MZ{y z$-%#>Fv^J5e5xZb`HB=HUazj$K2p!0UvV zoS4qGDvE%TvL@BP4gTdzN*du)d$rEVzu+#YFQg=07Ol~D=f$6YmZ59}ejK(xB%OzK zAZrh(X;HgWy2YB@TJ(lOKqMJ?uemdTvRWV05Bx_^$i5_gkTd zb_p?SQ*1Gr9|<3E1vBks9`vWAzLIinQ}YP(z1}UAk#QJFv8m~mdFZZ1uQ4i({WA}p z!^S&*<<(LCE^W)zR}l|JUfEC}QpI1JwdHlTSw23qeDc{eI)_={@iku(N-rfY9VhKH z=_JBNc^vSu#GdK0Wip1=^O$~Dx4fntPauN2-sGwna3aVp6$yVBB6vGf7IQ{Mfsf57 zJAFreMItC}1ya0wjT`Abbn9ufoOIPG-m+|sK1`u)>#hDeS>QOSv)*1Af(InCFM0IQ zRGNDe1E@G2^+6p_?<|UztVc98y${;=R*trw0OeOy64+B9R6M+q8*6Vu!_33i=p%ux zkkOWbG&A&MwVLA9Y23nwJiv_uAoLjeDebM<$PYP6`%qR|`Q5=UIIz1x;1W@O*eutA zd%s?RD-XimWD7g0gr@k1_BOXUvRA}InvITdg1H2kCS@&SA$it!iz$k*mt^lDfy^PV z<};idCC!n)DI;-fV~rZYF>=1R0h^KQj%K?H{?g3Y*w}O@m?z`7pdi7q1m=ba9yxo) zhR3l|*d%iFWpa#&#Q0XWGVPI0kr;m4tsh6#HEf?0H8R#sLf z$f#KIY$!ZG3cL3J+_4D?a*H83zDu4PL;)u>E6}o3vP+_M`D_x01SiilyHCfZgZv zZ)dg2DIVpo2tv*NbHsW~$e%{6NB?QWdhVY_tator=DYq+Gv5_|n)&|g zhPqz`zx!*2{yU!BzHcCF^3T}b3sz$t!@k@QKDguuwJj8^Q* z+-}?VTnoMy-tv{H z=stCdWEx`5*h+K`d4N?U>Eiw$sSUEts)Cu@-ljUemi=3s^5%N3=_gHictP@5>demIpQKS&Xx-kV&R z1$kzSQx)4Mt+2MvS-xV`5Xg4jxnU*$G^6uMr&94xvgLt+o@sLj#C~P8RveP?p_huc z*&a@{PurP|%x&bzFF4%0Bqo1d+N$k22%| z8W;mg*K{RcgaSG$mJx;okMX|GiZ3F*G$(boChd_QhAa?xD$lkUa~tt3;-a7KC;qiS zc98O(6K`v8C^Q3i3D1>b2Y&2Qq!5~}d}QJfFO+Xbc^W|Og)KeG7z~l!4vrr0L-}N2 z6CQ_Ck*Ve&Q41S2@$=M;PiM$PekDanD`h>Q?k7{8pdIS?x@TsGJ+MnGHlw8LUQ9Q<!8`izKqJG=k*+$7XjB)6Ux86u#oSSW^MH5BL4AfpV($634q z&rs_E5D61E0(a8~WOJ-+X28LL<4og46y^d)^GMlD`PvzU{mrXuwmkFD2J9@-2O=77 zeJQZBwjK&WFZX2yTItQ@y%Sn8@V_A0@Fm_d>291*WJ-Z-l~h7n3F(7d-u^nB84OCG zefPIRCT$)-l-QJ%ElDepd{D6o>2vsRixhV-LmAOMxwyDBF;?86j+3DT3~ zuicSQl_TYn%|u9A;W0EpU6FkS{ChV59f=+08)aV}y4T*EIZN58F*x`6M6`ewFXvM~&vQe#7D4$hWcPB(1mu*4vj%{a_$^9Iwe-^xyBOK_F zw4!U3T$F)TkaeUrHTOF}O;eSa2pOKN@HiNVjCow#I^k&P<6`=3plqx2hvo=(8+`fT#zJ{C38Twq7c`IvCAee9{3q24QqDZd3>7-tW zqMxBp^BWwIq!o2e%;9wT<&E4bJ0>W;7X(}&XMiM_ny9JMj>d0!@tAHwWkPi5VG0Hk zZO(?Vi#`4F!EXx_e~rc=a!Ygh0lctlmF}BOL79-{(+I{=-3eimSUdxdd_-&jHVy_> zbG=L1W58(daDuzdPp^bc71%9ZN}kMu?yK!(!72MH^SFraXqL~bTm3U()j`BLoZBHb zb!R~-qXq8My2gvCK3n6msVjBiE>@@y0i6<5`(o(O90Y_lfD1X0%#$3ZfTxE)9Lf=4 zkZ{&HH(F7LDWw5GTQ>Ma;SaiY-yo&!i`SEziUKjsJ_g7Q%bZFnhXpaC`?N>H+}H8p z1Ag<3`UuQE{@l88@z?QLmr+SPGN7U%<@8?am9|*0|5M|I=n)ba$eBx?VzSZ}?LHZ} z$nMV=QVI2v}AhhjT;>*!xa3^@A3#)2ifI28!b}U(E zodD*|q+XdEnE^X=-uI`3T~as!K{7Z%{&vjKT91uL#gmN8e^DCvu}2xOaT!Ia3em`wJwz*3QTuy=aj2=p2qT~sMG!I6h1s)bXV=;zegTN zmSps32J>a1Erfb~b9~_3W^GE7d5oy|HwMX!V5jEGAIe`tnXPC{StYp4FafU31l`52 zD#r@!P|#lFHVbZA^c|9@SknWK4a<|>Y0K1-1%d(prCbt~g~J5zz&I&7S#|2<)o1II z2MXL^8bz&O7;Bek&qou1B-4nkM1J{|`J(bc$G@k`ZzJ=|-@uStWWyFl8Rxw3zquUBShTPuc2H1~aE{rS7ws?%N zV@J_WOdN^xw`0G#RFi;8#Yjdy(Z{@tZwxNIG1xA@MA-x7!H}UR0oR@up*Yq8&VC4? z35e>6izm(r-jitx^aC9qaEfT{GH%q|dUG(5C)h-NrPj5@%W{8rIYfI9ZW95vAO|!% z?w|ONBmh~_lbiMR*s1&#g8cX$2o9zUgDrwyE%XUgzQ;`c7xdi-3YsMO@5aI z@G+$Uo`0;;vNkFcaPwR^+WbBXq)oLkc>ZO@i&K%oA~N8|IUu|ZLtAh5$);KaA-EWs zx;X|&W|CG);_q{4Jrbz>%<`HLAwIuAZRYyW2O9E~HoB-d?g~&rJXjCNqErMchMAn3 zn!EF7_G0Ks5y_n@u49-WiY0AAYxM*p2U4VgP3Px;rzoWmeEb^vIdpPNV<@7?nckfH=MSnWa=zcc z$IvZ00;C&y=qVk>qJ&qg`Da)my}!&uNf7uqgRVah(=a*rJJ1O!|CgFuAjcXZ0zhc3 zYu|ZPC=*z7^Q&t9(uV5DGL5HC5LQwenA)G3-$4n8>8M#KdPxZi*}DWt9}CCO*S8Tv zJB}EkaJf|+752`Hog$Kws^#b22?Td0-fNIAia=nt8}zH0@S~C95=^)EPPlWP{i;pv zAZnVg4@<+aE^oQ*eSl#wx;?iMUN}F*PKYjB8{ zK4-%@ap|pEf!w$F-%_4@Yt%EpxI=BTcd_6(I@KwZkk-&PpM~U9b`}L-c{7u&6Z$@D zfH2ibCMU^IQ?gsJC*D4?K{O90=M@7!hR)6f2ykX_#*&>|Psxr627LUWyik7b5^QJ; zoFIbRLm+s3yj{S|jzeV01dqj2ouVPbZ#XyEVquq0BpWZ$I0oQJI@JX3OQt+2KDrC% zJ9MXBYF#g0pfYjlREsW$S-RA0)DWcAi*1Au{)fNQX4XLCB(PlL1;?DXpc5M){+zm7 zry^O+Jft|P5nkXf3sX+Ub~#K{s&`6?P?}QLNyQ>u6>|m$DM+ytMjDYvIS{1Q$LmU% z{@GeKaVUykzY9lGs9a@bZT*vI*pMM#=`Nm;UmS4_U6*g`hn58f!uqn|kMj+Z(SL(e zA0{w(^`m1fvQ^bu75TL)6i0re$9)8ZGtEtD@c$}{!=m4~#jgTq;G1x#5{?#L>_ETL zDW#OHf=bEZN!71!7RaxV33ntDW9BoKfG{7yu^1D;4A{x43DKSlkc8p>h7Ci=Tf2Pw zvv;7&&nR+-LIQPCBN~!?Yg|=p6!ES?d9Fmhq&x z(k*v%L}wJ$Qi{OV5Oa3gMP2xazA|7>k)o_vR>1r=TEph`?tha&0SjgPwc74eM-cv@ zpZ2=@2#wgM!{T>t{MoSY%p09Tcd9-d5>l!<<&Hm4S_z-vWS95h1Nv(Uy6B;*+diqa)l zU1`rY1puT|8mQgLqu(kkD^(UpM03E&xh6!|=9nYpc`2JwyRpGr&Iy{Zu(06hYbYOO zll2_Ql0L_BM;-EWSkR4Nk50Qr*&bfZz(AUOY5e#uBoRl^o# z+ycNa!Aunq>c2Cv1%DC&^v?VEs7qM=iJF=VY=jt?Jlo&AHi+zQnNqV2B^hJ~m7$SB z&Q2^=Sh~v%J%za-je*qOHWuOlCmNq(CN+yZLIMq+4 zxv7NRJv5p@hb^Q;&`XqVdAU1CRnMJ0zq#O2Iwe>W#f_-_)@cZ?Cvo%%ozH!!0-fI8 zL*FHvqp=U)yJtBV9J4}%{<2MB3;`E@pT0jp6UrNTP#nCm>TEKWRA*06;czDTN|GYV z9buOOteQ=k5&SHtr79+-E*aKwRJ<*F$O@hd=oYSdkhsjUlJZa0qEIuTI? zX~=L)LrPkCln=aqG-WcFA9lX~yfd^e8Ev8wNZk{~1+bCkDzvzQn|jMHT_4b$bKaj* zEuvBqwK*Qb74@1E2Uvz}v(GG#tSVf!eU+q${AlDphKV0|?oSAEJvN;%fW2$Uy5$M* z;MDT<28Wka{@ev2oJN`C3Kz_7i<7bfS67lwWVexdXgzY1=~!k)5Y~`9`cI)V$Yv2w z%3GeE1n+qPIuLsj^u6H>f=C6n!9h&7c{pF5c?{DxO8dx;IfAGT8<^l*=p||+aI2Bk zPworHS`v{Zn65py0D%;x{8SJdlhZbU^%uxP@Hng{YEYPsr)8J_^*50nSBGAgwGA@3 zCGY$LWF+*_&p?XRmqwy*}+=87uO;?tW@MwD`NDP?|VwUlw zqzDr0al+0HB?7H+&h)(EDuS|Hp0Jo8f_#PHLXWUE(8+=$UX%hF`&5xUWDdO9KT~cN z0*yDW4$_s^k<0m{*&`RBWCctA**|I;l5hb+M0#O0R}2qMF%7S2L*#!NITh=!01cx#XfEh~d=pX(q|4V;6k6vBE#rv+IxQT=J_eql-#0A|D z&uL5D(x~u*rM0pFPr7=K^3z``Ki#vuwK^#TXtGaIA;B!jt&^%Wa?xQmg~8#&k@Lmk z!!Z{V+Wq01l^;HPI)^Ju%S+E}q&w$bIYVQ<1R$^jV*-MCDSqL(4qm3V@zk8|ZaDvrk1&p>lPslP_W_ z*~vLTg)XnCAvb5hcm>)}|IemSzRf4eE&;UL{Mg`YSrw{+(SJ;}H~e7b4x)qnW6VE8~q?b`L@)h1niHN{W-2mYtN g=3f{2f4(LfpLHzy@c4tcg|B%2JPVWa->lyK-v>_-j{pDw literal 0 HcmV?d00001 diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/v_vs_vd.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/v_vs_vd.png new file mode 100644 index 0000000000000000000000000000000000000000..926de2ddb9809665a819694dc1593f97ab11677b GIT binary patch literal 385738 zcmeFZcRbg9-v<0^7pd%ukRmI46D6ZivdfMTWh)~iMH!()Wv|FgT4qQ_HYEw!E6Uy( z&+$F4`@Em${{Q*&I$ziII?rT$zn{;09LMoK-U2S1SE3+0NJb)&D9)ad*C3Jh;y=kx z?%a-lrSP=L;a^*wbt_Yro92#AR(7^RyaK#}JS86ZbJ|^J??DBW~bxvM+7Mo7FS>YJDBV*M$|Er(LMYe2; zilovpyQ?n#a@~jO!6!q?U4`~SQJeH1ar|K0zL{)i8##CCouXHDcj}hcrlUu7WuMl) zE^5+Un2(a!n2H%$_A*&`H6lGy9RK)f-H_uZyv6_LpQC+ASv&qee2S^Y1ZQ}pGA2}-j-*5Au6Z!Ai{2LknjhlZ@g7n{<`u8aQTPXfL ziT@Uge^27Sh2r0n_-~>3-;?-nq4@VG{#z*iJ&FGoihobyzlGv|PvXCY;@_kAZ=v}2 zB>w*`6eGRAUc`qK7Z-o+o+$Y{kyY(WULJSiR^yWEcuTTUo7v`(kCWOOH!5j$W2P-< z|K#;Fx~oR{L~!fIEsRY0>|pxrE>F76!NDOuFgwx^EoOOwop?^mse&fYmyNShHl6Q- zXJ%%yl(ycs7zz8Aq4&xjlDf&mem>^n$U><1>VSaT%piNr&a1qR1qR_ypH_E&xMeok z{XyNxh)F4wDfoy|NCh5dpg)K&q%B)tX}m2v`CPPU%e!meNAam1D_`S7ZvN>oKOsXp z`9Vudt0Lr(lxcOyq3MN;4R3V5?E^3*7>zrTNJfO%toL`1~AWZN;><(j2( z`jUNjw^IZ%*ybO8S+X*=J&ul)(0Bc3p~w?HW2Q`0(-w1ajY*m>&bMUi=j9Ja zT}w(xU?C$TOHzxMaj0RFxpTgd__Deu$AfUL)m6a^$?xAUWGyx{HH9XgzF(D{*L@I= zWnIC^$M|>QPmp2J&C1N2l7qOO7q<8J912WU3XLoL*4io`M0Y$1r{REiRKg`D<7ZAs zHhHkS&yUfr{ap+#@%&q*KyMg6Z=8OKLE6=RH-jjTPPX2>PiMT_aO6^3Udhn(Cepdj znS7+%{`5yjGXC>)Q?0MmW?R&uhKb zgBYzY_akSx{^Z`&(m-gnOX=UA?tlJ{CWlrnmMnhQ9=G$$+zZ(?&Nw{h#n)HP7SFfo zQ#jUd*|Dc0j7`O~CX9`evgL(Z{L;$zQl@0Z;K0n6g&C*Xpw=-L81Q<{XBt;ht4UMx zeVEhu5SnXV_oV%`xr%D6q{z#niNgGmxLZlDUh(6a4!ZU`+w_#2cv&zUl~tYg^zx^B zm9-JvLi!tnHIH)<{v4c~0Z7*B;fCk|KJR4}EnVGs2jd+5uj&^r>|zzAyMmyeJyPM-#5@WWKm+FVfuL zvm3VFgO8N@zo_upln0Ex_gJ2B9ZP?agpzkD)KOWdDZTd-%hS5bKw56ovDWnITJ9X- z75C0OyU?1)$Ew3QHBBr0DFw`H!$*G>xg_V1lcr7~_UUj1K@<$4!lMpiwq5%f#B3il zd9Tk3AO%Lh=NR8*ir<@u^Yi}O*>ipyOSG6>2-1NlyKk6+<%b*#($dodqN1YG($f6z z?%3}wZS+?A=}X05kS0BdT94XG z6D?{JSj}{cNAI0AExttvpXV=?>4+Q;wn7~Il{Y8l%UAHz(*ure zxjlRqlCSWsx~F`yBaeA;M1*ck{{W3h-pa}f-y?424Ur)$W0_{XWj+pH&xuvy8Ilon z2hQ&zHGHzeIbM8ctsUEme!z^cyIvk}J|`oCE6#g;Ie+|R(Q76)R@V2|e^8;2G`R0R z^JQgze4zW*WW%6<BTN5^@|tx&Dt5 zgH14kLgCb@Q_`zbpNK10)W7eH%W8jP*|hPuDzCP-HcM$>^Bj(@`p!0T(~ozywY)Se z+AnqUy6Q9jzSDp8>LgN~#9Su2Tzh?X^v7?kTDB$2qnl-2dc)q9b%`2nV7?(wI2~o6 zGOu*)Pg+KX^;;35&xv)}pMJnBE5qcyI&Cp)Qx63@89jY&x9<`*T+hU zDTXo~3YDHYau{3ya=?#0 zV$l?LD6hxsmh))y;gXeaIaOa$RFYFu*~h0zy?30<}{i+%%$c8Ezbv5aYkX?6i zmXbJI$|V-s$&$aeT{pfP3S9a8uwJ$}rf!HxWCAHX6EIVZk#-aO>PG6l&M4tH_+V1g z@a7NmOQB~EWn^X!Tr>Ww=dtm($F6m0(b)RhwSmO@Oo8R)<%+=<&eW-SuY4uavg7EXc6O-to`027xV2e&!J1z zY{mAL7&?3gW;^O0(0V?du0~#9vFv9XLbOcZz>;GXHPegkyK9q#4pD)~LYL)@0 zgtA`&n9+V+hJP1H_`^VTXfQrg+E&uT5)`?rz1~ZoMiGQv zEGN0=sh0H!b zJUl%dZD(;pIo8Nyx)LzkABFA82{MwsPkMHCFy#@&ib=1MqOuKmU5xA)i>Ip? za?z5v$Lu8aeo84UltjBtvTTYI@LpeaH@>)y0P__bY9 ziJXq-^J+m^vD>VmA+v_#2}!!+dg1dN8=ty8?<+WXdXhGHUwu(fxIXo@{iIgbDFqsZ-|e?1*(%zL z0*+Tv1uH60O5HI%DoVq^YWnH?$&;tHkt=Ke+R4K|$t<&U@Q9SlkJwAK%hFBjpW+He z>R+1=H+J2kmGe~Xc@h?O2b|^zJG)|^4ai4JiRUeG35k!DmD|vzs~;azn;LFlc%GWd zDl5wz85!xiIB_UW+HJF}tnBa3yuD~uK6meK*-b&Qt^J5xpdDBg0L6W|PT}kA`_Rs+ zk)Zpisqa2`uzPTDkVQs@NzAUhBHnvFV9y~*4&hBBh}o+elp-^;v!Bq=tTxe8PMteH zJ~0vU`STe{ZdTuYa<$CIZ_uCIdDwSf5-*U9>-<=Rh7F^*J?Vq{yoS00K4a(M6iqp~ z&FrerZlj!+ef>(UovEYkau$DeCOs@7!Vhh-Ciqgm{o&^t>1Sv;CqOi&78mc|y?a-0 z=Gf7ry#UeHHRsNp6|!t(yx#f#T;Ct-wyXfu57RHt&!!oddOdQ`NT-pMl;jr>I0aVG z{KitPKJEkqV|5>j51QXzH0OsA5tT7g+}z~AShw@?#DFqh+W-0I@r-BY=PS{0BL_O) zTHTdhU)lnUvN}8~a;;6iAxh-3on0uK%9CEOyo;|)Hlg%=YF!6bZb{cXhQfNkfSol4 zwK}tCt48C4{Q{f8$m*xJZQFL{+&KkDM?nn@jj7*1-k9dtU%YVPHa;;K&v^CwOT*lb zeGKygo}GYbQ%loke(zC#v2U5v<2j{duXLZ|cxf3A9SUwU1wr|b z7ocxoV76goc6K(`W7*Nw%`L#-0HQ?0tC?hinD7nP2Nu#T492bYg2?fUit3#DPq?fi zq3;@dE&EBt4TxW{v^*ju#ULReL7XQ_G(g_e!XJI#`}dDXOEZQt%PLw}q-wk~Eb%yy zt@p0H$9p3f_?GJ%9Vc_DYUCYG&D6A_-EuqCi(;i*SY>2NK96u~XJ~QhP}w^EJQ#rKZ%PALHpv*X5xHw=GB!NDip8nXh-!D*KKSZ z#@mi(>AfQ>U0YzV;|&?$xB7Ba+H-{_f=k=9QS*z4O^4Q>OlP{8xw#4y9Jhf74<7Je z`Mi&ki*;~ALQ0BT#34hK{j|M3KkmM7c=%p#uZiFLriO;fSC>B#F|>dGewv~^0_x0P zOAnoJr#W^$#v~+1H-|~ow#)zH-5r@nO96iL@@#_<%VvG$ey$tqClC;O)YR0v@*R>Z zR_U&HyxoO@e8J^_{K@6zWk5q78L!pPG_nr;^7;AsCzX`$ODI9ba9Ce;``z)592Mr2 ztu61QD8A@qj?ss~^J%(mt=anY@87?VXFeAt>~rtl_Q{)yii-S#f}2UgR$m5Zw@L^` z?xyE6sz9LI&kUaRE75IxX-KZ5q*N$-%4Bw=iO-S5KV`+g3K5_=>yi*<=0AmI@A{GB zMBqFWpV-;^N}Y(9#Cmr94ByWj%4i@VWK+AJjv~_`KX)%5*BZRttOJ-+S4qw`@~tK0u+IuC8vcb$e@uHu>7h{3m=1 zhlwtUVNaH!P%SRMcke`ie1pL)c7WX7j*X3#v#F@4Fu}u=(_Gx$T3x{_CPuIFgy(Wd zyo{$LldM

yM>9rq{1O08kvj$@m8bmiJc%T{bmky(l9`_6IkO>{rc&7*dX2Npo=Z zFWa$W#{h%F(o1=c9oqpJ;kZuRmn1nqGRR>J@9la*p7I&9N=hDNVqyZeVKy;0uM}R= zWlGlygk(dsa5VXQa%%yolx!38Vkq6AOedy*vIc-^^IfNt3RN`pMjB%;+u9lp&N5bW zc8Q%M+RRO1(zAaK?hDT0;p4|g#1!@Q8PL23Y=U?zh&Xu8(+uGVFedl<55cWlxAqRz zJzauUd7fI!F`t(p0DAK7I)1B&%%gRndM0zY?gr93`Yb)-tG&Q0v=G&a_VAl2F7XA72 z=j%I<9y^xoy|MnezMdwFmx#^qbCAY{VolPUQDUbCLS?yPojTrHUHsrKqL~#GL=J)w z-gtKX51tjx&oVGp+U<4OHxGR@pcY^nqG}+>hyvJM;z@32X9sM!`NOTn)Q?WSm!O#0 z&yQ)Zg4mIrGkJwTs;I6ezj#1u%*-^;d&8^PYb}cNCisi}jT?T*%rfn@(!v|#rl0On z;Pol?FpA%XL>KfVI-HML#=|5|)g0wu3Cud8@z?06KTxzlCCI~j)!j3zdLZt-LqmSR z>mR>=r$_mgkCnW!wZZDzwV)k)nM{BW>pQzjJQ;Lf8c@E0@QJTOgm$uql1WQ_eYL_XgGSS%OmlQ z@ph2Fva+(|GZagZF3C7dN3$iJvy^wDqocb<8X6i1Y~>JmSe`=0W9c@&{)m{^Q_gNQ zLsa-`#Ot<~zo`M{Q3ZRy8+)5~v-9xmmR+5?dt3WIL8n*hb>fQP0Xu^i=VM+R&^BRVe)0&tov zqM~%Uxw+y_!@G%($atiJyM#*nPLKt%>T))I|_>geoZ* z#rFZ#Qs+k{X{TM-1TZfTstBd!`FqJTKZa0*1_!Tni<6U+;|3SplEH&dWfv${P5D~ zLm>3#0s%Jj`5rkBF{z*V4qHH{`f2W}RWo2l5W#SyjYUbW)f`~0o|}7gY^)!oOLdEu zmd*0a5ZTWMNZHFVvff5zfka8scv9^7mrf~!u`l?sa!UJ$TX}M8F&?PFy<=lsixx|A zkj7n?XHse%pSqx26>nJ}+f}eK32C$U&!1pGW)@!FJu)&fka%c8NQ0t8u8}=?`j9}V zkUs0DQ36%B3|F4?R9ywL_kH+qU$^*{En6b?xN6;#XZ1-*Nhz#jF;~^mp_@&Rqo=1I z9UspW-gt6c-{kuBdItLa`~5+}GK5{+bX*@a6!uSn97Y~Hqg8U>UU-9>ICXqOLA$5n;l8N7tbBZGWn(zM zhhMC~ryb+P1O>|hMC3E>o$D#_bhEoj<>W_)N`=Et{5&EeEX;4)CEhZ2SpGU5)!xO$ zGVoh-a~b5f%VuUr?6np23!OOu*~%F=KJArdL7V-b+tCr1k`l^ZA0Hgtis+3Pv1@;I z7=r3YhNn-T-iI`wF753$G(H~m?AiWqabzf3u-+?4ua#fNAT94rO-;Qs#PXa2dh^GP z^+nm#c3fC5NY!TDihC>1mX=pm1S`+QNk{6?9W#$ADw4uqRWpEH$(~~WkZDjL2m$dU zO_AHIMZ^eS)7;$LGu@n~&!5WxC$)?|p)LqGk6r-c(H*jRs_5~!t;Bo7sI|wA2bnN~0tA;@g2Yl7aYLiLyMj!SYJ!b%;eTkxQ-mVjVq`Pc5rc_w-Gr|5)sG9$Y^3= z!LEGV*Z(*M8&(g`CW6RCy7+AuAb?t1TbpXGfPlcoHx|KV|0Lz}x7-{Yx9{KIVHbmh zA8v~0yLbrT>%JD(Q1I;B-1A-3+P>y9cBK9MCZw;mp1$FVv|L(c$fL*s06i`fk>6>d z0X>A~(+}PBh&`Kc8hy{mn`YpKZJC#A!#P!}snEYa0p@SZOqL$|`eN_w(H$t?RQU(L z0C{z9+|SI+JoD|JX8ykg!f|EJ3ZpZ+6~|_~+2Mv3h_u}{Xiy1SHpEdLPEi2h>6@Hv zl1`Q;Wf>OHIXF0M)=?n(1uyapqR2xAAz|Z&JoIiT>=uQJ#qP-};f#Am~D*8ms z7Q$|tVbOb&8_%Mm1Y@h&*xCER5$=3bHzJbHvN7iJ|McvANk%BXz9AudG_&?)9-*V3 z7pS3UVrpbCyL#0h^QM3c6oGKsqkfmKZ zN^Z{+6MZ&q+0I`Hfl0O3+8;<7@(qXBFtmuByLM5gvl2n((X8RJ>7S!9HI3ZVURz6c zT<`7D_a2NZLfvMEYkoHN^f2SX+**hWDSCH3m9va0IpYPT1Lj>L;cMg{=L zqpipp8#9AVo&x+-&oMf2@zSMJ`uh4m&8amern1kQUrC9K>bY~W@tq*g!7JJ-`Dtk!(zh0N zgX#DO2d}A>`r%@=6YwP8uigD?P6ZMI2IEVvo+_1 zv{mQ(<6kpg^N@eqH$-tja4RN@VGIM1x-c3I(xN2#O;H)zubO3?XO>4plpdyH2qn(Nk0-llsN?Ks3Dz!O8Y#p&#%u3pck)-%V9jRS=?W zJ9g}F#+V#AlSICID`WLxz^_f4Hs!m`vX_7QG`+g)luABrEX2=$68G7hth85LQc^Ix z_MGq2`1nu=7pyESq&(Z7<)Eee4jnqa*nd@>OZVmOYuB#L{r*865)#4>@RVRWf9A}Y zGDv+>O|ly-JUqW=8(w2>_3+G5q>2&-*6PTUXVKB0s;ai5tLa=d*S4xgNy z9HA>zR8}57apKUAA3x%cg+OHkWMMlfX1iNTN~*oR{Uj3gX9_j#)vkO2NH0~=l^3ly_MfbYt!36H{hk@WeFLu5E3*`8tp@iXIqq#IG~74`MI zLC8?MUe}I;dQ|{JI`oxq>nglK4tPjrlarlIK^)F#%N9%{bjK~jzd;3cz%)wQb&7<7 zu>Sp|rJyaam!org5r634hZB3(;beY%< z*`vL)Qz&QUv~ms}Y5+N=nhS;HG$you$J6$M$x{Fm7Q4>}inV?FMq9c%L!P09+HXFj z59I}gWGgc>b62q&wOX9?rfP@!&TCdyiI~t~7|(rgFY|hQji^d8tN;WPhWzON;K8cL z@5o1wrrp909XWCY?JNn3q`2dtzs9mrv8xY;K7H^9N zTJ0gUuvf1*rtjVv=cef~^{u^t{C_5)QEK;b%xe<08KVyZ)s#{Ht# z_e1ODypZx-xX5*y)lL=Bite}fib1};kC@`=(_6rWsf+1U zR8$C|#>MHB;7 zP-T?!fULKAdwVba{W~xc?|m;fSHOL7A{Y{8Sz}{JdN5kvnUpW4-(P{!4+j-{n3|db z@>MZZYrFx|k$yJ3c<1Ww{5P4&{O1KlwNR9PBRj&I!9IBq(UV zwsOOu)a#J!#;OqVs&{Y@!OR{$8eLGAL;z$$pz&B11Wofn6N-2n9TT(L*w}b!WyQ3+ z*zGFFH0mb5X~oW#9nm*Nn>V2hg)unc5;1E9+BX+GAbsLQF32NBVM-H|Y6w+C6D1^K zZrztAkiSuW2u&4Yj{qurN(r+cutDgFTMH(bQaE}mX=rLbii!$E=h?b#o9Fs1h*tt8 zWh9J|^W?jI&(jED5)&hNgRHx|yEvDz`Z7!x?eA@(cSfw0qBj#0h?g&4DmPu}#*ksz%CNC|y z;@J-i32CN?S?<`j?J@wZxaW#+`|HZo10K+PWVy%V>LUa>Bfa6<9Z+z_||W-o1Mt4UHBTd)d+# zfUwAZzz#xF_sQgB0(FCGdhgeXx#K-z}L^uk41#Q892)-2o`}N2Tmm-Pl$THmr1$|ljY{;XQ_D%^7nz((xrqRJ96Z% zi^*+(kx7a~RLqZ1h#kgSIq_X*hU>xWkoS1Sm-Y>$3z*jc$(Q~3aR7XbLx-U!45$a} z-PhOG!z&a(hk}^tg7TVJTI!l^_W}|@OWK0MRf$e9xJR1rw^~qO;2jLViRKU>zZu{V z4lPHl{DZFuwRwwfy z@vwLu`_(0fl*UV%8XES{;2~l#A*xOj^CZ`4(^EQ|83nKGgwUp*Wg{dcq!kweSn4aE6brh!NADrdd|FsXmhafFuX`i zRPS%3*hQ%f&K21Y6h%c%4Id4K54Y)Ql+r3mpX`j6{w1{+b1Tg<_abwb^5Al9}J+cGtC~UAuPWqj;mt9XB-xv^sO3 z>OZQ(7F28lz-kGSBQuHu&ua=kKECcho9rPg(>XNJP%|*pVZ0EKc_DH0*OIjU7ElLU zoP@#o^C4XwR|F%kicFtCfqZ79_9P1ESbI9h?B?=}d3O|uvR0Ikh)4v`A#ut)QgjEz|>n&9#$2!=H2R*k3F$CfP%&P;vo-0!3if|;S=N&{@kpGb*mzbCs^WnpXw4OS@y=dxJoo)|frT<$%vinp z4yb<@8dij4_vI6fgOK6s=SN#kPi;6s($7cCXFj(u2Yz)x(ToWQ2&i4iMtm!*$2l=p zL&2SW|0q2CXn$rxF+3o%6Pmy$-wfHS9T-P?d&~5%0V}r}TI9kx>42|_DDu`w*J|yF zz^e&*-du;F)!XJfMC^iTOde^nEHF7JD1hR+LCbvbVC~ybU@Q%*SfKwdG|B=<@dBQC zX)}i-lnWw-EFIAfG=Ir>+Q22DIuEo$W~7pc9%2vTrh4NLra$3PTEC_Ts_Q4W;2Ym~ z%B_oDqnoL7Jk`^xEh|#aW&`?fv5mErmBaM(^yWW@iZIxnYRgDY{)8DurnHN*v#{9p zcK+ceRR?B_O$SgBUd*hNVv^UWA5>D}^{Dgyy?c&`MeYT!+G|A|n7n zy(}|+K{uw)PJL~G0fK6d0|>@9LoT5&-StrP_ zfAiG2)U<{o`BE$H3o2S<33DAMw7JxcHIx{I%wOn*sv;3{G6i3TQMXld{-PAO8jgwO zuHQs0I{h<6Pzs9l);z0?AT$|y6C8=_bpJNHF2IH$kC*6TXFFI(bJI4F_YU3_4xEeErT4;Y(<&R76IsL&r?zYqV&~4 zIN`7%hme>Q_U#+_2d}k*r|<3l=udehT#xhgC4g}Pd5d0ezYYEx@wUc+5&aE>nj40( z(`+_W^Tc0G#VU-A-r9@SiFe``ez>Qi5ICqLu*kJsBUZ$1HK zluNlJCnYttAKnG)n(RHW@%e!x0XuN5OgBD-GyxZkhX+i0sCHq!%XjYHCB_Yy+v}&( zW`qM4Q7|wtz_qvcjIy%Er6PFvUcGtq39cUy?d;b#RRo_*{sM-V_E@^GWIE^{5O8_L zmb)Qy5$I|M667(%S1>OP0nHOV8-0KjP!KfSy77Xm@Rd87Dc9b54pj0gFRvP7oGBn+ zb*H*3g3wiyk!|SluT9*D4h8hvosZWwE%)7ZCtjDGo!u0dugcx48Y50g^v}0UhhHto zDj%gHp1jvO{78iIG-g?Xl``&gXA*nT0e4SxMbrk@)YX0Be|wDOf4u;o?nidgkk!>r z!G2*f7H<&&=@w^|eD*Q>)XWT($G0@7*kHGWS@n#X8ojWt1G=dxX4J39V(Tsmvb0iR3v{-Nn0+3wvm z?;i@n3>CB(^Qsweb=%8(55qpSw?C86iT%!4>bLT2T?J!tPF|RFva7v)ccvd@8u`)D zF|#1H$vNhQH6BydA&Yw(^$_^;DS#N;dih_T{*N5b`>KmZH`i1Fu7c9f zBk$h56YyBF@4g8w$`7L(zcFf!>(_bEyvX1@@9i7@#SGxD^%4<$lAf#DIx8eiY7 zEi;=51O)IAfa*s6MW)&TgN+@9aCYxymf0DWeAL0&**73ymt7ZR1^Kkps}mCw#ap&H zJ3ABn;}Ms}2Qc?1%f5rvUIh>o#Geg<7JNLO)7xiq5NpNb@y}ZqCQYr zU5!{~YA<$s!}4c*e4H>@H-Gy!6g&@43p8`iGl$AvEOz0ek=q|#($g#d@#E4fJ>Lp< zX`5@;Fo7WV$yD!#DR7&_Q$h>D=*}*t(EBeT@ZdG4tIh#^nM+VpQ4z5UUw$8sg6rDT zO2AWsM8oi*)ml7rl#T7<$B&!fm%V?rx&z)V__M{3#5%TiZKXinsO->=Q<E^tv&2T%E3F zChFlid2$on99UOzD10m#MOqQq*XR#Uhei6J=yeV`k$7PEy@2$6!Di{PtKU)B8k}F6 zBjgrWWDlDMvsOnOJjgcQc6rQfg%1!TH6ORr>`665T;5lQIEXfdD%zZFW+{-qb{W)c zd~Iv9kcfcO=v$58(aF z*47zcVp5t zqdM&q9}eJH>&Uq`Z_OfC8AzBrZ2_eA$vpgg@WSBV=Nc)>n{|@J5urI;+8O+d`UJDx ztb5wu9R>l}VgU$wPo#Wq?;~&;!;!}|t?q_7SrVQr!gdc}n+XmM-udmJ9MAXHjq$QL zd4i7oQ2L+ZJnZJ~E|_gvCV1^da4^N!-_2R{hx~}GFL7~k7EaEyKU4OxM#0HISi*9Q zOLbg04k+VG&lK% zvs#ugHL5xw*ttquB#_Vqcro@~OZjp$=o&$z@kZJm!>EK?4Go{ImV)cTolAr48{^#u zSA{%AuL_2z(m5beD!_@bm6>B4ngmFBK;f5Z@ELyl-ZDX12C2GQAM_dBPLpjnvTk#{ zM zwB-;RAemIcx7Z~fk<|?HNCZ`TC$efye<+`>a zQt13k?)#3~NKpCIk0xUm=kozWR2|-0Cz}EuRY^bEblImoKMj||s0vN>g1;5G5w-YuF5MNX*Y*?mq+* zATgH0MSH9+QQ}lEPpKpn|APkuVMT%j67X8`C}%8Tiba7<0-}5M_N_cTTLe|#&%kgR zGd7q~0jrdhmB|P{DuzE@rQXa0o;EQ_kjs>3KYG*z_Hsh=6&4ZM*2O)Of*r*K4A-xI zdA^J1`0>lo>ko=pCpZq(Hn+6+XmKg%=^ezkLZ1ml#r0Ze?t#vis6C7sAK_|*Mx{}9 zqJMF!?=(t+?=Oo=bmb(Nc+#*+GB-bufumnVg*+y$EL>d5eLpf#0STWI475r4L$i(! z4j%zygWhFB10{aEsp*WH_v5fI$nPJWlNT^LXvSpN8UBuo%K<9@j&iJz_&>bJF)X@= zk!jjdzG?>oeE`}gH{Zm|W3fR9?A;%2Ckf^EpQpgM4-?k}F*_ zbO!>zqanN)oE;Qfi^uo{fvsr zX?!{{z8P&ff_Yy*sOjg%MxDZiFKAl|_4G&1sj6Nm_3{LD+_JK=^0}_=w7a_`=2O8q zNUnEb)+bMrun(6omC(AK;$Q-h$`Tm#Wr!3TYm?rvQQpC<^7WfHk78mT05lU93FGzD z?5tT_eLvtA)=PE*4ko0etV|3cK(Llma*j3bk)|ChFQ`PE-+;nkK!ec#ZVmNT%GG^yoHEeXaHn&i>1%RdMQO0?G5ompG55IE}40RY!xQB?RV9T@Lp1SPO{f7_QY z<(S#I>ZXCWaERJ&Iq~#7)HI^tj5Hp?ASqY8C?y;RU$eHh5{5DN*!P@J z#1To_RCT)0FN~(at*;~Is;|Ns_Z7`=W&eQ#r&LtPAyt8I(8A7W54CM+X^BNb zBC_BQR6AnBCm&eg=aS)hY47zI&X60V2(DaJE((v1`(HfbxJBCn^0TwETVVMmI{KA> z2M?|giXo=?K4srHLO`_YIy$0$ErCu`!>RePz-i<{qTDu0t|RiU=0oD49Fv5rJuq6z z5av%JTvKeZH#=ZO39fu(!-<09avpZElo!};h1*8HW?vt#AtD?sf9dyhOYO) zWzwkI6LN)PZYLjaq-vG^Q%q#iMBqw~%wtE|L=4>mrV(?xdhME%=gM54fq_9jk~hT> zLwHACUS0!8m$dH2c3t`E3b&T+*yh(b!eKq}a$=^~y_-P64hZ@|P_&5JN6(&pUPDDN zfGA75!hFlkE&VFrMnhZM6R|~{i0e44$y-MH`^!&wuN&BwfX+K&L8%WQ?M3r?bY!Fh zxW=90?YNC0SiWd701_m-@V5of7Yb~Y`-~AzNV&+*QogO8rGu?(62TgSA%N(TBG_O-LePXFt^Y}sT*Sz$ol(> z;>TdgEW+S-WN@$ofyU{q3Sij)eNt$nCq;u(%)FL{mxJR>-*+|vfk%HK`$@pUFzf-8 zr6s;M9&hXb=}&8P_WG486%E*#fUAogCNkYCop2F#fmlR(*%89oT*omsw)9nzeV@=! zT^G-(s068?^}ljLziW}JJ*@8iNeQXhH5-4FoQe5HO3_^hYPi!j9H zA$CV#7tz+ZhH^JJ90f0@SROeAg?UFc7B$nKH_D-gu35xknaCcvV8phkq@m`@YtuZ) z7G?0IIfB;djPCF5=+K*3Oci93b}fUo(t!%Tj2b_Mi#_ zi0YU2FR|`ni+dtFR0oox^~;kd97<@knz3;_2H<&J`{9*(31~}rCoq^kCT0oSnaj$Y zl`X1I4EktSyU_=Cfl^*9i1%W)7QS9`UQKNT27pEYppZl=P6VgN6H7Ta|9|@o}A1Be^X1;6coNZhh z_ZOhgDFhwE9>skK116f|0`Xb^{zyXA;*3(dupCNF(%ZxdO!p`xC!- zny=Zai&NCZI0iI(D=3qmr48KJzzlkypSFpgl&PvLj{F}8AS$uxpC2% zE5#8s%yk0$Sd3&@>qO3zVozszmr@K< zA-EGJl(Clo*`Kk3ylycj9RR5>&G6Q(Tiv1{Fa^;3d=`FpVpd~mW0T#y?KXlg?aGDP zrx@K7;QSrI>f&dygX55Pi)0VOZ~?8Hel69Xn@7bRwVnHH}-vUscZcF{Joen zMl`xW0T^D)OiVnCYL*oCkr&>M`nzmJH^x)7c-u}npjzvHaDQh)F9y^4XQ(cZAUO=* zel10UIiyxW<~yv{6G-aH+SrE=%cMD^jvZ4b%6G?3;);!f>5U}V!@S58-!r-$ye8t3AhOjO=$D)H3i@>=5H@fqQ@1`;ct6iv? z1zz{F&a#7!E6CAv~lm-{TH=aCzwusDwK>RyJm zNA+)8rY@gfr|pl|Y<5NH1=J=vfpjp6T3x+5)%FezDaDCXaP%!ojDfxVt1lA7gHwRE zNlXHfMl{wqT)#Vqjk~T*;gC26W1F)%_>4<bfe-Ri6=+4;p0c2Tk!RkyAeY#1U0vCuLp7q>G?e{N5{B=PE` zp@nf$tCPTVIoWR|F@gAc4LjEQT*uZEHd3*8W`cJ3aL5yLb$|wERLa zm|yF}1YNyGBtPuVcGAJx;W3B2|f1eLR+N?lUPW67= zLJWqn2u5|Z30s9wSOdXTW~z{`rbwbYt?J!ZuU<8Q91q6nQ(7vErGRa~a1kST@N&M= z)jI$P{GNQ36&1ZOpm62ft%NSVF)Nm?MTYujP;`?5suWosw$cb2Hs&W=&I%q`m5pp_n6f~f*o1YJgP8C^^9^8eYdtO@u`KKT6>kYdVLwz$ON>z}t@8-x z)zWe~(D01~1$=6*13)vx&Q=Umeyo%p*D*BCFf0-UY{ep91w%9}b4b*?1L7&Oo6F$M zw@1rLZHE*=xSfDNWG_H__j8gE7w<(;R*3sf$lE{}WO@2}V9}piS{{i_VC#!jEBT@f zL^HzN=4z>`BCCzy1K6imRItB;wxd(zs~jtW{!f!UW1bqHh4_ z{R}!O`2Mz<`FD2nn*e{!(B28MI-#}{CeQlu`Ps+zP|>u|F07)V1!w-2-oE5~Jn)^} zW)flHCmg_7km0!5i2MEsZ55=sekT>`Y=!(`SFoK+;MTHc#XYI1~`>f za|u;4KdL`jCe=F=@;HGMnnj6w!@>&I(Lx}N9|AnttgYn#N_oa14krt+>^3kep5u!3 zRDSrGFuA+`Yt<8>U0LF#5?=i!^s~DxHz95Z{yXlmaJzMD0C!RBP+9QE0_uyZSS4&r zC;Q$9aSIAk5j&!qS@5YKfbqLLXii-tmScpisN!Ti15tg*qk__uQj{a?7bgrsvl8$o zNrPE1En^y4>wE;(dTxjW3TYX?v0}pnKGxgUcevx^R;Y7C@`Iif=c4k_CbD{A!GoZC z#Brx|3W|v-L4o+XEg6i6@bD;)@X)}mj=K@6>}YRi!TjjgCQE!hVZp>WD%|>hIAh>$ zVb_JjcU=11VTduFJt+|;&+wg^hf-cij z0a$?osb3C-T%qQLE#w+;mkCC!cpO$P0V!Dp*(r9wxSzOE9ISSfv8E<9xCU_=cGqEC zf!`(3xe?H3_@h3?$mL)x#BOJb;}|x7kh0If2sQqM>%h%37z_nX{c1v_AhAb>J^60& zCm;3MF5y=lP1+I5s!_sLtQra#m5Un%4g=dk%!7Vc#*wyzwp%yx$M%M;SV3) zhQK3K2?dLG{CkdWjqh1w%*_sXt)u?%%@z z&qTx{9TFVjdAol7x_r%|2>hx`%gdLct|;eygHH<1L!onepz;9-4bIp%&3Ns72M*NG z5X(1cBUi6-cxQ%SiFje+XPxln<0NUX)%|dPpiqz?`Gpmzy#_N7zxjLr+jsA@!*0Q1 zN4VQGufv~@t?uNo;^%{=k;SKhw~kZ)&`#Iz`}KiucEm2nWGG&zu+q?+dX9lug+zcYElnqrw5gKZ zv#QUG?I+boEuy<{#oo@yBHz2W8hGpS<;x%6j*^pzP75>;R2D($c5#ButUyK)4SwJ9 zRT4jup|w0uKIXxdzF*Qgt=xuT|9%s=l#3m}QHWj9@;~&|xbk}8TSZ!2m2enGlw3BV z#A?iKEiT&Q%#>=#N#dbeX7T8K2-o5*M+vhQyv>g?xT4_-I^I5}HS;VovJW%FVtSz? ztgQBv-6tMptcVg@D7S89&JC-=n}pwU6~(zQS-PQfsT(U2{6D2ZDLm2L&ZkE|EPW11 z7$sIHXF*bF2{B^ zS6TKtblcyC%flQ9wxWQFtWZ|~zjo@t3i^R5ylSd}*M;J5Lc z8VOeadI7Kp1mmvWKRdneUeCdj44)_dh@>EX6H#s_y)qPV$d_#H-S`bv{A*sj3OZa6 zNe*+P>Zxn8&ZGOj=Kg#N4|WLjw%Mx4s3;=G0U^lV8B^sl$$n4QR0`iTlFWdfkBP>o9NR+fAvI(+GMmo zm%wkj0MEf{7sc;Ce=cLXO6>Qq%>8PIi49hh$P(jSlnmnnVa1c=hjUf=AIHZxweo4k z5x-jjVk@liJ9qE)MZJxnyzst{%eZ^Bn=n3uZH?Ln4D*==l z|D+1 z0FJ|+uZjNCeBl@3(u6BGHf~%-6oC6+AV(P|M1*j~v5#-x(gDA+G0(UW?PP9lPH=tW zOv#NYC<*?Ta$<2a1H`P|`%#YzSjx?)sEy~_i6f`U*Tf{cz3+)hMpFI#)QTkn89ut^ zRDxghK>UHrF|suk723bA(xVFC(&^^8&53>-04s-rfv>OP%X1x-Y(sF=0=QvQIBJ9$ zk62aiygC*M^!Nmdc#-qNhYxj^)!*4gW4^tMzUum#!B}t2!&Hh8+V)+tw2qE9ExWh= zUR{ZSVKaO)K~3&ve8`Kyk@yy1hI=ITe7Z1+X_9(cG))9HPaoxD)0Rk!2x(LqdRivngom>aya1zu(*p z>HSao;Ids2TIdE!FQ1Enl@kpWvw77kWI}Gjm)fwGkVJrncx6*DIyxLH&~iHV(rLZj zg)fK0W$rX9>x2?>GUxVhw=zv#(o$0D986hF`InZT zp0c7W5~(q6d)-`0#&Z*0ejOj(r5AXwQhO}e!OsJoCa)Vb4L8wElkgHa6iC;Jg0!BC z%S`yFs3o#xFntDi1$v60>&;6n(1~MTxmAR&gybC$>axV!|6v`k&J?3SGa)itBVv z*F1u7<8aI)TB|2S!Q=O%E}ovuXS7Rr;O&{b%9XcZ?~J%~W-?v*~{@(ggb+|>MaXO z4oRK3?x2{}|0!>9OOOh*; zG+a@NIe2UrPv`YDZ__sK(vd1&Y5!oy=9=BKh~(lOXOOzrv7(^oHl1y^?(QIn z9(Q?~E>FL6*Y!2J8Nzb;KNr2DLwf3O`M5!LZr^@zz&mra8EvS9rGaoZrX-T}rkh*o zOEZ17gg%5wuv1(rY+=XV?@2!-txB1L+E8NZ%oA5hp_uk9_x@LsZ}sd;-Nfe5n0^%{k3%60&8_h%iirsuq%%i`_j`lBjXlRn25bBPOi!+@ zbHhAc3aq7<23De8#6N|z>XMtOX{^qD(R0CtCtr#Up+|hLkbdkA0v%zk|FroP&ala26YcAPig9?Tqvs=Dy}FcpKK0M< z-(4XQT73Rbb(#}ZR~Q|=EVc@FVdX_t#j4pClBR7>jnhIYyLn^SfI0Mr2%UKnB={JZ zeNj{yTi<~nBO_wdms6n@fw%d}yI(OYL}W`QI%XbczPqDj#vgzQAwr>o0zW>E!cB-% z#$VcFq6Il;mS}!R{>$d&X3Gm=)DSv_1Aa14wB}P3?jGHR0w7LTb@`3+eU2=Z|NqHg z>Q1~#Hp|v;Did>86S-|O%FO)o^xl{0rZ!2rn}el)O7ly&E0-P5Ihx~dIlNk7M_^KY zRk7d9%ps#Vsn=4^etAEffw}Yz1+VTa`4wlX_aT^T2ana)+2?5SzoWJD zcLvc2r&a6`TccnuDUA!ybi3X!-+zz&0uY1~5E}VAGcmIn_A0c1;lw+#Dfsf-WX5o_ zg03tct(G%d@@ToJJ<04ThP7oTMzY(Ga=hBpRfopf3Lf$Mz(4@*fbk-yI7xePw?UIQ zsi-xz5p&0EIvJPn*;mz z?`Q0Rq(8A~AFu)Hh&IT^h=uLu;7~sD9Ex2`5^Lia9QgyxL5`}<1I5_k`NUE1$&9u{ z5jGerd`IWPiZgnJ3Ayce#4Nc%g9nCkZP>8Gbl4I>p5DllX11R^Sm5#lGLOF&w#SRT zGwP;}KsA7=YBwi2&?KJKGY5z{810sDqyerE!Yr%PHVAt!*X{XMQ&q)+ z;ry-}u|3ugJ^tn0cDMM+q9as9IeB^Y4kCdhmlTJXYU(hu1n^h?Uezi*Gz_mAwzr80 z1<-J~jqKSrK3AE!6A%ju#f&Eg@;-ujIOE_E#-@?qppIlvzEPuV%d%>LBjIMu~*sFnBapM z;=~L3haBgdj#>#xu1V<{KucgALgunkPAIj@*lRJaZ=UpbTR#5oh#vbde55Swh8ZTp zrEA7qko2>uz2gr?%%p9T=u`JLEBPVG2*|;%!B~+?xL^)@*U_c?J&#)pL0O5)GD}~Q z)LBYn0Xy7QB(#b4gU>hD@CeVf+#_8zx~WZEhpdQX0I`S_(!`>MUM9+Z9%$K0_Zj01 zlgRdxp*8@&T0CZ~ZjF z0Q#Em82$X6qg8&i8)idT;hbj1rt;gR7Gpj*moQvYDNFeY4rCJq#DjQ%E?%=-!$xVPA{uYJq>D9OJAQo zc=z$5{4Rd?;DJh1+`1A!zi|Vo?FeT{CMMi%%84pB@QW;CT)sT8_*U)RJ=;j~8am3V zi|*s!bYHz^_9P7B$Inb*hhWG(U$WDJNl0!lvafg<8&O z8uyukZ6u5KNF)=AXd|lYirsEB(92W z$BfBgbQ1A_i%zpJHSwZw!!-^V{1Fp4CyQ~O(j5M$ux6Hj0z>1f}|vZJn#L+ zd>0L-=B6Bxb+tRP3Iv5#=WZy9@rnKIWGH|hI5H>zsgrcDM`w*U9*xcpqFeB?*j7;x z_gOQ#yA38rgkVs5B#Hs0bAnnfps@)W(jj#8vj^)7^AP-0t7rp*ZD82=x|HP#TU2N*d~%_nzO-xdn;I{N{~3H&VHrXrl!lJe6U=zjz6^ zUygD5%d!aFSAslSqJ2Z)XUk~mK2W)QO`FIU19%+KH8J)?Td=Xvp(Gr+xSwBiFv&-c zJFQMJcVuLV)2>IJwD$T0{ zaeak%!!c`LqsFE3^q8F;Uj`j9edD_}I*6oNO`9Mn24T891HQsYsUTh-oQChn8bYyH zwWyE6AmR8$M2OOKNaaTIHlf)LA?d+)pP&*6DaS&IyIltkK^p-uCT)zduxtGaR~1mz4sWcYj@}C=*zF+ezU=A$848e1a2q^ zTBpF^UDMue$g$B1%6F>^h?EqF#QTkzD@c9>&x!=Ql>3dIb|5=B#IaTKoAwQ=g*$)6g^FTNbkJAc!<<}@SP8H^vIPtxwkjP3 zck%)%mFzK2VeZC_ps(bTcyS0EY<9Y>m#1e$H^Rq5NUR&iy~eTD5|nGLvDyUu@~dbj zS>}gNmF*Y4!;CXhEBzC*zIBaTI&|YdscDJui;@_a4SmpWt9BI#Q_X) zb?H8xTixWgV51YZgcpqb|IO3 z-G&Ve5SLh{QKcW+CS@QN2;=NcTt!gLZGawf{Q|50F+A^ExTJ8;X7}e;?;CS__#LqB zTF7Vb4gtLP`J8L3iRe#8FwSbwz)Ew2gkk|$aSL%#@kzFl10P?U zUc#$RWe~PxAKfHGQ4{}(4ey@dtggPdXfa$DCh%mEa87L+8jcYGE&lks!9eLd7OVIpWCH`&4ZIrfzkFebkKh^* zy#C9NF}$q|&6+%L7y}Z~1(fc?&4(T?GPJ;^j2ThWXYSuS-owyUa^|n6wou+1ynZlM zKj-dCxUSeh_XrNi({0Z)j`VQ8f3b^qu~=Kg(qj73K>dxqwOB%PgG=fp`B%{4<@M`P zC-2}KTE6i*ERGO{{pp9F#NZQrjEKJ!U3B;y(uSh>-n;5{qt32_ z+3+nC{o&xvFgV&`%1FnDzGHK6F#t70vmlJ&`LL}|4Q8Q7N1jY|ry=J-epW%8-TT2Q zkMX|RFtq=DbI;s=nZq2q49QG{CdGe95Cia#698d)`@V0(Ew%=Kl)mS=Q8h-%&zG|0 z{|@lI|5~)wgKOU6Lb~HUj6BBP!l8amSid6Kw||3XUOW}iitp!m1Ua{7?k0Qk3D9G)$;rjXVmnsUBxDR^dP^$jb-Ljd;zD@A_XD4;r}@C|{bu z(!jC*I7HE)?M-0cym>dLak01O1B7E52Ncgy;b;ce+`j6` zZ7*W|SyWjYfW-ZV)v1)QXXocK+$EFB(6&klFN)P&VTUf}j||_@<_%b=w+}Mo~B>1ZQVrVq!=$ zW8DrKnJ^R;w3LenKTp|+o%CvSkj6#F0AdErvo&6leO{C4H5>^J&mILW97FFzB20<@ z1-K@e^N1g#L99xrq!`d_V2FC0VDrz?FZdCeY$4}N9~*m-7*v+8%MBDmpe(@hxq&AV zt5Y2sxeOjBz<#pw=M1*A81=2D>-3%o(ct+7|Hm~TAY?BQ0DE;HkK&%=b^x_j5Mz1R zDQ3YNycEilCJ!K1*6jdGFa9Y$l3_y74C_#vZ(pPRYQZe@_GnkImG~i5No9~#WuWcQ zLAg*&MPD$4tg<({))FEyX$esi6U(6M?#yE_^k)Yhf$fY8etHcJ86?&UVa*yDl$0*y z?;wxe$g=UrqoB(t!OJ?e`A@(nbJcHPRX>lteJT=3(juHReSgx%y8V=?k{5+D4jc3>R2XZJJ>)@@UNn$Mo!zT*wJ>|+6kVIe!cU*b|ie#9aBu5x~b+!g1)1aLSa2iY1kfY;Azhxxq_B zN8meHu*gDp=EQ2Q%?t&y8%^d4mv+Jz4_mmS+XEuSBnmWq?l!o!@r=N% zy3_4YBa`ucgNDNqa&At8?IE!qK1zMCXw|#PNo~QI*-=*UCgVDrZO{V&X?NuByeAM* zF6^q&a+_(aRm9v3uq2j1BC_IF>kvvsae0}af3aXWC^G9 zi<^8xib2`On`G}F@khh4Z~?YV%e0AADOOgviqy-aHrk)?zzom!QO%EL-(lJj>{Sz0^V+jGzwn3|jGMBXybBE%d1ZDv+ZaXL^9H^8UE%5w{D`q<%1X)il^ zKS;(*OY@Gr`P8X2mj=kve{Da26QU@}qO}&drdhAgH6bM@rK^lHXgx$yt_$CEaMR+@ zD9tVrgBtG4?DAB$k%1`G3P|Qwqci+iQBj9q=JStfU+8ZoFx!XtP9q>hz-?ZNy>aN2 z>YL(q4JkT-dTTLX2BRfsp&12Ua-BfB427P>UTV#DU?zDSHNxsO6EKJEyu=@&O1==5 zZB&Hb#V|)ceBecZRa65u>@vii5AP}u-t;J^EoZqJyv-?;NbBJ2z-szO$N=$|h<07K z`RQmMtGD2zQ?&PZ>%qtRI~RI)2-#vMt0-T)b zW3Exql)1dpOw9#Evyujt%#c%*<)AeGkNquucLa?XAfDj28iikrt7AFmO@H&2Csnii zfTLA^{@-z8-HPJ`UqjZVbT$>UNAdUs(33kHV0WXBM$h!cRwCv;g1rD{MPE8EZG#z4 z1C=)y!c)t%cXrAH@~Ka5QE(qMRpjel#(T1}EI^b_CPtm1jctKgroevRIcxL_6HShF zDFYh)WHgYZNym2sgd)cV0 zR&hMP*6dt=f8A2hTQSlU2R|8Oud+@FW0eH(ri z_9+FZ4x#b8qRTZPFgP`VKdp9=;*bbxDEoHEdsRxmJ07n8{iD5bg{tLTNwF^VM}2)w zv-P%n3=nKU_0m&B#aROk$Yb-)XmUV=-oFb77hD&jO#u{qO8>U4P@^?pec)5dhfvX% zLu+;&@2uq#uW>wQ48l`@Gr4N$LS;*|tN1R57ewmISLQNpbuyT=+#7c35OD_y8;1h$ zDzqLX5gjdpfK?T(y!`#wuU}99oc0XWmW79ke1s$q4A^`UbKTXoWuuhLFq_l>uMp}J z#{+};-dSl67?_x?ai9gw@~GBMQ1Sr`rz#&AE=iwmD;ism3X&@KzZ<6%cl+uyE4skS zR6Y!X#`;X+3?!t_w+6{OC#?;NiycD@EIEWV4-Y&UGKtkigLehAHCNM`y5UYi7Iq4{m;gutEg@$;UD5fGb55fL*ngl98+?S@(fu4 ze?&K5(2yJsv(75tQG7jXm4gr>!yf z?mdnYdkc{ab)>a@(?}=W!i=xo7_Jbn?c_kRvPSR#$#Fr*9|tOcCO8%Ck_p_k5Gh7{ zY2aiqPOz;{fef1P^GI2J)IXYq07K){%-G!I;^v3{ZpeFKj%Uw4aGZA0Fa~fu|L5y@ zY75NP$*uG6!VQ~qbtIN5aDBuHvseneCHF|GsE$OIP70-$-Wp}D4k;?QB=ra{gz0Swj}{f?n+ z?42|hSp)&h=yp(0!{9!M`LW(okchNSotmz26nWlH$vQGo^H$R6NfX%>5!}$!eZW|> zSn?vyO0Oy26{B()T9Tk%>({Sj^$&T**w9O4?soR}6_Q5~j7-FzK$MoF|0;v_)Sj!{ zByRBUJ(q8V$M>HLY`zOoj|y5-Muh?lf!yf+H~P$DA4zGgFoq6PB)!SpDIPZ?RZNq0 zmdj8e)&So?B`-U*WRZ2m7L6}76vA}Y_?w9Q@8AeKg@#K!sOTh&KJ*!s&7{pf&+cOUiX@tb) z0fhKpV>^nSMHS2>CyjL1_%wfTzd}49;sz`x$7&xa+=5<)nYNl!TzN8AsodnL=;}Bu z&wv2y3iQt>FkWCAM~;&%N#}-q^aDgTSIGg%xyJo>zr!U5OZI!l2`m8v&-DVNU%H;W zNfKCqU2_EECA$Ut6a&{nh3zWZaA%%Kg!9)k68`tz`rzY55yP8n0&4bbuZ||b& zIB#LlJkOmat@^an@IsN$Dd2mqAt3hNqivABS8jVRS<(2%Kaxk+)q<{?oYiaW!2DsR zSV`L?XxQZ!HSdxXuirq@=-iyXZJ#y9cR;ezMj}tgAtHPz$+{A;#eT;VVA}}U zk2OD4Yy0_Z9*;U!zPn&4RxQ&s`Y0^u+x5abH?LnObVZVEJS7jsZoM&`lcVEqSDDJZ zoE&8&T)B!~Cq@s%dNJJ5xj}FluOg^O6YVM@H=GiBgIUBH0dYxwwNRXb*!`E@4dn}N zlG2(Q{U;XqOw*c~-h#?T7Vo;Lf&|>_5U>!in7>IP3kWW}*4y23kk_aJUUSn&9eHpf zRCu6dwab5DX`MCwZ)l!KY$_l&^~PMGP9H?|-p!2dz$py53V;nBAm@pndgNUsasxM| z#t#4qNX{4dK$4p3)v&(R&`{QKeS_suhsIBIADs5921s9b{qo0*u|cVE_40%RmzSgU zh5=fD%nO zfTS%V$z*u%chvqML8xR{u8xzi-T71AfY`#ReOdqrvd$OJYUI#y(xC|F)0v)VT=N#A z^j*1)q#N@1uN!KEfI{1u%;TajDfRdi$;K~-qMSH$$f&JP=mrA{CfjhfSfTUA@0o=D zCg{733@p~DPBvhZ-n>$@zh ze9CXK3BwHyt6hzTT=Wo=s_Fi7!I&fVn9|Lo+anQdo5q|+U2_|4kHEHuaD*>M zb)yWOjb>T9f|WCTsJptQ#T2j4JJ?D9`4w!fGW@m^g|}C)m5faAViQCaP1`2B8r_og zCI=$3Prl&=Y^C%H{W7vZfJ?H$0AvCx+y_v&Otxj`+EN{H^zwn=2^|?^=prWgQQ9%Svn`FhhAUqv)N4(uHDU^>r@lfDgp3{|-kr3`ySSObVXwq%upf22xdjD* zMBH$QS%}Zb`54FB)@#CDdj-uBgs0kLcxOVX)ee<*tU!{SHEaA7YY;&3#f_W$GFlXTzx1(D4ne~!&-Yzxi-?twAO)>{ znFp#FLBOzBhqc%_4GgW>s!6 zvWSPS9WI(Ya?#1@Ut3;LSt&WdVEunow6eH<`n8+G{;Q-6L1;?HC%Wf;5;}})#sD%}VPc^HHm^fZ7rn>oc%%d&bnxaMauG3BX>FN8Rf8PL zGrCX3MmA0Qrt9(#39=1-AXs*mbpWsasjH|i%KE+Lg5R-R8z!M_zoo_Y(uWds0Q4Y8 z+_i9-FwR5?sC;Bx@&)RV3=)r#E+1thv{_a1kCpd>^2I8|M}Y)p555f7Os$WQ?rB@~ zuJ`PyY(8^Lmb1_awOW61HoYG z0m+kt*_d<*CIa+&R4VnOm$&go4vt$O`AheKGv1=)y9KB~wDdM#pC5;@61OxKC+iI4KEMyo}o|o1d5n*T2|oo0;#h5woz z^$vQ|ga`YaRh~Rp3G)<_ZTjmql0A>qjwYaXN3qZCLGm3A_1yyrxCJ1{txyaVYDEi@ zk*tT;!P7ZJ#^aQ}=N%CBwy5Xl)xRtZECxgJtKNxL)hIx!*v=xtZh(5$Lnb&7ruDCbjctwGKq zSC}Orxlxus?%|Pdy+RG)%agyp-i=RA%tZr(afPWTxPZ5+vs0;==@=>2xDQ*kWf-5{Jpp-d=0`(>UK5s^GK~qISZSBKAO=wdwy(gssAL+<)cZW)qmy4b%?GD-iuZ zMy>7p|3ptz+!x(2R~723ZfLtmpQ;;-oS@U*-Z2U~)2YaRS1%m*Rr~ceg>ae7gx}vp znxNqVI@%lM<3|ObI^*4~Lkq=}_r2NlT=b3eg>AYj_w^)W$I%pO3cJ%^f#Sm9d4D~8 zAmaQA3imml1@*%5f%E+x#S?1{_IZ{r|NT8t{u2F{H7~T@x5&GUO^5ly_q`5jgd)(V zIcbGN6)sCsO!5xna$V7dsWk~4Aor3lC^907TqPA*jHU2P% zW%`F;y@It10+n**kjP|T>*Xz%lX`zpDANN*|0H!fw4zkc5S&tBcdJLW5W=kAutDWN zD)yuYm;rI9zbM1_eB27p++x$U53N{d7$~Jgv5~rb(wjKnIHMvW5@!~M@q07b0>fVo zX#rE7ged+jQ1-@iLgS}yi;~g9gN8pv{;^W_`>%ccH}}}FcK9io<3MLL{OoH4T`A5l zCRUTqv2F;i*h;rktzpr_%E=#+j_ZsqkRf=0HZEt;D|VpLaX&y`Cdt_=R<@o-?v>3= z{_2)u(RSTgkS_=c2~k@x3!UDp0WeG38T(Q{_sEFq^GM0-ncPNtsmpPz!@b%hlp^rB@R!GvYnr1-#f zQu9&V#!s#;oJ8XtNz_U&%zH&Ypf-TTuaf46m;qj`b^F;NOgutc9OheXfW!_b0Tbec0!qm|r zq)HCHQ*o^uO&R71g?z9B!*c}thZqS_5n>4rcQ28LDa zMXsDbnrliX8fOAS)$PM8ssb%1V~^m2YO@g#Gz93U3`1pLUqhQ|dTM1Q{uAbQji$Jm z@r9^6cT%FtdLUE@49f_^6sXOUcbz#NT5Gp2^hTYAg_{JO4bl!__Gn5UBKzG6x{R79 ze?62#V6Z^*xD{s9O_-b_Z8$_sui*6p;C-!VpC@=3Dg&=-GkD$c9bXXvxrtmtr>F(M zOS|9~p|+q@v9R|$BtwLPe7k4X@t-esqL4V_>y`Ex%6$FI_@j+vWkGx!ZSS3`1lJPT zJZgjLPW32$m7IL8H!;ZXRO5|N8`+(8eXfddU1vN}%UEq1JDy&<8*c_5o_Vrws_<;4 zdV-Pc(jVyR58St}W{bOj-xf0`wFN-ZwFF0*8*==rhUltXGPi8DmgoWBH(VlE)=X!J zn;}l>#I^$-zpp&6@UF5v<`lI#oz z@0nM<efl($$#TwroaYY^OiH#XMcLi*TTxJ3as2A9BgUqWH}TF(9sjQbR27YB zvdgn_z)YeEmW8PY2PPssoOfAwJ`PBS(H4f693=l_(N1i`3Zq!Ia;Cp+XJFw6?8(%F5E8bJ z8e9N*sUsJ4{FdSmTt1R~S;|&j$RBGaTCu|kVHOdST?vw*5||3vF{8VN0Qg0kyOH3| zj?dJdl&_yiQ=2Nrssq&w?|BQLaK`G)uTY4-_xB5OPN(eXgina6-V<|b8yL*UVn3MFJ)}gFz`ukCK8BOiwL?VH0sSXc?gdDYz~Zeik>5&7OS5jr z#kMJ-wgcOCtaVW(2_+a({<*Kugq3g#NXHl9yab`5`oq?aBG0JF;l~)C+v8Z@;>&0) z`2qpR4^NPw2SB2Cb(yVoc$bh+z;pTt z#B3wcjPJ5yDnB&Vpiegi;}cN@5XtuOHa&00UjUavFJr>V`8hJLSNX4P7zgfC&u{@< z#&d@zovXpunHU*Y(y+16p*`T=+C>R)5eXvkd-u{GWS-<%R3(fF?MM;}QpS0m#i-LW9hZAZbv5 z<{_YUPf^;@YQNyV<)iHLCf}N(0LcZ>X zAc}@^>D?Z;*_4Y*DWNA=G2v=ing;tsC4)K*GJlTN`^3fJ79(0PHN{}sgpeh0H1Duo z1#LLL55K9YDPeP4Q**znRRh)V#<3=eu zn@acD_A@vQlQx5LdxdvPdZ2{fK!e*i2r;#5%Vy;bw!)LQ-OWo3WYxgdQ0;5ux^A&VtSly;bsSYIZqF3!&~*&;UN zi86me(r^nn5_Kj?qg2Dl@#9AvB1}=g7iW6bs?#JvW^pSa83Tb6fx-5JfQ@NmD=45a7Pl3_O})GJ|!|&$qsU)d&k1v#r}P3$BALY04ut8-g6b z)9Zt=sE5M4xkuwo_R+^P>Z_th6VPmxF&iV#N~`Ql>P?EpOWa-tiYsvKYqOlw%^F&6 zA8{?0gKk;(@o5l!T#Yt7K80!bWY0g`(X$e5t_(l`jlc*0XO}LS=>uqt-47eJ%Av$u z2YyjGP}&5L8voh&6?9}WMj`Lj)4Hx5#UH`J{0f{VcJM^VVQf=O2Jk=E8e%5MB!ZP( z7cN}*%qt~7_~Hj*t@EuvsYMGP4rD8zcE5;JK;E(iuyT^8#$RFORd~1H<|>DY%K(dS zm}h-C&6?Y**cXOYg|WmHYz5hu*R)U972pk@B}W!){Y7z!{P^{9y=PrY$vSIrgB3Bi z65&E$he1}5^RDdq@7-pId~4c8m;5B{pEHm0qN-mVz+Nzb)2~E z7chQodyZR(pMwMi&-6xSfrw>cG@Irb_IDqW&uwYIUU$!pCzjqZy(I!U$^ZJ&8|Gc< z1{=@dJ-dNaQ><4yZeN+q$M>WLP=|*qip9|Lb z!=+9i0ZynEMC#q_VRQt@uVuNN^)T^-dQG0DIO*%JLFau9)j#gphL;c-VynSzHb;21 zJS1L&;mc51@Z;d2DEJ8H&Z?8x7if)2^Py<9#fp%;zW1yvI=|LoUs(k66R>Sz$Of-? zSc`Vux%E+*rMzh8hNM9ODj0OKIGAFusBzDLSP;0EkQ zN5sVx6_0-rYa)jSDlo<#B<-xiP0~6p4rl_#95)EZ@s7qo{}il=NBJGw!Z}Z|T3!i( zI-#?SM(f5l9I7ek&bVhMXw{fPV7=WCe8|8+;QTsj0E$3;yAPTkvcVo-^f1sxk~gZA z8|@aY%Z+IpX}Q_f7SQ(nuPr+FUt8on-m6_dlHAC&QYVR>&#|o(8~75b`8aO8m?@Ga zE(VO#?FU726DRtANR>VpLC_a7>uw+c7FYM!PflLevG`3;AdHHv0pDz^#Cp6Y@si71Vo!z z%~b)%Uj+LJk|O>`>@D=O;8hDVZ8?Rp7Y7P`U_>PyQ9>Qjkdg)9aXQA|-#$Jzb~Vmy zBQ+POfuoY@2qufajQ9h7 z>IUD!Gzg)WHp*(~9XHi7^l8D!NM-v9!$|2+T|41|*kl0)x0am8k{a#%>TVVROB=XY)O%_nbP5AFwH0=u*ZJtjMJo3>Ow@p;-Df#%aZueB26bNc!5JUI9 zv*YM7b91uUf!VI?%Gw)aDo+pLzA((Q)4m~TLzH+N|1)k_8?uz9vxr4EVs?f6dnN5` zOU}XM6*c&9RMBZO^#DAoLqYZv)s%{41 zW_AC3$wG|6%RxA2YZ5WP_1-Xhd+P>2aaAZbf{T2&R%u>25Z3J6Ov?ko9Z-#GIRgNI zf2x6efqMULbem+4h!%2od3SsIEKD_1ZJrWV5<=Y=QL<+HJ1+4&p3cuk@|$oEa)V=8 zPDfU3qaw%j=F@24pfBvqK&b_>C>*^$iu=byEGu~L&y)9ptg~`i!7c}UU^PPD?pwzL zvq7jC+-drXFQF1DIMxCTJ{S2fu>pM-oKtx5mjMS5a6Oq27!Ys} zQ;HT(B0X7H87p)4UXixXK~yFtg+wA}#p++brG?JWw+TJaDZ}*OaDQt6w)`TFNtkom zxn>670Uqte8!qRMLORpZ+A0(tGDdRMF{&{2fS%v!`05wz7LgCv6U1hytRGG0&QIIQ zQR`lh7B@I#wi8tt1Ex_rDMoAm}4q`?4-HsvTY(3%ych1fb#R`1l zj6E0(ZbG-LrC6K@Xn6Yp7Wia-ik%BSgJmjVdo_vZ2I!Sw`1*$HxPFk(<_}_hNdAr= z?Ee3zid?iI2O)B?tGUfZ3~Wib0Q{kHe-rgX(GJQus^2Y~te$f{k|Z;3HclHnnbzh2 zssEV;@zIY95Xvcz?tfCSgE0Kk0JLl8&Y9B1@3B&(l!H~`1Fx<=Irgc#`eTRTXnVm< zhr|bpFs`e#=Gim#q%#Rql66f8DjpLW1B~?p0P0;z=gtXQh5^P6K}uvrc@4Hvz%=Z+ zKBQXk=@{4_JE2HzeSHm7i{DrnP!aaYg@7THt3Oc_ext-zM!rYOk3Xz23;pzb0vU#= z5NiPNe}D)=ePIN?S43rqdg`MMxP@>7>v%{}L653!60Q1u&?s%5v%Shf zZ5h~@xM#y%Ao{BdSjf{Po`?tR^oZR#0o4zt(YhHZ zhN-$-rTJku4Dj~&^Q`-yPDiL-YG3s9e)~Gc27~Co83-u=|D+x>hGzdMN5UCMH~B6N z+(U>uu23PbV7MM^T5?YKJ45`31EgwU5#KMts*biv0)8x)d0Z}a$fQ(fQ8d8rE23$B zozsgu8oCTs9Dlo-;R%4vS`WOGe5Vneb))f@dBvwa)t^4)LJmk72JrV8fh}gT0_(`a zPO$J@(CNrm9n?plZr-IUOOf~i>r>G^i~l)~BweKA?-Ba*ceLd05AHqt_s7qBp9YW# z57P4^J&@VZfkNOfTSUi-6h$W=qv7y)>iK#K`Y^`>R-Z*f%lawx8tXrlsg7+%`#1Rv%`vS zxRe(i-^-ls0JskWKVKP^6uru;wjb!8TFcB_AJoSN88X{cun!zdk|*CU4k38UU!rK1 z$RGJv|99qz417~&Az*6AVK4<9M>!P=oy(ahk-yk~1#n=v4cvTW5vRKR&tjybD$W1C z_JxHR9nv1o34DN#(l=ARCi@Qt{)HD0CaK-6`Irhx1==(ksUzBrp(32hqK(KIVgq&h zR%DiEn^y}g1~3EG?IuvwHAxl-UQRyCi|_k!Rb9gZ3(7E}5%{daHzVOFQT3LNmu~7C zd^|n3w)raK#Ul^BPCXshQW<ar&@`%C@o?d=nB;ZSRSA-codjoTc#Z`kc3 z#5oP85ahh!9BJH1fU9R_X2N>_aEBonm82j@o}5agyNn-&tl}6rFjhyzZvZeWV&lYh z%41M5d(fj$M@n#Hdx!RC;O~>kn%V+16tLPdtl$Zkd*X-ov>cirGF%g(2cDhrMeh`% z{=|i?0slh|U?YeRg=GGKeb(X;n*F9PWt^&e5E3%R9e@1Y@JUsaaRA!m zM-?qEpTnoNlx(%rqL1n_Jw5{awI4i>c*YtM}EL>aaV6k?1{%foq@q>lPKAD zD2>mzP7r?p6jm7fcXJK_MlmT%gJMt<#p-)c&(6Q|-}}h=7}Om07ZE2>q2S8d$o0%- zX%c&hk9TCPg2G3LNLbM?g{{A_dnmfsgBF_C^#@Qmfm^V@UR^u% zR3_mj_bFW%sNZFD!$sH6)XXgLUk3qb8T=W?f`m#W;KHODGAI!vp&37LP`pq^JWq)JwA%$fkXg_WI>PTST+ewAgfo% z(o-XrD2SFqP!_ZwhM58oq{@{*)XxjtOkDqHrw@<`F!#%Z{@@-U(ne_5`Tp9Bqr0?0 zkt9lNWZayVWO60jPw~!xpO*j^YxYzfQgCsXUM-PhFLlLb{1)eNi$sZX*dD<>KJMQO zpzaZlPNb7d0SK<=(Ebw3%nYFll~}Hu9y?|WIV-gV(>$>*Aab?Ns~s~v*&5m#q6sfW zD42W410$L+P>V}d`NSQ@lg2<}KYQGMF92TrjrHDHSJpPG;CDh^a3HM*2H-nIa`$7~ zgL$S}OMsl%C0GW>?ErkQi*?Ryo7ve@XHF{XN+CrXCYkZ-+pvudVn2dyXs1$#A_gnO~dv9 z%u?X;2~4N>^+sJ;nR;?hU<7GVSFm-d_JyP8bF?`95Xp{sjE`^u+zt(0bPC2G0cvWm zyyD;ea3#2Cj={S12>N|)juAz_#VvS)NO8Xar$jAHt3WI02XraSEbJn@Wx$x;mzS@= ztMuh@*D$nlDky%N{#Kt{iiwTA4TDA()`GqTt^~=#rf39SS@}#6KW=7SDmTsm#_4ys ziVha@*OB^#8(1y06N!z8R+K=nx3;{u_vGTjWhab3I9i(U7_D2kjx1i+a-R=_Fq5oh zO~S8n!PQk2e;@1zpTZ&p14O<-hULbw0=!hz?900GU{X(j74P*^C2a)SY$NC_NV%`? zehLZK{A7axAzp|R9-~f_yF7;@Fx`*HU=ebMla{=g89fbmA>V!k;bKv`-gN)~By_>w z89xtOFo{1P7Ik&=Oe zSHKrR0Z_%*Px1=1vm*c@tN}1h7IwlGmgIX0a9BZc!X2!0_>3iLrTG9QSFtC9rAY}+Mk4)&hZkT#uZp7WL~q4L^zck5 z{iK~(99>#87z)|BGyv}J!lg?B9F}Xi_ueil5d3RmZOxmZAo4rWgXk^^o}FR+y95Rp zM*M^XznC9w=;+{qD=4c!*QEi2`?!Wa`aLpMA|v;S(bY-_7RB-D0d!->4My!00z-w9 zxyviFoec@As4f0jruE?8?q@)V+IEiu$p)c%5-B^c$E_|uYp8pDe{hU!2(gB}<% z2QDGMDiHs7WV!eeVyZ@v%m1gN9%EU#QW@kCV^2Oy&i8<@Fio5-9Lc3iznsaXAj=$r zG%qkWMkw8w<1`zWPa!eDE4P3{N(>Yc|M}l{qoWxi$CVnLj_heJ&o7faG&^ zNjC~HlRJQ;b}R8+VDtk@t=<;{1m6APMYcP~P<5LiJ}@aSFYogj#?P1z{5a_xM!D>A z1m!1rK~&}6^YV0^O2geQKO6xnobM&+6Il?_dO-p=2)q`55k)*>`q$UAt(XSdXf*z2 z+k0_w8CWUXM5wndR)N!x%(IS=-2(o$tGDbkjLf|_0Hub*9i3f+WUt&&Z23E~0D{UQ z>_Kd7`Zw^9ZP4I7z-49;hL}j-DU3sm<=BRMceov4evIV`zVrEZJ*z6P({*yb$>Bv? zXQx%8BZ1!Ul$Za6xS*)l5780Utb!? zn`eap^Bj<}@B+wFSBa9IFM762Okj7r{Vu^_LwQ|T7+7;Og^~eJLgqsR3(I4};e(hM z4emWsQpP^O$fs~cHKCxGT=w#MoCV&ieB$@-bw1}Br*GhvFGTY{h}T8W2PiM5i>KP< zwa~_ufB2A&j^XLKdTKy=i4uGwQv?7=h-#UL8ozwF!g0Bfh-r>;vR@EN+fm5&Oy5A< zRXX~^55WZ~bAX};m;RP48ULM~%^=A!J=#-mX8e|>{gP^);Y}aJXZ9Ej=to;HZ-+W? z`&vA8#hpYIqfl>m%>b5(jDNM=47>neCkMc}XW0hoec2WTJ7%UabqSP>x5BMG@Zu|W zYum_ai(;wZ#ZX)mQFiFBf_o-D4B_V57eKJDi@(6GsmBE#)V~T}@N>@9Wv_pe!ed*2HJJb&{QCF|@w?1g-bzq5O zF^-Mt`gV@csHm$^vBr-fHh1 zQc}-8zkpO$t`05R2dUcq&l)`6EIr44^37v5coyHEesHtyBeY5ey_ zG#ondZePp-&@HHh7~uhZKoty{dU0+7tGEOJgOsQ=LGpA5eWqr&)zaM2Zq(e)bDcQu zy0GKQjNR{?KY6S9q3;M7HkSbO2Kj2oT@Uu1S)BHn%z3}&5ZRjRJU5WWaa!>_av0Sg zKYf(&1bZ6}S1Vz&FNg*;DAt&#USsGr>qb1-jp!~h=q)6U zn{Bc_F5%Vtkq(x(ZjDRYYux1vyOwFpV^e<29oV0b$9dpm7Pu;QAl|dYsgb^#o8vGg zSuh#wNWUnfZ~6`bC9=T#twCs^Ru8Jj{e*@T-!Ula^rz&d`%{NKdTlH;57L&rp4;CU z?x#9qa$kAIJ|n9r=0zp0?1_Uf3NK$sIo&$WLfy+j1CKR`)$kyP}`*9rR?CGEbju2U~U>UHN{))iAu^ z&OLyeh_2BXjQ=1Ec`nGYa|k7}r$)X7C$~Q_Z7!5x>@1gqDrd)lUsBR!S?C-UR8aA^ z7U1NMid7&XI5Gcr&q97cZacvx@9K=UH(7XGPE;CuKq#jO_Qx0l9z-OUgDCtQY=U&J z5bzWn{{{$t)t_~VM56n&gn8;<&WFLAjmuNXrz}qI;L}_Qjt1^AwgMb(L&~($jCoXqcYBAvVIbiVBtAR1oF2Pcv zEQ}Agff^&EB~iHoBA%V7-p=gb#3nOv0QKSt%CR@XoY1Dq81EBDEVkf%D2^=x0X`(; zc`#L;*j9jU!eKx^$G~&~vFMX_v4b@xq1mwDEqKtz&bR@b0xt%0ZX9+%b8W6#?Q`5{ zu@`&tN!Kpd=5Rj^kJ~(s+X>k=5{E8R8-VS7P_%m0Ztq~IpYpb$ySb}ZLtX5Fm?sy# z_(@wxZzLI`yS@(e}fVYgti z$wC3-dcz&%VpYz8M81zp6_G)}_UOB@?GeGYIx}NQ8N#KiFY3arShKFbW6n)00n@ZVG}&k#2z!?cyGrWy zRo-|t4`CG!gQ`3SSj2iI1C8)Mbc8rHhdA}QgVt9B74#fY%Q1WnDto=iZ#&F3 zI9@4~Mf{3w=s}`g%#80o&EyDhYZ^e+0-!CpR?Ej6hE~0oEPi>6zBK8HiPw4qXJuo) zjmcPH@lJzjLDlX1Z!H&K2Jk##h~u(nkB{x2?xR~kExFSNdNOPcmm6bfm3asPJxSa@ z&JA=N2RNlbGMGr$f)gO?`L$iuDAD~o<1l>l3Jy6pZD#Nf;k(RxC>{rC?R|?)?n7p7ILN$Q4sE^F+Ip4> z#FFA9tphQEOBXzF#rwzg8sG zkrg^O5)qt!+f0{r0;WS<( zq;KPy4~2F2;TR;NfKKO_K@QJZgumjTBgyqHsyY2QnscK^eNE6VN;-H6X~6Pe2VdkO zDm(ia2c>Kpn?7~rhDcaPdpo(n-S=oojCA*#_-4@ZjLUQ+XV*zl+^a27vZR2c)eO(H zy>yP)3dGavb{sxY>LWW=jqVY;sWU_QuSMESf^BOri(9pRA-5UhILjmP# zGu?(v4;;0ejTWiL!sR@gYfWRlk&VrQ3qA3}C1a{9Y64jr+siYM;jG=i;?Vb*UJIHh z=zwgv?d53}$3BfSyI%&Hdq9x8PU^8@$tld4fkWFv5T(SGyvv-%lMBI^bJ*e3ig+6$ zMM=(!{)%dKvV;24#v3IkTm4SxC_x(1jQ{fV)7UQvyrvf}hf*aEmJ5wTkYR~l_;_{O^$%BUgSy5!(IQlgZtr$4xH z*Lh`b%dFLdIHl|CL&-6Gephb8UAd_rBHqFG@2>_#vj>Pb@t>;kYs0jI)>=OEG$z!# z-ZFP`J(F1kLpssW@0!%mi*V#F^swu?4xR|V3ow}_J6_KY8MVW+aebUT1QHkgb3neh zdTrRd1CAj{ZFX&WZxX}c>Fq?Y>{&1*oEU)c*oGablqr^*zRGP|eU>1cO^Gg(ZT>Ac zmhjwR%#9^w8z`j^gOEC0ByHLG!oPjVQqOa+sq=nQ{f#IqB;SzKtx#2L1hyW*rL^ff zM)QBzHMZYRA6Hc3aX6nk(dVKofb|= zX0C@q*xlGi>gCblJFDgYykXZ?`-S-xHw0s!=Ddyw(b+jW8-#Lt)wUTr8X$xnYjnhf1%n3i(Y`G&Zw}1M$PmnwZ67Jj7#f zH2<(!B;`j~a3XnEOM9Tj*g&yt0kM(@`9b*>tl1QS{f0I`cP_zmx%(_cCf7%z(S9pp zxwTO6!9!$^uBQWZh@&+bHfoE=xIziyTL~VA*45(=!!wtQroJuPXAolZh5rh)DEya*o6toT_4sOz{fPZ z3xwQ(Z+R&*Ls!QTnz8kKu!BS^Ui6dz?r;K3T#L-Fj?#1Nd_j!D18zURXt-|jZ*paC zX)bOdsC$l3Qia#fE*eQVcRHKj#20zM^lwTO{Gz@#JQiR*`-Q*3lMzd7$&DDi zMy;w42$j3K=E*M(m;st)`2Udk#Il6@R}xO#s3pLIp8Z+eRsknuev|^C&bx%Q$9s^u zLo+q;=+7Ce<>f{owTbvL9qP~?aCxtM9hnsg^Pt~K4MZTx#XX|wABMgPozVZv(}CNP z?rIyl>_s7u@4F4;ioe*jF&%;>1zR@RH{BRSphk>}@2?Jj$sa#}T(JDe z%K2bIa_wEDW3o+S)7HTPYfe=Y6o?2)0kUU5Iop&CSdJT7mC_^M4*kLQ>@jYhNM?Ov z-H^CUY^@eSJ;1P*10R<}q^uoV0}t&9`?PxlZjl&?gXV*?Saw`5=z6J&3U44Uul*>X zQWkcF$V}h@f)sJ>OaI$KL=n6|?`p>tsJC{%Qj4k5O2itQkiXt}v<_K4|7&}*Op%z`auPOlEWGuH?oAlMWZW`6c@2^kN(vMX-Vib#3G#2vlt#3q4M z!m#!p*Ds>IMpzK3R?UYBhPwpr!rTAY%q@5gW+)e1U=09)nvEdy1zwgt_x276RvMl9 z)57Ie%)6uR7`n*imfj*C80$;08~4Ye;c9DVS4JGifo!FCE;l>U0jgc8llzu%UpoK_RLVzY=u5ay z9W)_m5NXAYP*`P?#FjAZM2JBqNJQ?t?;>+QRL&&L zWjVgjeFmy+hQ-}+v<}|*(Y3v6lWw}kpqIABQteM;$V#MS4u=vh2EqUH{|JTs27CCx zw(9$wHi*d+N{b_Pg2hX_;JED4@2t3-)6_&**Vng+o}LFhj9`OoM&_~60lil@YoDwt`b$TI}y1DD?+b8 zCVS$X@pbfd1@Cq8shERG9c=YEG(RDnivJJNXVL?|nGYbo6pS3>4T!GRZ&hxj`Z zNj?PSARapv)^b!5_cwT9A~UjhQ;z~s*(1pJb$rgl>K7Qek?eB_Cvyq-An2D}LvnM) zh2C;Z^ac{i;I!?3(XkwbX=rgBN=}mqW!_+}{G7O8Mxo1_kfUpn#z7vg()9N_aBv*j`ZlMWvFw(aEK43t*fWW>8T_*KZWgj}$5V#HS+x-< z+e4?)VwW+k?=EL#Tjwwd=Hfq3=W+oxj6pF;oB8|sooKG&7IcL|$^1sGK5cfCPj9KT z6%YpJk9eys_wV3q_b%m#+l}DP0~T?Ah-24lw1jg)`YSvo+!@&%%k}`19JumkP1@86 zoVNWHd~yDWRCK&}WcSYv`DZ+skhKJ;@__>uBO8CsCV@@YapOgFkqN@Y^$5;9anK~N zRRg-L#;%}qbM^NzBBg3uxSGYtE@@it6e~5hpE;2$zpT8kV0UqSwD~&E3GsW!?`@O= zO|cFqUHFkWIQf=8H=55!cj^)iYvI&{AGsz)U?i4=y#hG+<`I79ibx0M;|v2 z^PUiYdmS)88(VD?;D*SUv5bNpIkIS<#f>8`I=JNeOax(5a1G6-Q0E~P!ZpRftgo5P zh(!2D!YmSvJ^aFOAqWg4v1ZrTASVy&BB==FkK&v&v`7d#EPp(^-S@Vz$o!?z_%#x~ zp!Iz-jGxF@I#KSR#>59~eF{EjAwnAyQ-?5Hmw2CoA_VTv)wro!KC|;^h*i1(tEgptxtQg$42o$saIz#<<3}1ZkXeF2AY5ND`i55I!dxbLp?e5`BH1 zEqv8*IU+c*uJBNQF9J-xr_=yoPC$9`5!W5k()7$IiVZ{xV2!~ij$^+PCKr^5G$B7w zGJUtoz)6@aJ#P3?SLNx$;fnqMGMDtW8iW(u9o?sUwjZehjw*dSeKJj!m1j&iraQvO z=0jA?4xZTu)^)8ZqqB>UuuznOi&w-3+=KvCX`5Nmr9gyBM73uOM-4aSHNR1FJ0b`! zw+H`aSKUsKKxfBws`|tW+jd^cNE$^A(~_g*Czh8dZqq&^EJ(%;^n-sWpl^uq?v235@s z2WY+1AXSoJvk91avZT02Dr^GK6X63#955HDyCeivmg$rxA#>R^WyFc8AlV(V$=0|Z zel~?R7k3CUBN!H|tJ2L8?+PQ7nYTy_bP*&=Nf;;zV&vRF)5pPT zb5@2hLh}TsLq{+tA#IR~$c8@}%2;M)aOPKH_JA6QYYDQd1YW8?V@jml{OOiv6RnPA=)fO~J+Obc%uI@joTVX~(z zD^6)=V*;And$u6=b&Oys&@;gc`pfX7mmnKis`Y+4r7JS3IiXCWu5Sz-3vw_eGc#ip zWVMFG;t}I*PpEtl{|X`Fc!dTOQoZ8(AY$x^4OdD>_t$xGPPCL;JGHu9yjP0@MW|EW%BRvyP6&$#wpIY}r9Lh~Y- z^igCSH$`v|zXB3xzlQwmh-~vLI>c-R?-%rY^i8mFuYUk;EY&)d3WkB3kl`q^%R(w= zp3@{g3wF}u1ryo6T-b+ANZq&tclNv&y0{O59Ks`gz$22}4SCF&VjEuPfrD`_8ihqg zK3jbxw?N{%8fs0)Ql2~6#fT9MW@h_oB=qGY+kK)#o=M>5&XM;w%?R6yoS!GS#%$0} zA&;K*0lDQOEaxFMB6Z-?a&%?B2WGHG#KizQd^6nhDFo}ukui}i>Je9~e*(`llY&#q zPDVi@1~lQ{gapl95QRG)i5l{tn$#Vjc3qu`tw#*DDj`3>mutu%bRC4P$RYX5@+y)I zK$X`W?10`=9ln1&RNmJ7^wz4{P80t-)!#deOUtmv=a8+CHnXcUOX7RB!S*E>BugxL z|8<2vvnUEo%&E43eT+PXGj5e?^+X<#reoFU*L!ofEvhto?dQ zRar6YmG)ZjIL3sLmp{A8N{k*!P3kpVels6 z5|C^s&rHN|B(BGR=ARk6f!pfKW)yfZ?*kYdn84LL&#HHCd#>2&*p?xCq zTgbK_lKei=WRMbG670d|D!`kR4$Zj2QxVWa?w}zH$GR#UI$Bu`2nq=L3Bq&;GDH7h zCcv_io&wGY0qV@GiSIGKEBh!lOxXh;m;)r-0+@G~7;ltD4;3q*Wgiy_Sjd{;JD%f= zl>p$8DIgI&YlYCk4{3y2?4Hkr5^2}Io{|bI)B`y?aT{8<(V0c7F)M4(-ILS5X6q#a4vJhYFolL2wY$tZ%)J+ zn#r6_yw-yh_z*J&DUA(;3qpQuX3_(}9nl1Elhm7CK1XYf3)zt*R|0LTBl>FYMlvRd z*|>4_WR>zbwmNQQx`0*&JAC$cy}E?m;URRpoDO7UH`VmQaJEZZ9Ia@#om%9SB$__4 zg|Jhgg!3}S-eYnmzzDXGN5J{Y2AQ_yzVcxlcTiWPIqgvF4KryrQw$$UX_-}$O;o6G zbuS-4!cB&g}yvr^w*3F7sOyFWYma{EPR7@b}QM$P;+mYaWYugBI6?*VRiXUw!q)HN7jQxRj1r4;!2$)V##(*0S8bKZa6 z2WRDeYt{bkQmpvc9*Sdx| zBCddwAzx2XnPX|#ZPN9PD8~41NVzrCZ?db8YZ$ONd>GYsf6!Q-{^tw}*Zimawo+zx zq>S)Fz2*#L9|@y)KcI6m27f(p1&3L%5s^t~!y|+~u#kJOk zZd@+UbbK9h=`Cc!;FI}(jub)XdSYTB(_{9GkpvDhgT(5n#H^skkwU^lkK3X3eqBQ&pe59?n1cn>-`l?Q8)6IssIau)<49N^kmZ37#ZUE#P4JaO zErCr1`~m5j2Q~s(s%rYuzZU!FOR)ntW72%h|Q+}bUHxf?;?aaNdUH^FEYW0WU#42MAL-A|nn*}F1|M5ri&zZpge|t~$ z1&n{SF5zzRr2~Hb{`emBatgZXp}d5ISnyGEt<#9d0oD9&dQjEuQjOHT6+RNwwp%SL zsk|opg$H&?{`D(*5~!WfG-fIwyWp$EZYPltaohG91{sM|Kx-f*UV{^km&o7>C zppI|eUBUYQng=HT|DMx-Ov!-_|7$q@F&+OC4afi5`hPCa|3Gg@Or%>FLZlN&^#~Cp zO~gTjp9jNaj7~m8QaOPPIU3Cf5q%O-#u1?`VFkdQlt33iq+vuYFm>Ud4@+gza6D}{ z5^)4!8%drI*E3usv@s#5Kf4e$81&zFz+wJm{=481R9&6|G@aSjgkZQT_R1%w~5{IpacYx8aHH3;GvopMB&{FkhQ3v3|c z@-)dWV2iMmXwLFMkQR?qPu!Z`48#O{wetUc4*VlCM3v&IjwbP65%N2zoYN%9ZzRu2 z#*v1~oWW@ZQ;r0r_E3x1RmlKT%IzWi^|Vlj@0sS09{ud&A|-@)X;+?v%b1#%y10cWt^n zN1Xrrt-mc;5Ve4X^>yisq;2=8PP1JBj;^%-Y**eDpeZGA!XUPLXibsK_;CH;(36E7 z){Vt3-O&zpb&Zb@`cLP-O_aQ6)HN=fusTE$Ts7x?U#{+ag zi22pjaJsfoqcgfWxZl~tfH_sgMt_M$XGFGK=J>BSyRBU0cH>y5x`pG3#>pbPm(QO+ z=j(78iw|w+x&EDK3i;Ch^?I>5#0J|?Q=)H$#bBe8BvcV@;q%=8uia-9wuV}4|Hac_ zB&GL(w9e*d ztoqjrGY|7oD+a_sQ#ZVo@9*rqd`#e9A93U)jtLtsF0MUGlSA@&oz1^S`Sb1fAfYgU z)%qM$0|cg9{_ojke@KaC9wG-~&j#|Y*Kh=q*X0*g&X+)Iqb~;{6?*~ zcmC3)?O3p{Z%tRhd?h5^4gJ{3n5s;&LXM^l)ObF!dJ=TksOZG6pw5C!N@Bt)#SEth*VLjCH-sF#oDnk*lVF-7~*9P@_vr#?CB|BPRcVQ6gGM5qgMM1 zc#1$MFv@gOIQ}_qH}Pn)Qg2_ZSh=#z+rrsc3#@NX%6JBImW)=nyrR1D(w?DbY%aLO zZs(UO7zE*lqC4O$RD?Unu?K2@bT>3K5Yc{FvB~wWzP`rR?l~IE0sT}4^=(-;>-4C*Pz|HreOO~_yr=tzs!*)r~*ksU4-|IjBIJ8o0- z)#J6(#XPSJHO;Cq-M5F_++RnF-*e%W6q=Ts=uVJWERk}tGKICqCi_&4)1ZY_i+ODR z&1VrwAJiz14I4JpmI_mE{~&8wibE1u?A*TlbIfH^)BN%D@iaVYyn_DTV)%{wcoY#) z=kLp{ksA+>kGJ+SMQ_602*!HeR~bmP-a9nZrJb=~#j3?yqJ21&>8v3)*}7uIimPJ< zuS0G; zS-30GwYRs|;p1|HdvDe>~msinS8}y|wOpc@tXTA~OGpleFWyx$$ zU>m*A-ACU|H!*)XD(sL|ytp>vd_{S~JLjpE(%lYp;quM%&zt!};_@pArTRJdf}S+m zu<6EyHT`pCyXYpaa|s=EKQ!RE{)ui-7^7m3e0=tprU1w9tUHA*r9QS9pI=2ZK<|)Zfl@!Lvwmmpu1zDd&G^f!>b;rl} z;nqn;!_^51mBg+9f0M@1$%3BbB-UUSu@ae!c?u5g`k@T+*V^5WbA_iEGA%Kp;bxbf zvNrrQgI=407e>Wb`AWUG!pqEDzt?VIX3o{5_QcZn(r?n^ax_2=rUXzcj{M@{;v&`e zp~VWy(G_%as7s|Fb$FM{VGTUu8){i+JZ#JgeUUxpU{C~s&8M(Y`+H1wzq0dlvv;qx^hxod2uVPOPkWGA;? z;B)iYSiS4jdF!8)SA-W)$~nc;g~~^|(aNtI;A+*HNvrc6}P##lV=4BbtqoIX;yAhp~^1N4j;7r?}cOw=fJBab?%m z6}l{X{G)b*w<63l%eNzk4jm%LLt^9cURd_^CPDX+c1u(U_GSaNEXJAz@~Q2cWhn)a zjzpoJJ;h@Be(r>Wh2rbfv< zUCZoZH?0BJg$IPZ0>%S9=cJQ=#J8a>mVf$k>f4bh-XrM=7L!wF=={9)BjX!bxHdU6 zxhd^~REy5@k}q|QV~K@-(y$7{&v|E+CzAdXoz%D=Cxs9|ui_gqOTB`5A<`#YJ{4GGZ}uYmaQ9>(VBEA1eIp>)@}& zK(WUwKtHiQ=g}y`LfT9&?W%3V68VXb&aGQ{FCSE5{|wY6(^HJz1w&90CBEAD^aTu) zK%O%%|H7lcTd1=%ZA%`@&EsH1TKxT0ueugBMUGM{Vq^Nvh0}IVe)shIqpC6nbG|<6R&i@#zgf7jbp6diN8a8ZDc6IoDlrf7HG9$a81(I6J#z7yu@RCa_=zWD2 zuGS>wz0PK@WdV|F@urnAqtAZzQp4wu+f`)eW>&(-oqSOkp z$O@NZW2Mr*bkRsmF7AFyRJ4PXFYVWYGiyo z=_&iuwywEfr7S(SQEhu#WH0w+kM{orm||KZ<0s#6Qj0G=v5E4HqMc@@4~s_8$XBez zR}_#ExS`sr^nJjdpJSYA@(mvG&i+ukY%v}cyWY`pAM-2|MnU)6QtUI+E=GLU%1_jh zBZZGuGrH!c#(xHgTtYiEsTi)`78|vgPpc1&MhFPCS7eOelBmEVQ%BJw&YXJcL5i;& z-~f_q^4<{zJn*Pt`18-PX%`)uZYUBw9shKUoZ~kBf5Nc#5QKC#9ujb#>A`DbIcO?;u(t z2=42{iuhkbC1@RQYTIB_weI?Yg!;%oM*A->5Tg`qMAc&^6xqi({>sPjzm421#_q<_ z_1@XQs%Xg*r$776S*Xlcn-LSL`0LxAF@W2Rh%lL8yMw&d0O@Fe${SVB{ed5dGz`I6 zgKZsLO-tbcL#vVw-)@=~v(ZKF@ZzU#P9hrVV-MPU(uNvaW0w0VK9`#QX?47`ycI`( zt1~iHMR+ zszZ6Ne>*7Lwdj)jjmFj`x!X8hUP?`m+b!2&5!+?DP9P#ps`E@`>TcJWcdY`s(HSc1 z=cm*tjH^d&!=Z|?U$-oLRh6n1Nc)q4pi=D0^{btWDUS(&zn~7;eup#2naC1o zCyHcb*DJ_36KNKt;uUXALnaGM$dTnMV%ooJ(k!gY5KoXhUw`?gG! z=R=>@5LPtNV*Z(jr%wFbdw-DQ=B>lxkipw23!gjDvMWn{0Ck0|Q0aD$Q$Y?wqqm>Lv z_^@B-%=zlQ2#QTtN%y>6XR~NeL%o`gwT7XcX%UN2kB*hnJ6jdg;?$O;yi&T36Mv@t z?mdr#rgFZ2&R|Qzeu{`y=1G11+HBsjuq6-Aw1!9U(d4414EU*qnms#5vA3!T3WS0<(JHRBKe zIAPiUFj`89;&LlIlXfjXNP4_k*jgmho;Vu^R?&4Ex-?x!ea^qlkdmDrMz?U9&}4SE z-(I%z_)tphfQw^Q!jGqlyS~+h#p5)8hm(6=3x;zzs6$2oa<}of-B490k@9U4$b0S= zGC^M)tir}IdEV*jT-AO?U0tC3Y^UbvUKua&WF6>);R>n|;|JvGNb7g8P;*?M6K-Jz?%2N+5Dj8Vg`CNtK^g==E~~~bS*^5&dS^xJQ(8`S{3^^^i4`e z`Ygr&PHWZ4ABJ@)WPs|RToj|xF0U1_hylTcXRA;)q>$Sie15-8n{)*8)9llvmT5mX=kI8 zKdMVtQdbMW-iAW`el@<^U^G&j5H1@_YWMfxsFHxL+Bd%I8kA=pg#MCdOcoLK3!z`E zAg}3w%1_y8`b(c17Z=wT)C&arY061~6SPy}=5M?b6>WtAhX|BteC1`~^45_uv&`$w z6O7etv^}=V!LhrD)#&Q>>5znm7T#s|_Ns;mQ7ew>R0MY3Ufk6=Z-DI+IEJ6lnHBQN zV=f1WCOG$ubGr>jCQVpBnxv=g@#Yxz46VpWvvqyZva#isX2Rl(=Ny*uG`qW0CkAGY(7qzHH6`< z_^TQkKRp|UMGpZ-xE0)q-R?Qb%tw`7-^zUJ{Fcl6$uP^JWjWnSVha{ERR#I>OwY7_ zD(25%_FHu%4((duHuy4&^90Z9);5e18@qip)^u(?r;8Ra-<$MvjJ6}bA5~72Uh3cB z`eX-gL zuk~`F{BonzP9fKlt|@Auwb=wNlA@mfJ`HT(HrN8a>{rx{@y#r6srh!aR9kH1dR7L1 zU9WC${RKOLsC8O(3*81y^gmM9s@`PG*-VGG4$xE@T^t6jS>0H^3JqpIP$HFaIJE7T zvllfzyK%mxuuy)9k<5<4pbJK&H)j>LgCG1i|<6N-2 zzea7Ke14|I_oxf;Qv$zVpe_i9>V7zXsr12$L>mtIZq8VBp6h3^&8}X?ytF8z5gQ4b zp#FT%*MZ!PaK95{+6vEY-NhY)5PaI%ui(`c-ej(`0K#?_KE_kBQV` z%bXBndbFC}=C7Iyw>PU&T#)%WEnV=IOWpyC!C@9<$0!YoCo%$_k)oPPbi`RCRTfX{ zTCd8qFS+!FrZ^YT&l%PI_=#d&_=*PsRM0kts}>w@+Z8YpI`aUp(%ZCw)kSR~KLN2ebVjkgu4T9SEK%jTWZ=S4w%bHG4R5HX$cBactPMZ48`5Klpeob`Dq5E}f zYCK|`Fz014qC{q{zq@j9a!N2>V$LyO$wNaY)uBHP1?W6_>AY_4uVS0!s{(&21`5mG zEzNX^mcq6?ea*(I#3a9Bj*rs&E*+ZRr)n-M;LseEPiW=`P#B0EoVOVyEr6ma^G+?d zxbPBX4JYf#0gIukqo=A0T0ivj%ey+1(jzD2x>d_5vGjTe*Y{H~8y04|nELW^`=$1V zoxd$`vU8cyxla8PmJ11<1nj@OSZ6K8gVVwlm!BT8V&#JBUr^V4>m6>8y?k|Z zuWkxnsu-t`w2iItwAtO5GpJ{42=Psw{(3&NgOibqv+izI@#*|z{S~Jp0q+N^@)x=J zjT+vZY}56-(KsZ_a%7JShX|+Yk)LPsVpqRlqHAo1X2^72bH@tD#06qoycKu#-)-yW zeL@8#j^U_0Vwik?-)4%fs7l;MbppNpB%{UR(5ZM^4Ff0DL2}&q6D!zGGK_OpZKS1{ zvVUy4Z$D6+SMQl$weZN=TeEq5h8le`v9)q5|9(;r4XQ8b5%)+WzVr#^bW4MpZ^gKO zY^Y3&C@uNo*P^!ZGxTt0VeBV&^5lVuJuzKQM;flQ#A-6qtL4(7BF7hGR-ejM_|=I! z5l^W>H5!@!vC*G}-|e;RxB$b|)@n}4v|9bAPV33bAB&ob1oOhzu=6d!a23O2o2`d7 zg$(#-=tk8L`oh zqE++N5ZZ3TWuc6!+7}fBRHzb-hEZAMVz=@7tnlpciG=LH;v?%CbfS5woR~mD%ZcIuNlZkFbuONxsM`kcDz-kwFQgr7a?CDgT!2j@#$n>*k@ypBAi z1}dHS?#@nU%=8X*I(3W%8yt7d7?$&Wqpy{Y%-?ne%#E9Rw}D=IqP62t0j+VQ*mJR) zU#qUtwyK#A&YHkz7X&^gy%$iT?Wvir2{b5cl$&|M5m+Wbt#~Ua9h;icxKjNu)7~j6 z&hjB`tKj})$1zpszsh-<2R`5)Pdh&}qLk_kHnY%7IxV3-L}F%(ROjnFb(05CfaiZb ze5KZ7%DIQrx0ffWGt{ndM|y{mp;b`^z?UF{lQKRLKn)=Bu#lCPYF-#<==4L^vp)mp zAyd(2#dQ;{;xyfqdCzLJZG-purxB;sm9$GMwVam?9I%KRrPxo^EX`z&mhES(W0UW*go9fYd&(*1XtFt_=^? zfZ$l)qtClwF*&gMsqMX-0(7~lXYGozV`uVqGqh*Cwspb@S3iC|n_u=wF)a{#nk-78 zc(vioa8l9hZYKSCRMQzCelKN4ZS!7>3`tDsXOS~9)=b}(vaMcrd<|+*z1R?5^FqRn zNr_pv6Q-M>`My?s7!S1GiARzhX}%QwvaFm^XMWW|@USr^L7k{C0In>f;w9&T&! z^sOt3PQ+q}ZJFQtdgH#$d$DI?C1%Vu9#Yqg#m?B9O*&FJAz>#v>8eMbgqGju9xKjc zVV-^ylOer+*Znn37B(wlqG%`nI^3=Z*V>XitIQ@`50p>?Zdj>150bqcheirT)?eu_ z$PB;Cx54r8r2i?h2Na2v(#;#&F!kb;?N&o+>yGAWdA$I)U6gTI11F!vY~<-evH~k@ z>oe@tGXyg!T9omtr7TU4f6npy4I7SVxT^2!IFW5CafIp~Yr* z3P~sbpD$910o~Wb0oN=I9 zPFnL*%jX4|2cku$b*$==+pfUY@QkGL8Xfjn>?Zw^zt>MO;rggon(Cerv02k7vX!G59Sd6RVjis5ry?JmZ;nDT;n~#<;eJy#ppsxo@ z)B0@FDJ_3_Hlv^`Ul;v%G6QH1yH0QRs!QHX)t`A2^EH5C&vwxksG50uTKxt!(A*mm zQcxRhbb^go0g8%7`j*NxoE^;1^O$VALchqjiPd7Xq5DhgWT>EB2=Hu+ZhzP4iO&44 zC#Rkz9;POOXlj)^MQHq)lI7y%|50=L%Mnf0+nstp<@1_t*6w5fGCavu9cD^vJxw#+ z>H1*p0)KtB>qW|QgVQQ?;msY}aE_=0oH;MVoKA3!K-A&W4 znoM;ac^3PRp}u}0PwMS;Caqa=0(?G(Oi7siy>~j#5LMwJzpVo5B3i_*UG8v^Odirz zQI%m2kcqCI%9Rmz7`E`;G$!h*#jHL5B|92U;wm{QZ<5R}3}t$^bw@m00WMTy37;7& zv!omjc+jl3^vbBN>`P~}0P5PiIkjC8q4x^t2{Sc7nYl;V=K>lQ8IiSprAhmvc;I5+ zOjU?yx)h%*kli zN|83xx>{c!!R#yWX*o$YLQxg{4)&9^yVw*YF0J5;$Pn)A7RgwWDJdS+(J0(7F9;9| z+ELuV?E9lTbW}h^Njt9gtwd9q>DZta zS(v5Pr$#fkDdYvz5UXFBst zO{9szY~WuIYgBL})z~GTSHe5njdJmwTJk>}Q^=qUj4RCM z&o4Fge-vvL_&}yls-j4Oh0E=>kTjgkZmB+LTAF3L*A6`8h?0CuYjA@V17ZuE-+qEoay5zQD|TeuhTz3aCRzVKi9s6jt^ ziJSP9Dh}=Q_`iMq)L%AG?m`GXW4KgF(|zZD7W>gp&6r}l3!-_hA9fUf1tgm$Na|?~ z+5AScOTJ{xby&UEbXK>jo{kzffN!0IQM?DdLJvb*I`n^cWlF49D+oOCnl+BQPZX|wTpcx8Iw*tTG8ot>d3Zu zZQe9%x+{KsuAQg!uUM{jtxI3}>y9bEWpe$RzUVg5s%PmSbV2ri@%odt6($ zbOdLtI4KQzq5&Ikv_%)uM%&7~Crdo5G#Hy}#vMjS&*51&)>~UzO*yqu|RM3bBrgiG}65z4iU z$uBA^7?5H!IxL_mYEVYsHJP*9_aWbsqZn%-~Jyzw%Kb4kw0%;H4ucPgxiQ#hs9Kxr%L@nPuBh z99bb@ykKCl-+o_NHc_oIMw)A+c;=$gM_P;AX3dFY+f8T1O1@jHqK$pkhb6Dp<(}%k z(D0RfV@;t6KSL(WzM*w}1^-)SbkXHD(++)KSZ|N|xwRU!#!aMQvD)#{X^w~LNyg7E;i6p@)l%k2P z-n${Mf#YTSz82q}GxSHXy#~h(k$cNDBtG-V;o(?ik*TZ6wF`aJLIy(|r&WA?Vw(5L z(@t3pnfg_*RWjJ9=o5P>nG3e>$_|c>yc6^@SsUxn^ykzxvaPk)i{_yx-y&&AzW<8& z(Q^w1uCX))Nb?b#JuR@7p$!qm9W7yHEzzBZ@-LRMyYUW>483=W(r;ZxQR)OUh}|EF z(I|4X7@F;P7{$!(7sz!Hy=)ql6dOL#8oSb5R$8jfCa>v0+AQ^Lzfgaa7PDad(J%Kn zPF`Fv@Y>>th-}=L7NrM)$`&a1-%8`lnJC8@6{#9mnqb213GW_)OjfL!pe^5T$LmX;0Hb_PsE@n4E&7Wbz#6=-2`=)%PzBOWGYT zq230zkP$t7*Y_f?hIu?S#<=U3%Ikb|p5s>y+1+lqzv}8wm%aNc;_hvydTU>S^q0;q zjGr8{@BI33SIzEB?i?8!ElZ4w_4gK(#!!&0LNYp`Xp&c7K0D1TactC&W;pEG4v_N| z8^0-trmiLYCYICf*w>$%o@=4Gl(bamHxSmIRX!u<`olP*5SAP{oW}9#oqoKZEL&`> z|841Z>%2y#hfy}quo=te?R40OxsHmi2s2$x-oWD*7F_e)85+1VR9j7mO2~}v*hZUC zot&~W43OzRQE@X_;iOcAg$>MicQ>oigDa*h)`{+LcE1JlgP)_d3uzh}PAA^kUQV7W zS`D(uV~HE5LEwrJj{YS^JEPV-a>>*7eXUzjmH$~i;NeVJXI{GKb^}uq(f%CEmLK}T z1sQK@dCCH1SnP+qx}0{V#ZU222|28xI}NApL{$^(BGL^M&slvGjhykWNSc+qb?A4~ zOiAsF`}?>3?=26Asb;^ZrVWtvoTMe^q zbZjW8w$}HM=5~XsDt($LtlY=>9kM9Dga6RNim^*$i<)4xUGCZlMfS5C7>@oRamHC~ za%#PFc~!o$O`&q_SDKeqhnYlsUg(5=x?P@ZC+}K=g*g$44<=?S4faqyyNCs(wqF1Z z9u^qcTT(y`_}2OIrb{Mwuw|RF^FcVmnMw%(ydXZU+}?hr3{HgCjUks6=O!*8cP zb~%-={7+458Trj4iJN=j?t6ptLT*=-<-bgL&sRK^Q8D&| z_`D;prqUBCct%H#mGj*87YS}m>|0Hv&87(r-I6aVJZ3oKl0JKz9%;K+Y)8Vwr5zeO zBv~X0tcTYX%3v6=Y|x_650wXs0*AYR5ghLQTXKM?UvlO>gdd;V`Zlo40%Jt>L4+ zsxqxdcFA_{n{s3{9hI~0i=GUXuN-)>(M|ZxN$NwI5p{ZQzS8RJ`s#^zkJWXKvFB^| zZPi7z7PQT7CPoJXI(l8lyn+#}pe|zB7|ZZqV)58-`cbSp)5yI;5!UuOIn7=s=!@vw zD_AjBJ*kpsEpMPHA6QoTD77mhFP<4?|LbpX4_wRf1alJ)heqjgd;w{uF8_zA_YS18 z|NqA?BzIZ&U7_sC-r1W5*+TX#BztcM-6c0NB6}s9?Cf!rkj*iUd5p5hacqvm_jT0! z^ZT8D`0Kh}<2fGB$Mf-eT{yCAXA2Ir-0@`7+En6l8XbB7_t1EG7CW2qN)Z#SljnE` zYWmt42y-{{Lon?w?m7?bY_(MK5;prxj zoPJWmXz|6^!`^LEGko+z@(*K$u3ax_++zKHCJ8ZqNz6i;*FNkPty>$Q#6DaA z3$v02ISD}XPUf!^&Xl=_T3})zvk7?!VJwAAu}2)(Vn?MwTZt+1MGi zTUr3GROvi|91sBEQ`T=xUE*g$NVE^`H0$9GqD7M$RaWfCoPO)3SKt0&>5s$#_}zh% z1qF%CHSE<)g7RFd3}|{R;|mS$ze$=$c(?iZfs0_SbONj!`Ueud{bt98Rrzqis^ELb zYbbk0-du2bxJ!(Z-)w5_N-Klu;$?9bU(?QGiQDk*Oq$Q#@N_>IBQ|q+Nk*=bZMOMn zYx>JzFbQx*(5r?lnoedyW2;rWk?{4(Ukc~^$%2h78R6r0hgQq%)W!9y`pUDDOM67} zB0*=?pbH(FVZ8`qWMb0-N!I~(YzoO{;Pz>rV2vubI0#U&0+J=3aWF|-dW&hukxnz?E^$Xo|Dd2lND|` zIG10Fmk;0Xn&MNTI0}943HXPvW!!($9Rh1Oi(w-p*iqx zZw_pl*pv0<6OR6+E-^|pH*=pYw;vM@pY@P#E*bATnSs4N?u(?nAxmPRYRfH|UfX=v zR_OP9j6T8VF3qh@u{&d7mAm&B`~44sN+|zM1TOJTEa(JJ>L>5--Fv5){XRO)SEnDg zBC(&+F`|N%X~r$7pKWvybMIozXP?>zK~U0P_>kF=9e=1-oLTQK1AD6b0wmYZrm<-_ zegGfjeQVQ9O9GcP_V+4oJ$x7$a31TwGcsUO4nDJ@a|cRW5L-XT@;m=nMNTKa4NGjj z`9vI=)_YFqaw>ZXEPb%{<*S#2y`?R1EVGr84YA0K6zQ{&#Wm9t@^|bHA9kGrdU0s< z^hztT*Zh5^xx_ht5d6+)|8$8Xrd&>LQS)$-spYIQ03GX(5SzPZ01k%UyfB)Awb$h` z8HSony7Adpc?8xMmrr@0I2rmzmGJye1$}RGn)fjyDW$TIj(4 z@87m=ZtMVKAOKaGO|Yh)Izn%Iy(r@G+4NGI0C5YPq{=*L5jckB_)s%OgzUAnWp z@XlSic#j*DA|mZy9E(T!;rSV|5Qp=`%;=iUX3EBs&8!8b(~a=s5J78u?Ne3$PK^e^ zWwo;b`f0r_Qto{7M&?9R^_Qo-^4wpj()*`G3y%`d{?Kl2z-Wpj?XE)X%GeyMlY@4< z(sM(%W3jlbuO}zaxc12y=;{o#6{9g?06B>AA9c6mV>lh|nCUG=x58^pp5~y(Q%~}8 zoWHLpeqQZ6m%+V7{D1pkHtnIf6WJD9Pm?(Nv#U&%!dC|-qgy?dHM&OPx4udg>^4@S zq5*q|&)lk*)fi%OGK$5+T7JH#RWL*iF*yHjeSAR7>Nvn`>TPbP3R{LQh`^8Kx@?_QvW!g#6th7Kg~&X)ce*gcj1eI> z@*KD*ic>P}(i1&a&%;A0a5l@Qo4B2=vnj0Wmh~Y{$Q8 zjlD}%!@=)IQ4GUDnJ97H3XvML=04Egh0J{axdnd8=+Bf+f55-L|K-YInMva4`sJ&m z9{I(4zNU^u$12Opt6VO_n9DS?6*+tLP@kR;p^HDL+1eBEa0jB~q=!mfK`7`QuP~Vb zHLyOc7G(w*mDE0fe2QgaX#xvd%oyF;7P6-6EEZoNdAl~6J|4OsV_Mx+(uJx@#<2r) zPwv9uFs;HW2n-x(W1yRqO96tb#-=TS@I*FEAI!?tb2epv|DCkx#4jUeNBchLXSh~+;!I3S~_rvj>(Yxr1G;S3U#y+*ani;bt6{C(TMf>bE{ zbn7PxK(wg&uL_m=dFoXCYwBLVYMiAk@r*tCG$G!WMU~heI{7-jreL?oxL?Cf@;g&!MqONMPxB7|HRHOvl=`7rTp6= zkmp;ZU0~34>KPMWtN5q>gJa-JeqBBA_@-a>?e?HS_Odx+vCEVup)BaMqALoEL=Ld= zm<+|y!1iMUw!{`6)G1fyE!>!c+ozg09AJZ**!hok+6^l^{22uNzKAFW>IB5*G-n^( z{)3KPajbj;TWNaEl)6CH&;`>U9VTf_7(|*jy+CKLp?}^!^kk11qlN=DOZJh+kz-|% zi+b#-@7JQHEr0!`v-r#MAjaU2wn6Vai6ZR}>0^q2 znOg4ZJ3wsI=!xbAxp1Jd$JO1m+88acPDp4=u}J) zDOR50<`kIGF80N_nkm)v+Ru&r;0~^Jl~FZC^gyC`OIf^HYX@rsYi_kpy_+8$xr!mq|#=m zr!pi+dpb$RJ|uw}AYc8=C&~%l@N_fYJ<)nA_S*Fipd$HW4P#HqAher{p#8F+pKVS5 zzhY#G_3bx(6tCP2>(F^tEP@0&K(K^JBOsZ#~;^&u#0fjX59VmfwKHm)X# zO08;Y9D{1QP~*R12=1FshZn8exFnUb2}Y~b3Ek46BYv0Ga%LVwS^L@SG82(I3D)>OPWr{anqRI#W*Ex?;|@-m5~uPCf&vCv-D{dN$#7jbZVj9!ZO! z?_qowLFed{eie{l37o{koF(^4y5i0YQD&mgZN1GGWio1zqR|2KSNK&>FaCAlwF~2V_EI2|kK4zJ4VoWFoPw>)lAX7pb<#OY0O}XN|oY zc^@btrtv`U!Uk2eQA&{P@g$Ft={zNHBuj957-}`xOFcJWqUHKoF`yBJ)e!VY`uW?1 zd=ew01Rb|QHyB{c`LQqDHfYw-)^`(13#p+D=|Y*u4m{;j)?Pa!*TWshZmL`!TRg_1 zpBCn`7|uw=h~egnPPg(%xX{E;^a`)Ea!L}^P2TXvJ3^8GwTWp-%L?&K$iWtu_q`2X z8`g6<|3d~gPtSv(Qz0R#DXH>3Hs-(neV%pIE0We&&4DxJ#XFgkBzhQ_<_etnJB! z7tIm~+R%?vef2?;i+0YC%dwlYI)ZdmRnwd=zHD2R3EI}?;VKF2kwv{g`!cP4bHexw zS2MbO7&bDj)XXbo{nW!~_Oa-4ZO1Gat~^&3p6g{E{hZ0(e&+yl?5M`8MwLh0`V4rs ze7+EDv#(lu`q?vg&$!Y+kN2LZG@bjStizNq&;RX}-c@+GADaUPoK;4@6&RCOD)A|w z+QH3?1adf9&}s_~HYNJ&Vl}{vf^iYTQ=JKs32x!dJ-NIRtOphE*;Xftn|g?$rW#z_ z*lo%h=?ut(smA$-Ox@#B4e^(?udb7%-zMfg=|u?G*{4%;|} zzu@gPs(8qb5*_BM5f>|vOAjhI3;61De4tzKLKm8ryf=Y9T%|OZcoZFA^NE7)m)FOo zNX=TQcB0_wy46c_WQ|u^KmBINK`q6f_;w~QpiVT*R1R5EM*&G{zy6uw_$){h z@n8FbpC#;(Hy^n{`|>5ChGqLuZhr2caLNR-1P$D4PmS5kNlie%Ft7V4`{Ax1dJR z7_aS2=W{TC=zCX_q`j(|OAV3I4NBy<+qynT@t#hEVfjvHScgB6?)DSTndXt93-jL| zj?BXYb*ad2@9wkk&S)3=NM{)ILvyz?T?t&|WBY)1fTi&@7Z?fn$=5!c5@C_%BDg!YsU&3?&T~@tL1xww*)_xCjb<&yrA)k$2x!6 zufz9#(fdx#{dhh_DX@dMwVola)5$5wv)=RG=10WzcT!tNHpn@^oK}3^oichQy)1k* zera9#s>1Uk+pAR*S3V9OFT9PU4hSqhF>k-nzv3sek*MCbaTcn&Jk4+I@s07}eWpW^ zwVH-90*E1N$f-}8}M}_T1wbk;qahqx$5{541-Ci0`UKsWmNo zcdJ4klCPO>pg00l)rI^Qz@t~FPfgSD?~oj#aZWttJk^vRCY-~cZuvMILPi=4%#R#A zw$G%dO|nIJz@lw1FX?!ZE~nP%%;etG6_R>S=`$al5*=x1Tp$xl8#21&(7h*%e;`;E zZ>wPe>{OXb?!)GRTwWNZtMd&y+XFTlXxk_bHeb@;H0;ZS+t;jFmy4)1=mZA0Nprqc zihQ*c5t=$u%&eMyawDm8YpJDHpPM$@mIpi%VSZH~P#93_k0H5O#q`Nh!@7ICP}Jkx zPX1UsF>f_lD0o091KL1Mc$^;6=~UIYKX*2f^huK1!D=;=Y<;G3#QY>^w|l|*mpd(KZI*V z?%Z~EBY?_84Ar0m;+&s>Y>|?E#|O?lQ(HG??+(G-QWYtrW-~QtH^**Z3qw*p#!TJ! zFnP4UEyn8cg~fPp_tE5922FzrkkV2^st81Wt`xgcX3HE5KL^s$R8#ci1We9r#L%O5 zRz361>qEvwzTUFar$q+)6V6zg<&`D(j>$6i)#K=zl{dyVcKZ}<@as^yl{CRPO?eum zhJOwIS8kqnJy@O2&42zEUGB%WGnElXroSM`??qy{zCyh}Tf}ry&g3$3wzt-<<{vR0 z8-|&_9Nw0iW>!8y4Ydh3^;UKrXhevOu6)BT**?sDmhA?f$sBSK%wo2paACqeD*86_ zf*=B*J@zn4WFCu>c zjTuZ1JwQg#-z6QTkCH4Qg2Dv&paUBv*@!Exd50I+7=jwI|C_&Lk@|MJ z)Q=*uze(pRi^0npvEe&5(2A0}Zpm^SqhybC4U(fUdJ46@RWl|m)t*SjVgxx^9e$W*h=Vg@ZsyKa7oLL>J z(FEMVSbd~y+reUc9I;d(%J7POL^!0xvP$qYMey_E1%lG{Ui;;Mtt?V@3dAWB6Z*>r zg16ewYv@J32*i9F_z6%h^#YTXg0BTKxScqGsl1=?-X%X&Fa9JlR!$-HLM7sMAd(KD8Atb|5R*}20CAOcaN*T zPfeQnZx8J5(-Pa=`O0q&`?QL$;;hN(0URO2a8v&3+Omc84UB z20R4I<`R6KI8=Z5f1B!p{mGdM{p?jlX&_(f)RAD&0;3 z_DB<(#!~(0x!qMdjipP_LtxG=!G8o}_!XwE;P_YNEpSnZM<7!%UwK**_uNUxJAP{a zda&~e!a!!PB&@qvV7w7?+AA?bgCVO{X3)efc)dFK4E zPaG*EUo`WpMG+hlm^s`*bQ*hhq`U9UchLSE|CIJ|s?S|D zmminAj~jm~J?WHxV);0pv&SmCnmnGI{$GN@3Sb$EL}$SlGClAf2+ANe2F>5Mgmb~G zmn_1YA(mGOl7}KE3`;E?8l+?Tbe&Buqr#>F&tgskBVef(QNF#+ohnt%vp=(*HSY)y zWf>lZZ|*nXMi-0hy?8qCIU<$}I57m7&KHFsM40UR-}vu$Crt_49G%-4e>JETA<>NQ zZ&Gd8fvwhMPQvO_u4*(YT(z3$6vInwq;=qZys~#6uL#fI^foN?@=f#k48Fp5UyC{h18z~n+|{S%F6}&kN=Gq zroYX`egK2I_11=f1Gp%ek=@J!ks*S)^VMIm--eQ${5|Wpd|)B24)1$p>-%n1`#kmA zq(Kyk$@>3T-d&9%?I^Zs!PS?`HMcxq2gm18CN(pD7YKI3%H!fLpBZh8yt1~c7r#hI z)#!%_okim8Tpts|_q0?ts&V1PImp14^Xd}@wsgM;;kj)J4N2t>3@k8=*Xpr-PC+}% zL*S&r-fIkEeQ!152pMloZ@uU+E`ExnuZZIBzPG_Mn^CESSoKyKFtw&eYO^oyJM0#^ zN8c<^AMI;c?~B(X?pGB>uFRb&bhtt>9GL*5z-owFfAh#O3(vI*-S#s=2z{G#KE3kF zi~~!Os!re{Kuj8(4ZK;2u#~tpj(^u`ux+!95BaWE&#;|(QG8>{W@(~R7FNIaI@&n3 zLuJi0spK(#a!%%{e+A0aQta0=d&eq1*b0%1f4dg#M1HHR7+7p(<=<&gEkL&VQp9MI zF*Aebd*NfZ)!}ocsRX6!RMt(N0}M$H;+giWD`L=+1rFz~+6wpy=OPz>a5CVDm^6G* zktxm28)PWC{VS@A9BO#|@=;1q*_S!z1AD6_)%;UbW13e=6$s0yxGSxVR)!92H9`ai zcAGu{n_(ntBNZ@@2|4PQp1xRQ&En&8qt6XX|FwvC7MuoB#1d|2$T5nL{iRgtD}$G} zf#7?idf#$2K2wPf75B|Cpf*m2i(E=iaoC^rOVVyR{iF{G^NL?++bmqbH>PYa-eWN4~3HhjTou`kpgM=%;uj z?}emFvWY=THtM5@*?|u=JeB5mlep7;6Q4?sG&Zs5j?}({S!WN^YNSUVg4)LfKC7y@ z&p9I3BBZ6`6xil-JbSu)JtW%|cAoTXsh*&<`#wSQN)^X}9 zcb+=09}7Iz3@jh=!{%_Xb7T%=DTyZ8GjW3yHj@n**f~bQQ2!8>kOs5b9@qH68mcw2 zu~ZF#8 z#meYaJJ2f>t^5%L0u?uM%GQmg1pNftp|^JHKG4hIl;ov*Ex}gqA6cBV8~}m=VaT>` zsw6JxQ1`U4afx=dP&H?5pCOe7V#Yl!wRQY;(x2I9Y04(<*X~1D-kxI#ZKtRcY*R5Q zvEwG4G=2FoJ|^hTJhf5YPO<6cOVsA@=DtvW>N>GJADejG0A4YoM17GGnX4BM%A;Xt zMvcnW(4c9FkHX2GFZQU7FP1MrjqBEep-N-1liD`4D64i0HT+u5tC9kW4M zmtc3FRl(9#26J|~*Z>Hz4W9aK(XQT(=%5IMgZ%PadnkW3?5%O?TJqIVGvJgdOd;rb>N+dE zr^Z9zoO~Y>zXO%Rp=XF^ir3U2QBbJt$X;Q-lB5CkbM5UNh^RY7R#I-ElLiPnf7roo z61`-1Z!BLH0ek|kA=WPCjs^ydSYGhsMfG0Di_8LMAlkI9&Ik=Md`@1Z&NN?AXWVoF z=k#uEuWK$xCk`x^-#e~X;Jq4rw+}I+lOy5%g>h^mG*%j`(M!jbIzk_1)JYV~V%sUW z+DEtf6Gi|q6V?}Y(YDR0^v!}f@bEYqFPQQ{!F#$b-o?BB zR@^##!{nfg)po5s!|BQ%EhmF#BrG6jbG2PIQ?rwP91qN@quPi5|06GX`O!E)Cs)iD zl!Q+jCwN=RGsS$rWH)qe#XQ#1cv73`T|lvA{>$-!VZ!hmF!Ex#IN1P?%*4pGpJQS5 zpI$w@2hsETYlTY*U*9HSN$nv06YN#&YQ;OG0@+ER6-LoscMvPUjR-=0rOx>;$soyg z_5oFIb>ZmUI%wRQaQnZ?00tq%YeiJ&sR6BPtf_+(;HXwVaX$Qzc&l8k8zzar>NtiB zq)f2pc67ppo^DAcE^*%Vkh~IJtdF@o?aPYe{Pw+zXY_7Le_Ir)Hh{i9N!qTFNL2Rh-nir-?nF9Z^H^%9ZGfq zmH_-Xzt@NTllcmQu8f~lU}F{c%w#2LZr1ST zPXO41zmGV3M=%K+c5@!EB{n;h*p4C5nPri>FUnR!CT=xgHY(PVGe>Xxb}h#V^5#RT z+65X$XWEUL0JfQ5^s}#9 zfo44e;yIaT$1}>bW84GctQT0Gnc*VE29J23Fy(%}(`W#uWO2UWYCFbzfVnk+;Dqn; zWzM|Gz6U#>rxflFA?=; z?Y@~{edNQle|vG6)qi`7Bspo?yBAZLrR~mzr}OcihMER2>qz1#3J1QTma2zMol8f) z?T_kJwAbH{uCjf-KJqhM7aQPr`th2~&Wy5NP{I?IJRx*SiMdSe(|L|KE9ho;XYPwe zq`9*8ee=RS2zYksFlfU9v62oxKn-5G#*tx{$j_`^_r1}?Bni(sED@tXiyR9a|Ay0- zXrT9Zk!D0%qDzpN+WwI|yWJ|y`dj^+Uk3K7rN17Q_maV*nazq7H~m$? z)0IqrCj^;y;`bXCV7qnrqIR$pgubP#wwpYSN3pjNhs!FVY0I`ojs6F1ePb0066sH% z>2sIbqf4Sv>}0&7)8{fMyJG_rKZ}0anX@&wVjpP6piV3N?Z!{d#y+Q$vhVX3G<#vY zFQLGNr?_xJ8G+5hbAO@TT>mNOfLhSvwp*sCWkP7PaOM}axrN^M$%N2Z(=sNUeT7}h zw~mU5S9OF5#==*+euy@r=43t#Of>;{!TIr{Ssx2o^$K9aF_pi4|K!K|?fA%h5%_M) z7j$-K?jrwWr@5fcn#6Qtz(Hkho^r9but8_yuNQtv>Qa|AJtH(-s)X2u=7fiQ0Fd27 zO{#$GJo7{+9=7paHCHRY=FB-2>_#a57z@}9%&p5{H@;C5w|+HQC56XDon;*!k5?u` zJj(p%kBlrQ2B{&n(F-?i=L|Tmk;JVX=Z;|*Bysv+gigvwh&w$pmEpRhmFKsl;!46 za*B-)OZ8O3a?1khx8%h}o;uQapWOu>g+-$s^B^G{kVpf@9ls18g~rvO7KaSsRqZaO zZCNH`f~n@Hy1hMX?RSUjP`U;78g@MGTH&lu{*>JDSH+M!2W8&M`jCS_Qx->OVDve^ zkiNZX$kZ(&`~qW3!4Gyp3)gKDT(~H?`FKRtm&UfrG4YgpQL{NiK z-!=*m0Kxqh0y0{$zOH&Ut~}xHc21 zvjB|rnvFVS!il(b7x`4O9lxrkuLv!`pB$Q>gcfa)PoNb(HK}&AnZu3e#WeRFoh10;U5VBInT0rlH!fjv)gR&pv8m7}OB$E0lA5IN7=UA>iy@sx3wh z4%jg$MjP)J9)zz~!(wyD+F<+rvHEyy*q15|S$In&s1BI1wr3yM2Vki{jVqb2jl8Dy zy`s?lyomy3b0viuVn1Wl(@S!!uKuFx+dPj2dUq)1(r;h$yEjwd!Rta4?6G)qB7S-a zj5gG+=Su5cf0~tZnCq9$36|F7xRZB65n+#WUp^1%AExxkd}*>Ou6s+Kw%CZf`NX|e zWReG}ISNl{LxTrH+F|b3@1`&lK-d1h=Mdm%ls0O35?PDwccB@6@Dft`P6to;Mh=Ry z%)8`ibIM#I6zY}U66FQ2&fF_7aAlmWM#hFBhB{Jb{{-# z?MTZh9a9V@J(v++rhKpS;Xe}!j?&=6V(EW|4bCPIKlJB~ z{rZUuTJds_%1LBoPKQPRLMN5cfBGG|J7-Q3Tpje@n#;+--tANgHfi!`<;AV#zKN)S z$!0noci#p)scUq45$*W)rNJnXs_BKQaF!stKAO*LkPe=ujFY_k# zs|Gisl>s=LYj$K(<*jzI|J5ksiZZPRM@B!(o6s=b)NRcZD-NTWzMh!V6U9*azL~Ta zeY>#XH`Ayj^T*XLk&AJ)sncf=1lNGL!^g;DDrwx!yDyuW?i7f*jypNdwIfrAwCvpD z-Uxn2mfWJLtQbVY>YMC$5MC&`Tu!ib_6*z6<+WjU7 zj(3+84gA5&@ywS7;dEQ6Ebas@6Za7`&b3^GW?x>U${OfT5GWI@)Zm*eTEc^{$aDvG zh_X9keeIss{>Hn+AP~>zzaM_DdQC91KZ>D6w7Dp~$pO^|??1a$cveVW|98u6mG$MM zg5XwP;yx7PL?${e>)wsd>6J#iPptM?PkGLM78%2^)+aN*u)BI*q%Lx4V6jwV|pvCLkZ zbu~Wrue24!bX6&4rUOEBCD%TWn_tKxpx9aVC}S)^>}DrEcbSI#4l;=!eZ3#gh^qJ< z@@v0)C=6}iN^QF%njSzdEpAhy6X2?S12R5+cSl{XmR7EOoU61(;#2Wi{gdjxXCSlN z7IjrXN5Pg;zTaLD3Y6>BW;4$Cm-ojq}L7G?6NW~lRTqC zQIuKB!=FL8BEVc~O;_I{3EnFCS^@dAUgCuJN<8*h#h*3M^j2tt(-Rqsm&w27# zvm>U}_wKoCFBctseIb-lF8UM)6M59f zCiQ}=vJA>MAVs1pe{tFl zwc$(NLLS6(#^G0?3S)Z01ri&gm{QPk&AtU{OEFBji z@bR|qrt{d(j@XM>P7ol!DZjAPAHyi#B`aI}L=wwb=(1o8^+`YjCQsFjuho{IdxIhlxYnPXW)Z6W!}G-#vzeJxWw z`R!#9V8T8zVRusxIa6OtN!8zw32G`-jLiCR#(yd1j3@uRbj$Z&l=uo;wbh}+`JK!@ z{gG3D2Jl?@tFGXB%_I~Qmy20z7j^BtJU@aVem#?s?(TTi_lg!j znSJicAoF+axpow-P)v@l^UY8m`aK3-#v^hC!g_2yAV$DEAOr(I;lUI)qE*py7L18+ zh+DzB%wP|=cumZ46P8(Zpuyuji=|DqPw^Zg+VvbkqXt3A@l^FqVKg+k-L08Zx47Q+ zUtCVr3#Aa4jB+k$lUq-%ef}B2Kx$QDC7v-8{x~-h&FWETPf*U%XJ~6~aj`F#|Ja%d zp8Xmo*|G=xy(+lUMmN&wda&lLDSZVA)4>@ZXHmJksqlz&HVJAOqzEV}SH_-et>)6@ zESHK>I9^R)@yZ&=gOYyFMf<;9o13yk1kmI^Rz77JuSA(-F>dp@OjTmsD zVxB)qGq*4%O1Bj4H|+^QFVpDGNn1~kM_+ctjYy0csf8H%A|j9Y0OMY@|bmhi{>j?juj!I~K*^tT4mdj91!+-6H zpJ>!?PHK%>m_yTW@yB8rGGlEH^yBme6Aj}hUVsBpC4l4J+Q3M`5j!Wx14l&DExoMy zcTL~<_6!3Q`u4c-J5>06Ux*A}%WNheOWC&fcvUD16C5E2_(umaO%X425HV!zP>+N8 z&-UorHO;azfpCJDrLlo{o$DC^&ZNPncnT)mvh5|e%v;r0JhdX<$gh|#9b$z8pZu$C zJEgUHB!tgHlC;1M0Ep#Rz~z3r?_|$%#3~5oh!kIGjY{>|{IB!p3AV{ouOg0uV-%36 z_aySpRkYtKyx*Ia$`uQ=7vX(jVOv@%=bLjZ<6UG;C@=_fH05dbjq~*3h_N6jcSyM* z@E)H|<+)r>$$m=TzX`=8aOo*mIaNn%#uCmg%T0cUw^Y^4EE`L{1iON7JMh(cXUL)+ zWxGJJAiK8HkZ-f$fyO4CC<&3QI^9rDo5Qsa?^*Zp;!YQxZ;2XosNvP$eK_WcKlsM| zhp!VROVN1;2r#H?I3Tahg{imdqv|JXI zzYtA}+4sq2ilswoi&fkoQX3l{vMFwBHEle-jbHg=%NI9$;?cTOycC7C~=s2&{i=k?Wf;Xu;MV zir83(xNiJF5ldP-m>&m-#<5Dps6NK&2k|)?+tGvF-fQHK9#%J}wWl|peE??TSdwhb zK%1yJFYol6W~xcU{pcd9so=Y9g9M_z-Vp=aErrE}o7H_ME)Vx*%dWIb1rl!aVe0m< zi3zJ=hhhe01kCO2&k=9EH-Gvwa_rw+GL+N>p+n5RT6Y7 z{a=r{_CZJ8l4=Ta;+<=m z8}>p3GE;?4!rnOh(SN=+6C-e#5e6e#IUOWg970bZQ_Wwq1^2iDyzng8p{$tSaKoY)f9EEXs}wUvhf<2@@INBq}sA z?CGA-z77RL*Z`nY161!polXEK-QYA%l~MeCJ$nLl(ZmelxruNGhLlWe*{u2&pum@} z9c@B)(P6dYZ4fgkfQ$aes^Lj6$>3Gl{;iX!I6?R3o_55yeO+ubTTXu})YMqaWSV0O z_tz0?*$!JX9_J=Npr&sjUgs+<_G~T)x#bL>vyh8_i}PSisntNro@H^-J?N+aI7a=} z*uFX=i}EWn+qF@|BDGF@+mcP~<%FfRuMyEBlp5lL;`k1ZHD%Dp`eLqkmUx^L^@n6g z9AIbgdo^PJ!7!~o@dp&6x8PbB5MuaF9f^V&R5Y7St&`>djm~39CJnB-x?#z!XGGIt zed!bkZr(lL^7XIw5479*xTChw%+GFv&#XpnTq?>Q_<1wxy6j81(Pq(C_Ik^ z@&BPE5|eGbUL4aDs9Eug>y$_3#pR_GZ6z%smzFXD{y5A|) z-%9`4<5QL(Fc1tvuYMx5PzD&Q5h%+bXinsJB0f`Nhol0+$RN(*dOg2|=bR1`mu{~( z61Z5uh7pv{va2(WwY51&dyOk-W0-42Qi=e3euvk0lH)V;)al1wJ~8-FAt)d!qDW#M zq-?N319GR)Mg20ZJU?tOR3d+T?#A*}3(ZQvr6jvl`Sx171G21Xfc1WbfeB@=nf;C7 z=i(rloVkoCsnZ+T(bw|NzceZ1QEzg&B_BTCH0XFz##dJy^mNs(yE zk&dJ3Lf?-XFy$Qu?BCA6JiD(28{d4ohjTyk156|59qOvoOFfWw*^Y%X=v9y$@{f?`NA2(=QV98k zd#v&lF28bG7uHu*y`D*!hJFHQ1b2Pca$+TW(D{I8u=O>JN{i-y-^u`e>Eu9s1Clux z@24x!KW*PQqUq`<4Vnr?jJgQ2l+C9hAY?K<=+<3dGRCDAC~llCgr8~Mt&V;EEV z%o7j({th4DpACSNC#V?Rb!J81~FIpz{ z_otG$E`P*M2+Z=LvR~g7N<FFNwO!0);c1q!P>i?lNhA;*xI}| z(jROS-!CIb`qXFl+ZfCx9SZo-`aE(ij_rEzL#H;n7E#-BK_V~fYvfr4363T14RT;& zbFBaKCitU-oKX1AL>@Dg)9g|;vQSrVDEM6>@;tTLh(<=he4V>bZ1;rPdi^|IcGCBo zWBx8lPUSr(dxvx3dDX}JydI5-IY4o+3nr+>!h*wU?-t%}?5P2KT=M@xsSA-)v_eXs zWvm6^wqyh@lN!YPR2n63jTmY<&cbTut<2f<9Hvak?tl`n)3y5CA~&89qL@p7VsrOb z%142Aq#HNH_oII>o#q{Aan6ss^Cydb`cGK-9(LdXuqcG4hSU$qvtM#8CF_|-F-ZK^ zwpfV&%+aC2u{1!p;hd$ga1x)ACxka#%q{00~{VpHj78#}{n{2D?On#}P5X)UqO{Qtvu6X3L;-$xT?qS>B<@zRT9HO=F zYPv>yAZ<~CAzDGQKqI@*PYUBsr+{nJJ#yC^X#UBS)7v`hyPpns*{r(RNj(1usn>{f||Dk z*6m*urMNgIuC3{D{1*z!FBG%D9rLU~tqI#pdJ3Nb(oE)Cu)R9t)779@x6KHZ)Hba? zbDh->4^%+wUrvkb)^jFjm%&b;j6c|=)O}WidzCy1Zo(n5wdr~6gpuG2RRMH}J6`>X zFZyw0Z8pqME9y?)(!E>MaWpb61HHPE=O|yJ>g=yvfM0xXOqfceQk^P?b<}tve`p?% zb9Pp8g?2Q*)pk{VlsaS_ijA-(a6!M$jSJ$omTD2*%xh{<&_8p}S~KcBv>>e%^f-HS zzx%Hod5PdnmJ_j{yS%Wm)v-1|i8Q*ny-D_|YM;2pFE7DpT8TKf`2+F)yjKO&b#zJl z?=qy!^|x(o#%aRd){Gaam6a;{EJvhl8)vj;%}5dJf@oI`i&zLiTRXY#Om;Zm$-l%@ zD!vB=;v(GlzUS(AtjIV1D}$f=4~tlzRKIuS(bdWH|EqNHIViYO+lp}eR3!ccrtl>e!ep#TZx=BeIQJ_)P z#lndELFKK=bl$@kcoc>>oPEz`zLln;0Q=z^`6`!!?rqmcwD@W&zY>hHB0_BAK(12r z)!9Cd^JJbzk#@GI6c3*#!z9kmPlB^IEn(E=TAec~ir{6Ce7;)-)QjI)Gr(6#1u-px z`dYVl-f_D#pFZc^so7T8h{Ma>XYkql;f{kUGq3gozveohi06DkN|31~P?l9H*1gnYro6|vDBZ9qKgKi486X}!ae3KwWFV9{L-FS(Szu>vBH>OZIDK^ag>QI z*gWA4pIw89Hdz9=<}#DS5AjlPC%62GD<{;?6Qh{EWXgACULIfE1wX|n`2l(GY4h<7 za~qE>@VS$>F|sI=pI6L84G$&O~TfuhTj%F&VUij95R`Gbl>uQ+*31V zSVr(MuEbBrZ!^)Wf{_MtF0~!&;KB+i=TelJr}yUq$%!7^nqh7CSolXpmXGdT|6ky( zE0TY(CFmxFU!LrIJk72{C||j1E;1l1UK{$0(kDSx_x05J#+QF&bdwnNI8ynRD8Y#k z;b>AZgPBrhsW$PYp+ixQEy?=J@@`;OXA7I)z9Os-U?!R_U*P21rPl-SCm_a+MeQgHU=?8#iVf%iU9@#Jk+nR?KD&gbyF7)6ILG(_W;C!H`}}Uwk|$ ze2K6|^oWhOD;hWT5kn10{EWI~4Y>!Tbx!@8?cg3FWv3@%LAGh36D+U5siK<^S6X9l zkR8P{>=jF-9o)2%n<&{#U$XyI zct|!yd=c=-dnquv&qzKEZiEnnLp=^2-i6rf&YjHuaAzU2)b+cE#go z?Gh(Hk3)+zwXS-KYP?aWIg0_EOJ%NJiXsVz1GB?}9fpRbA%&BvTDH?eh$48zT8Q8% z{8;;$+@b%J8dS5{i|61V({I&K60mPbnb#8m>r`Fr*;tVBC3I1bo67mVO0qTfuErk$v*EFGa`8s zV=*KzYMpTIGWHXqH`rW9rw|g48Il}=O^|wFrl?iV#UD#{`R(Yq| ziF8lyTb#7sW&u*d8*WMEKZ?1#w^lvu`6~vvy)u_*s0-kSRkiQem?*6`5C|?&8 z`=2er_B@Th&MCKY<;y$Uy^DyBLzxR02YCp9pbj-{BghZh;o99)P^M@pI)n0^gmHsM zl(1C_?*B3MCH_!4_*j!Cch0?ksj+$9`RIP#{Ppr_3&8WB{=w$etA&cv+k`m}5a34HefcKlN_R$K zLMn7W;Y}k6OQ?9NROzt{w$TeHR|O>cirvK)Pi+3QPNhYL43-@k*SASuR6Gx=d3FMK z_npKjjDXgU8*q)j{$wjq#E>PdUV$U3PsOs}>y)C}BriT&dnfv&au_OXhsd52xd z{GeWRU6u69xQFBAoY9GqG#|c_c+?E-e4rQNJXU%X$4S*BKQk@*NWIh^r z8?sfYKBwo7Hd}nS_)}&aNMpk>dXurN0`HYXC=n!3E)g)dk#A59D??2PFbpZxs0VC} zqK*W?d&cwT7=U>xG%$*z(`lL^%=K+br-6jgeN7BXQ=Tgm;OcvCb z5F&`IU(E<&XNI&PdBo!+gh%@V+@jyQW?&>HTg?+4dv){69np`iF1lZEf2|>opTJ8s zt?MF^JZas6>a_C4Z=2E$rbu*>(Z0x|Cb__(ph4mdbLXGK7y`#6cBxv!?dYp?&=~Rw zX}w-4d`7#;vx+l#viK?6?oXhi8%^}`2E7ru+p-rwvxCpFZU(4Z z)ah)XnGvtDZp$4-ll~5Y1k#IvI7`pd9afa?Wl9w8H-%h^oG}XsheKb=Z1e{!3Kt+P zoZvqiz=_W7nJF{>vI=>pACrx4h2I zR3T{N>a4x(0#I6~twy>!uZ)_ff#*r>F8N>}MS^u*Em_9raP5ZkZ3;iIpE;h{_Xy!d zj1rFv8+o5_Si~gG0Zk%MWGd}2AsIQ0oH=f&&u)u$Lb|Y@YhuG?=UUUpXuUMy+tNR) z@5NLA$_IAjg|@4&)R+WiK_H5)HK}dr3F9HZiOuPo)Rt}-Kuwg|b+s3x<2bp!r?bBU zC0J6I@1?c}>?Q@m>|=aoZxeV!1Vu*k1K?<#w7^zHTS-yoBG+kWiYPA-adm%iwm4w> z3Ca@mmOM*61qeN6IgX(!6mlEV)k#XB&*XedUEcOTX*%^6!$W+XchM=(rQBP#u2zc< zEe(t^>cu}=mq4D$Fm7hhnhEXR2#%*^mnpzk8O>Bnez_SHj@AFMeyGn{e?Dh;Yr z?$n3sj|qWObZ7=d2oQLzo?^_~O|0144Rk8>TD6#SaH0=AE?DzA*8Q<7vo}q$O8!WZ zJ--G@=h8gpoo8yU#NI2Ku+A|HrTL(lk-#Z!IAZi;U^a>71HxIUv zOP(Hul74p0sn7Im^KkUdoesRwt&;`c$h;dt*P4?nfLk~pDsl>l^BU@H3c=c>LXW@% zFGa#XbXvzX0|-fR3N>Nlb3l${Yc1Olte<5{*i>TY8@$%=5vVKGlW!}JtfhMlk;!>d z6vBrPSCJJ#Q0Ja)%e2D=g0j|LAzd|B-1fSD717LANzG8M?x6?vttr`@ExYzMPiNRe zA4lmVYTF{^I#OhJtX0j!gaRxZ<;NZ6qkn&fhVY3hX?8)8azz13`(2_A6XO|yOQw3E z3s`%Oq8HAac)`MyZ$T_HJh6$c?oOGvwjBxiGcxhm>ZdNsKp-!-f%yzcmW1{b&Q^=v z+fnG9HX{O@O>yry@>JWcQEks}z(!}RGJ5k$bXbe9B{C**^m#6?uiQonxw&`I zAthLEJ!Za3`|JjBn0w~2<8BHCZiWY>ptta*g$;W zLR%gZu-cim75-xm2(Y0u*)>M3vh6LDQ{auWYipNAdAtlBMwBFh+;E>9`KX(daTgTH z@Y1S_a%$ZoR{IcDU0ab=@Lx7oe%O`6%?wJ_yOKsIeSD{XKOHpuNQ~^dD z6>92934r+pg<|?fVAq@T&&V>jh#vPBCiEz7ZQ;SOh%y$%09K)v0rf@OWj zeohft)ql=9+F&W3yqC*#maSa^6T>H=gh#x{<7l? zL4RGm?l2ZqTN0>#wbcQ?mU+z8oUpj5Kp zc1pn6NYv;1D@>`i%(X^!fxyDWqZsEoyTn=768p1zAV%Eei;sbo!XGXuMuLO34Wt<}#>mho73m zEva_XMXPS}|ElB*f9!K>Dpj@fIv`DOLt<6-jmBB;-@T3^=N`l=j4qs`TnO+8qXHea zVUcVmCitUAK_9f8_Zm1O*2y>eR-NSOg8dQOT|q$!6sA zGPPgus?P0}8CM7l7ecJb;dWmXof+SVR|0fKDE5a9%V~{{2}@2EM>M}Ppv&f#fbiX< zO&sjJxXI1r!r&DPOypq2;eN*K#5|~P(53wUc0=ZEhraH1G|<$!o@fR&FA9PC*4-wL zT$vT>EI##-^e`X!cglW8_1PrBPP`7k!y|XgKAa4RmXccr2`7FjKe>47f@~UeFiFG; zSSY*?(ovud#s)N$Q{tb#ck7<#EODNi+yYwx)tx3Mk&CZ%+hOf%Sc;My-LJn~vPjMP zD)(%~4JNB5z-q(Q)TPiHn_l}QlHdw-nlYlI&)m)+K|Ni-^p!>1uqT*t+d07Z{7vn7 zv8`XXc!H?j%A(DlO?HI#oFkJ`iP?!sZk$ZdQsjlzE!eR-jPSr09%eij4X=N*7rXSd zI6l1rBP%2m9(DvCxNrY^x~*j?YT8Ih2FNQu!Q@0%I1uU)d}uSO>vVO3N`Ff?_J2YL zbV`E*phSNrWp}0T&5^xAfNBWh@aK6P5fmoe4*S85z+ZzTUdsm`xvZbh6Jy*g*&VY6 zRVI&rT(BfB-uwmdwa5@ZS+Q$S^}3uzX0fbm4amNcy5aH;{rNlVXw%)OtwX8|(x7*w zqxq{DP7X)}e_#wMiK@l!JOedZ2>}eg+VedU1_I~HiL$o}be_A)1{QVF${dL`Xxhvr zb@-7J27M}97;iq#r|caUEP0$)oI$yE{_CY?@A{2g!c^6$Ve5Q`584527 z;QPRGtHmzcsE(mxw}-?*It#Nk*_6+6(apnzjlAIZQaVuXU4F>R>37uo6m_q!)KmKx z(N{hTN8k!KBiI+xn;&7NB`N?gQHW-}!K`K_^9lfPgzdETa~QepMOaF z5YCkdf6IIOEpOZBx8_;x?=TnWC^h1R8eAx<@XK+NT*$k}ePrx>I*H!qwZ+r~DbE+T z%863*2u@;oz-Vqa|Ba}tduP~w1zdm(e z0o}gd%Z_Y)XJn?m=1%FZ#}<26{61QMy)t9>(UcRK<{n&AZSnvc)a`R%cI-q&$XzNK z9)PlF4iR9j^}nYCGq`fmLYyn&B;S(hRm`iSxM%Oiv9x09xXHc0!P@NoZ2|cl^kC}l z%i&w9j>EPV!OL2hoJb8@lH7357nHZ7Yq${>E$X7JE}s#nXJas91=VnO94r@>g^LJH zi5v#T_E)rkq0|6}o~0n$jLj7Q1V{ReFGIQym2%)NKF_@{g4)7d;VP9LssLqO_N}Q+ zRNzkAx#2KoJ6CB%Y-cWRn&c{)Tzt&P{Z%@E(jBbQQU5bzW(W#Gj9`1eOI{2mND%=9U{pq=@L^Knv*uNfr`_w)iDw6AFrH~?|S}nNU{Uf7<;PkJE5#$aGDgz#XP&y*P&;i{b?AB zb=zLf*(`UV1O>9~cPqrzZ&*~8F#h#Yvt|KMK8V~G7~P+2<+Suo`hRv+i4xn#ZAVTekGAXAAD8S4Q%2Hp7shzqk z1+FST{OF7&#grgAS1IY3r~_~_$Ep{P~w^T!i85Zhd(&6 zICZY7N1on?=*thZ7hG1A4|oJnL$LWO76_=w&x9n0V7u_LJko08cZza7O6qf9*bBxQ$xAARTfRrdb_3s2Z0ig)CIQxUvW_DmiX`!IP z{W{0jq8nG{U7ROuJ#O1_T@6euDEgJ@p(I_lH}>o_l=#=y$xE3Jw;zz}NSRMw-FQV< zRfX^EwLfe8$>%t2D|3ZkFB)xPZ==Yuu;PoFlYXFyouZv)JWaEpUGHT&&w8gjL%Hc$ zIh3JmW~G1hjy6+&H*B{`EGJ(~M_^O-e|U!JckR)fRrvI=V#%AhzkCm!`*X#pvH_+L zh{*SbmtbV`Hb=;-Ovt|6lyHbh?q3r3sBND1%m+eg$qyX3u_Zd`K=OdEsEz-fAoa}` zkHwtG*RfTzPkZr4S9ZGqdLIYsB2@#v#G}y5j3bnY3`EeNyUtED##z3aoy{=F^}Y^n zq|Ppsp$a-LJW|GltghIUIu~y-=}O9l(M5{DHZ4JooP)k?!+IT9DrCtUuy#$^19b|@ z76<$4kz5=Ib;9=tihb3?FP453UV-tK2szH~3g=fv6*_8#l*^^o1R!Z}rdWk_?Dq8UdR22ZOOI z2U~kN`(5t`XqA@_(^=+i7YQs8nBBw60V=L+;N*P|c?N=<&C?TI5IY0?owbq--?r2L zAl3gZT$ZvKEc?5xcQY^JF*7uKOm}mH z{5t9ye*)V8udjI;X5dodYeLn`NtY2fH#T3TGJhAtdz3)C!g>{tYkOt7wZPtWZ9MP+ zdXG9yCbxPMrkkJ%89j1nVaGXwT(N|FqoPjFxT5u`3Sk@UEsL0b!X<~@+KCmQ2gnxv ze;YwCAtZ%+elzU{opWy!`vcj^j<_fzP zVz{`ib{~t4)WvJtvAkL`z4y+@r}E@43XmKmjtk8YKv3iz(TWxMLd?=m65W1ODU^vF8+_CSsJf50&E@xL+Eb4l1r zCP+xwoeqG8_p|YUki0C+8b7gHJIXo?`bM~EHmC%C0n#B~x}$XIdUV~zQJu>=blTu5 zrOcZqj!=Vy8d^uN-}cDQLh!%W>L2O<>k4F39?#k2ilU_1M}RabkKF$@qKXMgNcKs!JUM(;7)bp$4&*r@U`GLy#)0`)a=B#4gJNK-TExr7%NK*No*MLx49y8A&e?b2Jx6;^vH8>p0tK*{(8@Eqv8DH>IXB%XtLX**Ye46Y zIE1_MUgiX?UbN@tF&UWpt~$}lKb{VA?=(nG z`_J7~NLiCWGMq2-Yx4O3jh&~(wb09iJ6?HI-Z9j8DcAZ$i`mCh;9o~wFQ%{rth!<@ zf4=#D-N7JGqy__TtiIaGN!y2b!>wFj@QoyC$2;3omQLdJltF}OAb@)+&LBCuR!n5& z6m6ft%@mxhd_CUihBs-Is@>OeFJ!DXNt~lTpq2FUs|g-tg;(SZ)^R!rIIkxK?{MWD z+`$t7;L&CM--9JA?dQ7p3r-KcIh6>3E<7C1V*0ua2dbY=NE79@1hgI)?#G=k1tK4Y zfSnEAixg89Om>iLM^s#A@2%6P|)bQpgI z@$yL4P)J&K&BRPjjQq~_IpU@R;A9S*t9x^+4Gg3PuF_YEC&A$`hoBvBQo5Y~R+IjP z0I&(qOt>E>ALqm4={94y;i~qC4A8lgL&t74$77eFFv>>?z23NpVi5e7aHTe+x z7hJ(VJ}Iblsc$Zh3nNP^uf7E}QfV($*9|0YMc19#u@jC-_Y2O_gC|Vpy$z8LtVp?# zkj9thTVgYGX@|)wEVr8Y-Pc)r{cwaeFCaU5&~7n2Llb{AP$U#a1gh4LE@W5=MfpDq z%U%twMV-sMA&lg)WrO5{-ifY{_6RpQo%G~?R)CZMT1k$>*T|2Xs*>!EpccdrZw;Pigo|*v}__#*R$t_g1mzMKn*naoo ziuV@WZ*TG3?mSdC)ot zf0nW@r4&n z^(fvH8VV{E`Q5~=ysP7b3$jMii=jQH4)m&C-B&lamSSAAac7ncvNO_FBwM-1-|xkE zt)S<;t*U$T$Ut_9O|Yjq$}aQKVl7~&nSHh?$e#269&A#3uokOdCL9hBC8Rz#Basux z2V`5f3%hQ_zs{H$7B9f92IUwU_aN%j?4HwQhL+Alw)fQA&?X=+6G z*q_z;vN@=F7MeEa`{o7d$C*+;GY3_0u)}BQjFwts3X)Ifbvd7b-?Y0cxo=LkoHHlj z8T)@dS$}`=`+eMGJgf%h=u%;k)pd4pS~c5@puQNKTBYHMU2!*=c@H{BMVD~I@8&P$ zf2@e?_kCd;-kpS%zec~Z^w^@8D3x%iYO-Aiha05(0?!IL07n2m@J{Tcu+|>hYxjiD zHn7g92Nx9tNt+MQLYaH6=FSAeKFeVK*;DpsHr@FgS~Ga}&T#$Vc?5I=6UOE%U$voD z<<{vh=}J(|e@~et#RD0)+JNni$mNjHGc+A}Yz2c%NTPOB#BOqRii478;i!Gzyz0)@ zQ@)d6!l7`m;Xa`aQ>?Xu`0<-c2De@qQ8h8xp--RO7=-qgi@FU?a@eirge)J(Nd{E) zuRLU|Vj{ygY1I0VzA8@Gf;Epbhx%}Y`Icm`Wc zb?tp{zd(U=C5o&|&(X-+?GUY85=NasP3yUQ-!PUYEHSKzd1oe6WU#G zqY~Xbv8CiipEEotY8^;?1+luRE+u8hBKw2^3a$CK=yU8;%{|*dwqgxh+jTnV<~2^Z z<GfM)R~VQ+6rBrBu^r-24V}Nk-<+n)(*Zsf{Qt*8Rp5^Q1|ub z*9IrP2v2V~xE)&K{ju2PnS%3)vwSq^kn;$so?C`Hqjz~b=r$~3{yazsLdciyJx3el zLydd-n4%9_^O(HNs4i7X10DS>`V+8|!X#Q+sB{*q95G8h)c`KiiV=2BLEvY%Ziz1O zEnJNL;&V6dzKTtPupMXUQq@4+_+{3K!q%*`Y^lE272@_Vm(#oO{gE;%udeyf%h+V` zZ_3FIl^JJ*)C(j#Q{dnODwO`W#1MV*Wj({{l${n4nifGZWqMd{v@N(3YGh7J&o^pU zfV5&+P*bb3udmqh*MS{=p&{ufy9N6L%%FI_oE91d_0Y7eCy}1uJsGwJh!_N1keW~g z&D3?kYI4W!W?iHgD_?2J6HhknPA}YEjVtNmV|Zxrk*cK7PUa*C9A}6thgs@MD=Fiv zPr*10_J`x*4igH?IFhk0-Xq+N*I_OkU$1c4WQ2~im70XkPV9~}kcl?ZKKt3* z!g{9nYm}V{M{)(RJX=Y7!&MmE8Wg$9J;1x0N{@iK#@rphND%8hIn)&7SvX;?x3aa7 z7Ir2Cl_b!0<+?dqJz)97T^FJ}W2hnJ%tIyW+OwR61{XPxOowoJ{lXbtY}S%F)K9g4m|>X$%Kj z6R_1eku8YUv%4pcC;#gwe`#H_8vS?DLFpN5@cb@r{0`V_jK+CcW8j6M81gXB?94RW zIQEj?3-3julhcKFHRg&p=iNobb2IcZ-e~li@ekC6w&^I;=cU)}U!q?!urUK1Joj5; zEl9j+tu%3+dMfqi5Br^f#!Golm1Jcnpf2v!oJ8&opMdVDb35Lq7nd2PYToH(lGFQT zEKrewxv_}!rH)vzD8}iqIyZ=d=zw(p8zw7JtuJ`iN1-EwSL?8B(KK^@H&RdCqYBKNSbIe*mG5)0m@z5<$ zr%0oTALo&Li_Z0!!_cgkrdH$`g;2@@k6$h7n>sI((@t3Yc%(D z|AU-&%mn!e5-Cm5c{-HWT*CIA7$Ne_W7UuLe+E>k?My>SevU7~9H4F1o%+S*$hsZh)cbo{%Wiy~?ipn} zQz&_e0{L!&3lFvSxG_QEayXxU_B)_fjR*TUa<`7B+%6>JSrp{njPIl8V;t=5mHO$o z*jaZ`tCrwGT7JbV`uN1XyNfFdbtRsAU6|j7GQv#ZD%+S$L2aiqc;ieNAy$--vS^3+ z6VP532bKC$h2iBIqWGJWI>8`Bso8m6dFsTvs7`_{1+d3seZ}7@w8jw_yA1*gV z4?gfU$>c{r@H}Z&^7

8wX4;lJ#LayZNNvbCz-9kyo53adn(2n}c~iDfDQ<%y{vj z4w~kspqP3UZf3w@f>QKHkkg{~x{*`ch*Y?+2i3{Z0!Gm-{CZ0VD9PVQf+1U)O zi6|KNyg11&thJi}hrj>&r3~Ixln|+s6Z{ia7~I$}Siq^qhO-0DTD6!^&@cEBfzzpw zt@2au4~OtrhLyP=usacxw;*TFId4du2`RDSjLG-y!3>(8N%$^_x`=0@IphR+u56*> z#}a9Cs3`b%$DIo*5`C=cHvXrg^$X{`<4Eb`)4;{+^DB>KsDT4L*#9#hDuw^g+KUZT zR7hUeB9)2ae0wy(7~B$sO(TMYQS~Z56%($d2Zcau#UHn@ZFfN=E5>#G=Z}~myT~%K z5EA&l{2F;Waz7TEIK|c{0ahT|tG*;}*rk;KmGWo-1hApAg6MtXd>&@-!Mbrr9SN*(IRD2? zHfv~%_vbOu|KxwK3E70jiqhx2{*>fSofX9UH{N?rIgff^QDrWCbI4ggWtOmroe%%@ zNlqh`5Pe%9V#^hkR1I3@_63~QZ>hHg&hgyc*;dRxbk0liNpuc!}Nv|+zyA&yCtEy zkz`)F*1-xfc)sN%Ukpmg3|{w(6i^b+*|O8Zyr2=E2P7#&Q=a(lEYJe_yT2#-pEC^27oX<{XTApMW>hgYvaK=67kH zZ!Im*5aPuG#qhJ2a|SYvA#x0NHj5|d3nln%P`g9Zd|nUWI@q{)-bOn+A*9FD0+!3d z;#yW9=ke4~&VQTw+R?~&{-_@Gq$D-AxUxL0Gi-C2Q6}Wm8#~lTutd=p+jbUiXQ2t^ zI7gE)%I3XcimbOSF@Gc1pB>=1Tnu@>DIXJL>*OBjipvM$6jLt&79=`%c4=pVZgaGk zw3oy_+#JsNK7IIAUL2#wob;50##mgdDe)ZITXj;a3m$Yde|CiK!HwPWFAb8fE{}O{ zD@|ea&fg^PCM9BW)l)#z6FcZv#gdI2RM})DpCh-*zX1Bj>T{DfN)ix_0sbOXd{b&H zAF(>ZO0wQD!R;f`=+a;cGuxN>;M*tigFX^X#0q_Ve^vcG4`R$}LqnMXs2`m=-x?^)2{ym3UjkCx z%{+?>PN~%*f%@^TaQ~!DX_jz&R#@a`cNm}biJLvyS0_#Y2GKrG7B`Z7lDO%Y{m~#S z@a6D{2|Tzd*=qp|IRNSdSb&cJ2=$}HXlj)0{a#6pS~)?b%}Ju zYUFK@U&X`CvdZ!PnryyCUbDv-_X8P%vELWXEOWvSJaSt7QrN5U0Fnf7PN&cCGIrLM zZ&7Rj`Nu{bj9=}bUwu-Oq*GYn_9zZd5ycOJwI3xKpf?QejI?p`hHsYV`<=0!&O6HN zhqMVSa|=8CSG{q2SCbBLnIV8v#zZsFb1Wq*ajsIU_u56NCBU0O+-Q@)13$KCo)6uh z7UuRaE1_z_6E_9nu!8YvQX`}o?gV}R2t!ug8%2d>dJKU9j}I`9T0u+>;X>1a;Eb8|YekD8y>Z8>5A z_d=v>*V4K9aA;PX9Kk^q9sZQ1r^e#}KkD*pC-HIFj0^F^ml-Zj8r96YgRg{bG}hn} zb}k3ZCK#e>whv#*xeb@O?79$~Y`2R8xBSC+Yp&oprH0*EwX&N%c7!?VDB`GEOB(o^XM@h{wrBo z=~UJdC@Al=a9P(whZsPX(|9d^>=~?-0WO)tX>~H^wFcTG*x;wd$oZ;38g<%Tc->6q zZ?wz|@h7MCsh~$m+C#~k9^vw1r7b{52L7JRj5xosQ--2?XiWsfoV)s5!*~F!CzTH_ zXmzQS)vB{W;%N{&aahHtxkSP2PWz(sa?PYRHr7+Z2usCp-PYy0&2pf{im3YgJA2$8 zH`YVjbLqFzo|O82W1{1ko^1I)0MW*V`eJLd0*$fQ>RTryt&L9n>q+u|-z*;;Juhb0 z=!rU|fMwlYuIp6aAO4Bj+QMeHI}*i;lTh@`^U`iPV(cF2BhtkdNt^Pek;_4gF~Or2 z%O1`~9^Et{{oNbWw4jRvLzPto9QD;U?4zyT=D{)&;W=?Sym(0DzZT1-H5ej{Zo^al z+P^27A$7Cq!Fx)i*IbxRXo{V;F8jr z#e2*Wy@=WFrbdd~>tg^MWfGS6<6FQdsWGbW+Z=aly#?eXM514U=r-R3>J+!9i=U3k zQ3RaC8>wL)3X*~x;dY6vJHAFG=e_x#P?pXIM8-EB6q&n}_AKUf(Rq4d+p^*lT@L;D zFTML*JMiZo6C`2EGJ<6_yH=3|$$|}oq1XM)z3#UiA%43Z%FiV3o!HAUbqseR8^F{Q zJ5%!`GLtTi8!N@QJg25sl{ahBLs=1fv+8ZqAm;$p=1dwthr3k>_{3>BzrAzqm4R^l z;;WwL_qq88TocmK+9q2sNvw^?{_TgoRig7VtfY;$$kahe*C_Lc7hKj%sgX0cN8`0Ne$_tY;6}W&n0~bz_hqA~M-ixA?55FVqg32DwDg(?>4{~gP%NBu zFBD!{?Uv^m5FG;itNh{--1UQf;8(;x$5nHw@%o;S-h7&nx~EIwu|O*Cp7kYPRmZY%1Vtkrn+o&ybK(WpMc)BKNP{xUMG zFX|3|GkX1oGj!MT(l5fY56zd48m$!!n2h;^;9l_6K0QW%>y_2l|-Yp zJJ#b39brscxsQ}VR%5l^FV17U1h%h+PCiXR#qsS=X7c{~$URN4c9y>t9+!XFBkukJ z!I^cGCOMRZrpfHtNBHwME#=b3R75yC5?6k3m`2BNsLb(Sl=aRwL$5yi!sW(6M6Pi4 z>5CLU99!5IYuy4o4gCM=_h`QSb`HL2vAKQlqFWpHm-?U%{%$XcpP@O!76#&*=0Fe@ z;PcWU_kfg5WCi@KxrBA6Nk$K;89;BZIAFV`NNb;G__$!>ZOH-VlU^`@|ic&$Mk zS-zKF6S{fPq~#oGYmaw-K$FXOKw+aY%WGUcB#rPq2V+F!DSW6?kR3?CAL}Cz_?>VD@Wiuk#+#V)(f@r!f&oD&|<0Q%q_fACq|uW_%F( zlb%H9QTITF% zubYK&?x{(blfKL*nr~s~>w`nBH|$|uB44F@VG|(Tu1-!H%r(t9P1LdW?odu~n+Xl1 z9y;Y0S^Tt^c;c7wUlVGvDdw+8@OuuBgc@rl6NeDw@s*7Bh?M8L?BFq?Yt)Nt{4kds zb0LZ;5!IczNw>l4x2zuY{$>Yh)gXC}!NS(M#xKRn(WkZUMxCq@it!0rZtQVrnjmqh z{(kycr)PAbzK2Z$bWyV2mn;b(eGqqy%632K33zw&8l)f+9NTl$HM;*)(}msVB?EIf zpyw+~?8&J9mf~^1J>>MQI=hi+x_rkIt06dX0tMM1)$TjGpN1mqfBDmu8|p7Umsnx6 zL|>Sd##7wx?2%ynj!IwcM^B<5C-OcOWo;l@PSxm2-nOxE;vALI>`lLMByFBNVHfX@^j@ZKlg{^iGhw2NB0TNuPXM}E_HhyqHYEIf=+0ds6 zd+F)zpM6y_6hm%@{u})g5qF9|og>3znl1u2_5f(`5TweqtQ32crb z01#QpX>K(ewijN<%6(*!XpiO1(rrDwJRRo&f4sa#T;C3zTha^;)NvBPp|FtjSVZNj z)0WgXc(|N_v*!`9KTEVXB<-VCZtMteFRNvB4!4YDz~h~_gYJ*93MzWb6_|=XR3rZP zv0B20`WPuUH`1cjSmdw6|EN2R%}x|Ictlj=DAW|9-)t=p0Ag#|mEF>MD=}LHe~ZDP z(zbm=12@w1N@~Nu^wg#Af_F-W>(m0KcpL_B+QKV$DEvyudCw9G?vvsyT%D&bCEm}% zd}A%|=sh8|Vulb&a~I0D_lPL|@U#klEiCLk`IfjpBoj33irmgarT7oH>{!?6FVAMm zKZ%Qm{!|D{Z*t9iy>rXiEcvOy*E?NryJG}8>AXhcq6fEQL<99Jdk$tyO|(v5$}eyY zGle@?^yb=$SHIpqN;m&o-&2~-%ej2gWy7>yrvuR7AUFLe(BAmAk>2pfL>8Gt4#kb9 zK1mD9u_rU8hYf(m?q5BID;2ii^D)N0>XVb)^pX=PV!lP2b{x3-rZ+)aMtd82 zV&i$Y+x@(Xcez)u?k3@-4_^m(t(ocBbTZu>>2E9r+y+k+kY=`Q&!0hPQy?ptLAQ0# zw8!Ue(9Scmq$qOPqIg-6)=Wz*9lDtZ*bO+)Dv?$SXVM0ro_X!P(llqPWp`4#KRF5W z&Two{a%(eP^jmrpB2>H4I@d?6_LXvA+~37g7=Q@ZEYDTZht^Ma$iLehyEfX?GPVuRXt0A zDiCWz_PJVO-F{ngvp#CHf+ShvlTDL~$RMqmTtx*{w77}n+>)6jhO^%fv-%|}A){QJ zV{!sH&Znu(IcV+%$KTHr1MM67$kLHOit|@k<6#F8TTwH{J}|z;g~GJza&N=(;(({c z;;T=e!Ejw2Td}<%ig!k=K)WOd0o+$+sgp<+mv{KXD8;Ja!PgmA({`2I$f^Sj?47K` z@xr4fg*o=67QY;6Too>}=m=?1gdCg)*mV2L^n9%(bgItNs&0*irlbu@BHUSYb||T; zK%6nM+o-qKde`-+$B7l-4H}>xi6Fgb>tZ_?>3`}woWot6rpY892D$ST9XM~+wOa4asZ=~MSX4a#P< zbDo@06T!_c^cISBQzg2_!SgF)8yU(41-=T2vIsRpbCJcf^WN@|IKB^bqwPKnx$v$x z>h;(0cWFzw6sb@RHb6tfB6!TVqT+0SzXY(s=AUi|`PRCT|HQKu$C)kAza`m-m`h}R zWuBJ!q1rW+eBbJb;qik`>?2u5e4I;KmoA@tHqO9Sxu=x3p&9Y{;ru;fhyZ1?;tLRY zSQ8H=Si>D%<4HM{FLs1Z?%(9JR&80)xgd{h|7a~jR>niSXF$uU2$1~Bo~@>d^=YP_ znu{71DetF&K)vhE+|8Ex&3sdj^gdP){cYI@E1HR|#KAmMy+GxP*LDhKN-wp#yfA;j zKcH%o&s@H&>F}VfY=f9|$YuzLO3;x%k_-aBO@z8cavH5Zo@|zSy#KlUX@SCA*D+!6 zKR1Yco1T^JdE{(}dn5rW*9v@MP2q^7xD}sAmOBLk=0L(p=D7pHU!)>e_r4AF*N#PN zOUw9tU=Wv#_r39>4===OYi@yM*A4r_dj-1q4K*ir8}@Q^@X|o>N0M#gw;k}v3(D(d zKAHu0KE>3Zi%dOD-Nr(~I_&P=nC7BZE!aOpq_y#g19^TDkX)2_3R ztEUeBa%mdPv+%z1ajK?X2(rFb>WC+#o{l$2YYWSijta3CV~} zc4`=n%+_PXeZmBFS$@fG2RWX+`gT^bbCN)~!cq*ENC@EdRMevR1i{xRp1*usx$b~@ zQ<{;HiX!_{K(%(uQgEu?9y!IkHgxKlB)WSka!V^FUprJWZ}j{|1vSPPH@vC|X+ zsqvHJdH^sgvDf>>@ot#s{G^^TD7U-7-^Wu$Mdmwbl+e-xhGNvr-Y%k)t)t18UALK4 zHRauMm#bc14e(z#$P;tjJGe!^3S0hxI7>AOpfL#S>MHLA%&_QcHt?A)!D8}8g)Ui{ zPY$sfw9e|Dlr|X9SkzI~;F5KQrNqyV^#k8)^FQ`F9MPdhr6XEM1L`K4DMX!p3%P;{ z^!EBTCGtDV^mdshB~_@<=MPtIk@z%nn0K~+mlE%@s?QJ;aXGlizCG&zHmt!w^}@Hn z$=@J!2Roq%#AAHn>sQRIzpu#I059osM3n-$ixvfig}oL@kP-h2wjYewl$sAFbJ~lY zu9WVo)JS?h$Ug6TWj_N0l;LB^+}!2qIg4MWJR)b`hbn^rsSj=5i zwtZqe2LZVkJL1!xy_) z1rsK^=40ClH=KxE`-0bA-@n?~d%Fa^3Hq4LDugXGlKnxmQiOs9pwhteR|;l$=q->` z7`Op>$QxJ8gcN*XtA9f-a1T%fr0KDiv_YdUwS!sX5GQT5MmatKAu+U){y?28UrzzJ z!rR`j8rRokT}FogR%rKPWWyJ!jOoyF@m zAFka1p6<`J>QdY4^P3@pt#_Mf&_}Wtys8Qb*Fgj^d*Wi+CgJq!D|K#jN_4OpZ zxqpejImmOQybjKJ4BSPkwJed|p@%BnZhk{y zfD%|Q_-3Ve9ZKwP#rU`qM}3t|;i05U{HXlS?i@|%ud_10H>A~TIYX~u8~L@4a<)b( zFglt!s<~=?2>t;V5m!=6g(sTA{QRf~=PCCge@rD_bNIwurFiV!(MJ=o zC}EYp1Q$cSsMQYSd=X`H83|sM2FYgn=DW&!s}U_MMTTV^xd25p*-&Rzcms#RkvC^5 zm>kvb=v8a&cTvw)I|Hqj{|^3R?ZAN)-1XR_(f}8tIT@YMv^*@{h!|7UYFP9OFIceA zKk8ypz+Ak=`xWCqp5(y3wnGDEj2m1`+f;nhvEqAu)4290Q#aekrs>3<0l`bqOy?|IAYWp!L3o7@OJQm54$q%>b`f#(h3-d-AFae8aGK0`SU z@ArGHA<`*ziG1#s62jM@l+Y5uGds2wVl>L#f9LVIQ?3Dd0el)8-`EIN7{T63ZW3mA%e zmON-}S_>`eh8}K9w~~8jO}y9CX1)B>=!6uR773r!i{O1I zc_6RmN-2lsjf-h^RVV4hcXw$=JLL<3h#lZiAP36g5gz5Yk+k0PVf3Xk8X^mF4YdX<0Ss_PXijGG%WIJlZ7;1KEEmOy6iRjQQy#E>&KQJI+wBfD+}DF<}25)oyiv$d+A=#sxAw2lM@%Knku-@ z&(qR&UP!K|__FQX0iH0AW1=M=;ceTXDnqeGlaecX>gn~f;VRxZ(3-d>!;VeZG=|GM zi!uYOU(E;+6As?raTC`^oN?vtH%XhqE*##jcnaXeOJI$?y_K)ddAMSGC zdUG`eD(&c7>SZ0)vzL5{%&;gm21>HIKM~M%o8NJBQ0y(vpg`1WTJ1=|r~Avm5731K z=2~-jzJbTm3V}i%@FGwH+z1gJ3(86aQBgrVOi!%O0T__R$08{fMYaLR-NQG()e7^u zLrb3*1bw`NmGob4Y0>}o058FDc=(rx-_oP8Hj;UC$!n!)-bpo!m^7c?g1#ZsEJn=! zL(rTli4qD{-#-v}!_^FM03g{!q%7ccc!9RhNJPF>=5T924UDi!oooW!p z++kEmB7a{M!`YWl6Fa^NK>XK-xaGWorawg6LjWia_VjmH?$*rAth5o8R zfWx!Wsh-;0^TL6`^MkWQs-Y4EQA6MQs<9SxipxE7#NS0#Y?DPO$6szR6T61^nEFdp z&4?6eZIw`dBa-WLBp7fJ+`!OqsVw~yc&TM*Vwb>nVPuUly|Y<_5xyJ z7_HaX7~KA;2gj|wp^;rU86(a3u6O@rw-+6t-ZU|}Xs4NV?UG39GFm8b@^hxBg6UEH!D-ST%yTzU`)xx1^N)^rPnFgUp!Q>M;o?MI65jo8aZ~v4*aOGMd z$8(#k{Ny&!+I7mE{9g*gl{WF^ss!D{%qq4!?bE8gg1`NP(@`hbd;)52OhHvb37k?E z1r=@=1=Lxefr7CodA#ENqDxAQhsy;1E-c)FGp~msm?au&lgkEaRqZDIPTb#>k(1rh z8yxbR1xq3Ozk@HDVy`|23Ra6?^CgiUVgvA?@BimPnM?hKxHcN;ZXqu`s@4iP2-96r zA&P-PU36S=8(pbYUn+l~(Eo?1uMCL7YrbB(qy?lA2?Zr21q2k3?rsF6yPHK?K)M?# zB_yP4kyN_7LAtx&yZU?H|9;UA=w9aDJ2U6ZnYm_S?#;@t3Fz>Q%53zbFJu}{F1`3X zRaobaF5iz^&fYPBQoei=DirC}u1lVesdLqcn$(fegS9I_2;c92ysh>5km4~ycg#h{ z^@9xs?o*)5AbWv&gE2BxKA$;nbZpOugI+XHFg)B>)H55BX!sI$nkabh*yB0RinOYIN7S;)RS3<}20`uZv zZLa^4iE68ls@#MVklf%2pQmHi<=?3RFH!$W$+iY3yT~$6h}C(!(dTBdRPOYzBI*#k z{&ZW%Ot-<dVXAC}5R7dD=H(+fV(zQRX$= zyF(zQ0?Ck_R`8VXDi{#%wir5`>{>NbI3WGv^W)r%Johcll=UGS0^?EohJusiPa{+J z?Qe8XCga5cl)DpPee`)FMf{JsdhGe*4~vA<12Hb8j@m0XEmHd4Z+_QgE|LK!H62q@ z-(erKrArby4s=&?CC~m`WGa$KCknE}W83NX98}h`P23I0NI!ks7G$i}q*d>l^RSo$ zE*L5GSP zzC$2xwxoG;!#%gPLhiJ^PzU?!bH|4xgkVaA3bjm~o#*I0i?GjW8dzp`S*;`?3UlZa zLi(q?vFid64n{Rpc!|6?jJeq}AceAaI5pyvB4U&IiV)2?nib*Ahk;WnW^BQ+Vg`a1 zyIn;f$G)Y`*!j`nLuZKF*A{-5F& zYm!u`L3;?%8VV50;~p|^o980%e${)?bgy2Sf`km!%@=oi_In5@t;@a32XeCCkSDHy zvJUn?F-fhV2P?#YHFdLPg+;o1b)hMRk^zzkBK^G__12ON!472L?aaf^`%ZH|XP-N> zIAO)h>elxGh<2@US?{!PIQ-GKp+tFh0w7lNrgIYWo?w?MnR`GMQvKhrUnIj= ziXh=F%b$0?2b4iQ1_ehzCD+u{w~H?f6n-^wWVwK!veQDtSglDqqgaR7>A46K;%r*! z>Z<}xVi`e%6o+l%omaTKHGks#$Lx?43Kk@v`|$VW@`&ZhW>nTjh;|v5*ULE(4ZZs0 z@T(#SAL9yr4R6O*QZr1gm_~(SIU-)&ihUU^;SEgfCPRa+_?|8Fl|S1b?yCaS=-^&u z(E9hpJ7>QiAN*#t>hhE%Z42mq?tUtjlv>%%bWu&nQ?35ulTdoa&Ye5gV^`b8jrUr8#28EU;RN?%xo@G;So6Vvmi5Dg|n5gkLn}7;ED))0GMv&$gm3s zTpXrH*>fk;vawE}oxpxl5t05q#LZyhZNU{d!EV(U`@PNDDfjZW<7Axf=ecUqvaMxz z4R&FS+I1eokNIxxYRuau9P%^sg4WGVBjLJ`-2w;)0xw43$KlRbXaAsP*MAOC1{XrV z!V(Qpn%owO&S+4x_-3!o*djv)#K7*LQ#FSPh~t5xQ>M)`p0~sg$AE*qG6I%1ksn?( zcqme@H70m=hpKxzsAFAde&VJM9?sHv+;k;!edWR;Hmc?Fq{aKU#O>bCXcKIDFF+&; zc`BAq0zm-X>+>a(beD63C#njeeKa{iTjZCzKG*a%NhJES;Y#vZ$+hjc?1~r>CRxzI4iOk^{sm5_u=f9w2Sk{> zuWX95=UW^k1gEG@GV>LRb7wH?jPD+yVKCOkRq$@jH*qVdOVDY$GxxEss#esyxfza7 zP?1CiV!L193G|pJOvT&VT5qq`!l>PApU}vves?GuxIB4yfo4)NWDXkcf>Ib(@}!QQ z3(0%U1KObv^C{!vnS|F~JtZi9fzQhbfO;jh?tyAW&~^eDLMO)rery9`cO(la9k^_1 zSNR>Eyta)E7(#w2gAn8=p#kqySkXT*X(A^ElWm?}?#}aoZP~EAPb;b#i|E%TUHC4e z`{{XV0_~|W&<*b{tX#(tJ@WRZB!tFBN<%IRi}I*~J>l|t$Uh;#&XfR60(c!F&Syw0 z1&Ah`%WFIl2M?>Cn{hZ98y`jH9ja?k`$!EB0D`2Y`Luk5+e>islMx!+g*=ql14XxW z|I?|WZx0`^pQ4(n7m8UprD@D;`;O3OT-(LMwZ#_YH=d^6Z~FcmvrV6gb>s+yop*Xa zpRMir`d8^1bm)M1ptpZFbp=i0yd9k2|rtKLl~l$-OR!zJE;rIX&CkKU^8Tz`uP zZT~v6)%@-pUv7<+bvnnlrDoopd_m||K^Dvrai?^OqRRvTUiZ_ipftJv`xnzcMnGgY zH(OIV=VJOCLudWndK@>?*-|fd5Caxn&B}DPZ#C}h?TfAR6Mg^;=x_$ET}u;kUQL*ATPY^HlQ zYVVgFr~RH#9!+?aU z)=ZTMHVBj1rHv5C_s%V|Ert5p|4u~YQ zm!ddN#rKr6ujD3gUw_RdWoAm}i@NqwD&IZP%@m{VF`FUT|4cSHwHc$p);kJ+pb&z( zJa$m&kUVPp)@vMeD#-JJ#xc1sq@3LAhtX=kGADh-Me0e+NBS9xrX^Iq*_bKT82*&x z4e1zgt5F+J91eLVCoKbVEO&DEDIYk`pzD0|xZm<|hq31DJ|AN{XfqC8Cvni#xRQi?$Q}vyiB-$fDdXaCQP@R9(zq<*^05WH? z?Pnyd|4u4|Vfi6M?tp^=0u={ra46_5BZJ6&!GLjN!`fN{f`2gLZkKNMFqdrC>{&2C z!q2$IB^>t>O>R0r2JFpm`k6vM%|CK0C5-{VJg@`5 zE&E!WRY9lzrol7IisV->LmfcV({+CKA8=dlR65e#{X>G%WN`ZA1Ov0j$5S|;Y+q1xsTa+WG% zzzGSif%e%c*M<`IRVP4=ORXUZUgkM-MaW6JFxg$qPk~_@bhoE*bD0CzyZ|!V2)LJ> zs%ib}b%2RB!ey;W%H7NEE;)=4a&FiY$m|vvAG7?U%|k;radvyh(`36^J>e_6gb4nQ z>5%d;b(cHIUAkS9)2^q|*E!LVf_3ZBRelq`U|;&p#C0mU3!d01uY{l-px#-VP7kdL z`ci)xit_2m(YWi|0!v?WPccJO>cRdL{PH~htB;ucy-l~)5SS1i;6JRaF7c-300qjc zarcSySgnSuJ~FELpjJh}Msd@n`#4I#NZGhB>hw-0D)A7x0PFTW>(Mc*z$iaU7O5+T3O@uvHP#e%&Rp^ zxktH{a=fAlVWI7CodEDF400qjb$B?Cug`ulLd0nmSJw62aR$y~jrPU~3;EfJWT^gY;2X3oneJFjy1lt(=wQE>OugZ2+-B|Et_CH6Ry z0g47C)i@F$w|Zzo*!y6HC!58=Y`Dz9vkA~1niFkrIGOr<;mv}V=T`2smB7ay#=nz? z6Le5ypcxVrr#s^+QkN z`8TzGqB$#tTF$9DIje(@uC8YnX5rJP8ilkHu>^0i0|?L`2PzDEzFfPz3)#VC|FHLJ zT`u2CXrQgq(qX{!b4+h~-Fo9bzcuz?e&XOkV~mB)(G_1~{ZZB|A4F%8`3)ax9Y(a= zDb9qt=l%#c0ju7eJTJzDnIczypJdzNODd(uh!Equ=Yrf%2_ysymb~{ge_O8MRABED zFbitrez{Ce5O^?}aJx_a!i12j;RmBnt!?g}g0l>SffoLGom40-Dr)L*j02+`Xh!sI zMk;d)mLOg6tZwD!dGHP@c7twbV~@Re?SNM7B6xh_eyWPyvB4!KgtcV-`Yk!PuVsDMMcpwbket}HJsXpb(K(=~M$ zn7-rtdYh40{LFo`8_?B8=N?j4kKR3Z70h~WP9AC*%&?8w(PjtMB`TU5sfYoSdCow4 z#GB0QM-;hDz5Wvi78rj;80Vh^DfXe1tIzQz7|v)^V0vfa!k)1Es?c~Uck#XZt#{~&_aMtC? zgX1@K(^VR|nk`BI)y_sbFi&53d$_r~j?Rc+`Y>)KFpuEZh3I_N+oLSCnKuzWb@P9O zBMd%zLp9q@?hqW%5M(i_jHqXZHWE)=sNteR_>SOjzE?pra3Ka3pl~5C+n`#+YW+D( ztBZwF{Mrrki~bea1$7{xCI4yx#LjDJd|CNES{zOY(AePixW4dk=Gdu zwXR(I{uej!Ze^c#d&`^Fp z_<88U@B$3Jl9SkczVf$FmG+uOwg-|mhLAIUHJ zrG-TNW`q2{{kqVmhXi$w*niMN(Bo!#S$nKcdg=+Gmt-P;PenbOVq!@5y0shj|{^51kEIcO_28tzGUJ$J9Qbi%xOA;2IHxdD6Fp}+7&1Zl7){i0dTU3Pna z>N@So_G)L(o)H1u0?RdR%}jJ|Jo%;YQ!23#Ba4m*wStF6?F{mX2*c)q$xlvii8% z8?})Od9p=A;GGU`mNpP~u2o&(lIaYN`>?5W=eFBgDm?uh_oEKgbb9=`gUzII%OWdlLjj+>YHT-xJTe(c&5mX_m|n zU7-mWimX+jaLB7MX<y%4orQ)iHKt ziC`zWAbL@L%$oj-)=p^d%)D)1qQgG>S+G-h=St$~!)az_Fw@6!Ea6v|#Kse9e_)(K z(wl(4XW2MlP{ZIT7}ggCZLL9kAG&3zT|~}p6jJD{VF|ts^3pdZY=z{3jF+~V*`H8M zo$FSU#>Tf5n9rb&{5{l|G(0Bbn(hnOINwgBVv0U{rlF~HCq6Vml%|dji}qq+g9ov7 z>gGIivgX+se{;v0O&s!^N(A??poN9OJPnPN;1wiicq_&0hJO(tx)L6KR%aZzdm>!l zpe_FR(xJ5Cf8*7JWVgLv6uv)%T2bY5zM8o5QGJ~Dwfq}`hwee~@`z{&-CY==C|7a` zn9=G=5vtenzrUjhi$+oBN60A>gf)g_!nXMb5BQJf(X(!n1`itE6)etpzT2Qu*PFRI zC(g{FMW{VCyL<${-hBrDTwio_eHyNe7opoK9^T`+O)}IV>CxAXA!giUf zbs^{8I1NnU`|E#3w=QP=L%N@!Gd#GJmk3XB=3J3@A3u6gMl%)<(T-L?TO4Pdo#SSD zgscBtS)lyQhji?7uX5}UV=@BA9+xwIFZO%7*sl?k*Ad?zD!p%(>WkOMBFi{$alfT; z`h=xQ5ZM?afwnmEEeuM%N5ZnlSu4VM$5~cV%6=WGp4D$ck`jsBozW^Sh%2#CVDbXK zB-#JjtOz*>X(bav)q{E$gD~4nQR___^-|8am<&YtD$HQY$e$iMUBRn(ZtN0xxVJe0yM%hRCRMea5bb@hh*I))zBXQJbwr zhq^=SD@cAPp@Cyq(c$R1XMhMAxxJ?(8DzEr<&oQ$yK-5IUi30_CrCB>Usn(kl4h*p z_wvs@0lqtG(JIH**?OU-IETen2Vpqka}y_dboJU4HHJ9I4%M%U^YGn|MQByApJUaP z{HIbY@<56)bN* zP$xH`k?c&rFD;n3k?6y|zNCjgExcMdGR3~@zR5?jGcXoGFyc^l0JpGPLr=vg0{kVU zTO>(F*tj7`2x8aINn;t&{Am9HQt2(?hPzm-B)O|o$Y(uUl;WCG1eL21Buhr;3&7Im(Z|V*#h!M1J{q{@ON9;O>2sXMg;?@%92LWd1gBjiIZ|Ip98;UOLs)(3BsT&rUCu}x|@wXs^GMp zs10Sy#)6=fa%HZdy@W_&RST%`ACkhzc5+$)q#r{gP=}E@0(Y6NcB$<^_|y` zUwg}B1qnGj83>1?5@Mmd2{n=L+r&U97EL<~YBK%T6ZhJ9W{v_@j6wR8w}y5w8ZeKk zF22g}EexT-So|U&-E5NcK?mVcIl(m+_6R5Tv65qMz8uEH!6*$sYNv%2 z)gJSS3#3{*LNgeeGzhslPeFJz#wEwp@5+Dt-t|D?xjU)$>#`g6OWrva^CRtGc{R*n z>Ash=a;B1K}VDM;dj*8Z^P)sux%C|y_`aE(X!dwwK{sz!3)ws z-uQx(NK!AXSYNnh@+SXzkHRVxvELE;$B1mJYBU0heI6kj=bRF9KUcMrX9;*xT)tq^ZNxMP?H!pkD*DmYvh6=%Efkm_y zVrwX{G$Dk*7&PPQ69m4ri4)GMWfX)M5nX%qH~ZKnhg>L_bdZUu2YmmXCB2Z~AE6;$ zDZ&*BCaKI(3%e%ajzjad>8kgYrLH!Q!h5dWm*#&+pc%a0`VAH1fNJ}43YeS8)VLK7 zJY3M8iq`(LnuHg~oTK)k2JzSy1?PEm`%W^L%fnyPMr>wv%8l)GLVZz~BKCoC!TtA7#3RmE`{VL_vxP*R2#oVZ^PoB2ZoT9U+QxGYJu48In9Y2 zNn5gAHbrQ7Dr9YKXkK+3z_JI1v`g+5kAh@bcw+GI=_sFUtHghd$E!oorewP(zFb{^ z+8Jz7z=kjUkb*@-KBUX?deumf%-TA+LTtQb?}%?ByGvZ=<^Opx$slL*<#hsD+M4w; zBo}W<8#Dq2+Anieb{dG-TBFos(X_wpE-U&Yo?mT{=T*D|`v&Yi;nJ zo3MJlpf!3>tLJ;T!}025j&kme6PX~>#HNoYY@HNT3}8#uN5EK zqo*IqTC-}PZu5+3+p4gNFXjHru{Sxm8}7LOf#j-csKPCVmT8aH7vpE5PQ<~K8u#B) zG`veugXZ#VJ%WP(q);f%!gO#b461%Uy6Y**)IE@nyrY-p^Wx*xkNEEyo)tNAtx_Sg zu(Mafdf#-ytNo!f#7OqKsg1c6^9)|^UXRMR)g6{fK*q1l8o)6Gk+jql?O!(SKt|{c z4q*a#DKM3O5*o<)Jzr0sR#GPkE5=w`nh=FBzGuqn;vuDx$YCN@gLH>RvOOY6OEr$? zQP0DYPg)(nykVU+t1AKRh!Z~ZcFkgp!6I!U`upv#^{o>1(a7qfTD;o~HcP*)8pT{8 ztx%ItvkoEfzS6qOdS_mx%7>c1B#K(5bFlvSsglPPYxU}4d_0<>?Rv%&V4+u_newmG zE$K5x{7JB8xO0u)Ev;NhMSJC2_f^wIr7x$Y4=xf6(x@aA)V| zSX4Jt1>!c|$5T_A@!~C_#u&XFeEnF4sWbYglvvSYiw~p=JrONuj*F$L!ZUt-dTM%4 zd_oq3Sa3w^a^Hl`j)tzJ66&els^haJ{jJOnAt^Y z5y#b+%DzOnC}?8Tu!7@7Cont(zHia|8yv%~7u|-{nUl-@kf0pN_Xf0?lk(Rv&$9$#1Q#{8AS?KQi`4Hf_ zc*}aN>woF+KPQbvt&05wPf_9dN><&k7Q$$jE*FR+qa-DZaPD!72rUL|e}VH+lcA3L zg}klyb*JyS7$0Q9UO5AveTAfTtmBD_HcJ;Gl?jW#m8?>0qJ%cN4g4a2AcxVv+Ave;re}5k-K~v0re;CcTVt= zqvPe8wIbndM3>4g;AM~NWKGB*p!dU#l`BVpx-hQxyCeg|mRALEbzlizvF*+Bz2 zXeKE~XCBOucqWRT_5C3UwRQ%sN(S;z!qF1(D6lWS4Cmq#-0$5SRrBqR=9cGB9wku( z0(|yV?{V~-9W{f?l@{mK1Ob{6`?!(Bgb5Aj;7D9t(J9Hfw)SKvDo!g}cRqzIB)iuD z(f{4Pkq1%`6GL|V=8m?jB6RK@X)fqLfRrTGg#bFbA?V*N7mr~QZ&E|8Q#%b|TI2Ory|A0DYll{_XZeX7a7>k~SI(U#k^ zgJ@|b4EJLU zKU#LM`s<&l+N}^6`Vb8pesvA+!2I%#>_fa1bx{u1s*XTF9NaaeQP4-3IB9$-lN!sA zeuD)us_%F*I1q;WKFZOs;dg{k*=h|EVhJmNNS~-}Yi0jrBr9WSq(&V@Tg2*PMl*`PzBP-MMpY3{o>Zr3+;` zWrN*Fmv%tDo%fhGS2_bCG9Sb=qgdr75B!kfUm`MW5#V1w$K8PFn2zW}IJ*~mBGYi{ zC^y)CPQKCt|#$0yGMhRKd$qHe_z%IHI`Wk zjZ+Ea8GD3H1r)Edb`d6?J9y(O9r*ydajfy|Qo9$<3BGfQ7~}d(2_^bgghx%DfbK;0 zOkj3zP(crjV*pokc%Ub<^Diyx{^*`&@umeyp7?jivsd3tUW+!jYhmqNstL+DF)m)Q z`W+zawpAMwJ^n5#+p%vM^rP#8H(`7`E$+lFEzOSzop2+5sOAc^H#7dZWZ*>z&DTSI z2S6rL(Rll%@LHoGs5g%rcFppreOR8^b^kdMfCd^GiE^$D-mL`hi4i~-^gSO@mkfL~ z(O_i#>oShW-g(kKNg%UdOkgAaNYtu&z*w$#M3xpd%-4}u!ge9-5X0+Dj4%R~O^FKP!)%Y-Rds>4& zSy*N@?6VDIi=O{V%ms4Sh+@VgdOldAMjexS%`<@`+gYi88u&F(l=TSzF*~fCXKlp{ z$6&}Qt5H}m0g=-1ZEmM;a*BV2h1xhhPhy>tV5itU;+_r$GUq+NpH4{2< z%_J{{3<rX=2& zzzk$`GKKJ5jX}aLEPpvlzl_q>c_HvGJbFR2ukr9Nse+LtZt*k@1NO4H6I~(1l903L zCj~wTu-Yytnk!-?C5p`rF?y&fVFM8#1PPYs9edEe_Bt;kG^5(gvl$#UJj)jcV-c{# ziARL@Lr-9n$W=Y!_#TejTu+QVKH08vSs6IHowvx z!uffqFY7PpTDVsYj-7f5JJ0MFS|z`{k;&loEr=@Iq4S{ z-a5gg(D{AHQ~v46sW}&DmH)aL;_hgLrO} z5E%=1dng}~p4VonlYf0g5^=Q%O#?pSWs+iTk^2a45oOu2oq{SqynwD3?ao z_NP5z%lgaUIWXM$B08M~o>hbtavf-*f(Utah+we!Qsk)6KZCznOdd?}j2*ZZsf!n8=rD_p)iE}$GP0Y<;5h}TUD`Ssn=cdqu;x%C6YIb3F zi{Dtqr@X1GqQ&)RggqhKhCaOO4%Ngr!h9 z{XILgT1yu)IknMW1K5kh&HV$if=oHqBI1MILLpte)r4hZJSxq$9|mN0!hY-!Y%XMr z@gK2gdDGdDKdUhp&ke}uqL{tBVz|_3V&L^Q*9)EXt4vZ@=SO(@rRJq4Ate-0UN^lA zlgLGR`@PSI$i)AyQSc`SuW;~Im)8_Vc4mq)r5guHbI(DH^l2dHN6xTDxx5Awq|6xz z*%s@Agi=s7ipZOr&xBy#ZF#B1E0J8t4L~WcL3g?B;LoYQf{JReJ}wbPM`7hF1qHRR ze*5fC>f(KTKQJdR>+BC#>NlC1HI;3!8TEHOvisrHyNv`q76BpPrrgo~ ztME9O?gl~5t-zx!sZHYJ2-M*SpH9^A=#DT_=M`f?=wFu^alV}PFR)t-m_)j(3`Evo zbN^fM?2#l17=)$}&`U=XQB#Fz);tgkPQu&Npe_~q$pTxY8WvQGy_vaHD)3zZaQYXf zpCO0oqv1FD;t;M;%3kz%USswzX_xffbxuGf%vC_Vt?wdP?hkTB8+^9c@a3V!~2> zWKC91f48oG8f-8ekD~74JeuC;XZkl?MTqeD9LCg!&P;2oq zB5W#f($ul7ik?#`hMmki61hTfVkJQGsE?DT@`Hfdo)*b%U5Caw;jY|odCqnBb5N58 zsp8{Kl90z>N5Q=PfAoSp-uOEkuT~ZsY1+`FZt@S`k+y!X8eRlL0QAzit58my*}>_Z zPl^~~EqPa>>f>MN?ZgK6%PhO8bd+IUqDOVY0mi30TeMu3igeuzA4y907%5G!W~~cL z)z$OTBx*)Ap>0egMlfs`B{OufkeIckYTAB%hf|=LP1oZ0;p=7g=HOLN)yI5<(A3R( zuG}wfXhx~VN1X6jjqlFyV?slFM2gao8^qt+$>_S8IBqcJQx}j;BLwH48(k@8<8|Z?yPbh5`XW53c2(C-5Wx~hokFK@Wg_R=#rUd= zQ-$o0MEIMlWk|_FzdCAph>}h+lmm@8W!ng`M#{C0%Jj#+cclGK3jpqRqgNj!>BMD4 z_09VaXEX1d-g?z)FxnUC?)u^WyTmVpoVV8A*aBAWiKbIEZTCfgqWRR(z_~wC666N$ zuJx*`_6?dr|-UjnHtMP@>dT@;htL$cE;CZ+(9luUY(dN8q1#^0{Z3B9@)pyNZvQI_ZV=uZ> ztv$$}3eX4&N(dnE9*gE(G(vLTUQSB@-;E7&U$_fj#ppGmp_60jEKj!>f4jO_T!l>( zGtopxvJP@>{C?`r3m0uF6I(teo^{*Ojm!WL9%;KXgP%(XcP+tkaiKJ=-}VC0#!AKg zSPru#KI8KmI3|3o(CSTUzz&xCZQYK)sg}Szq1!NGM$;TTl4#4P6A;LM)Ul3acfQfD zaW`nz9vDjBFE!%Hl#?uSK9r5%W-jHc(R(GYHL0na{x_tjd>AxE1-&w%Arczi@uLUJ zgL|KdhdHO{9zxJTb2_!V8JYpajD#rMcAwO5Xl}KimV&vcqj8i%tSIMx>XhhUH(j_Y zXSr%9o$RhX7c$3!`cCKpyq=2F>lr_6bHtoR@Z*mY>hJD1P|L2(Prmw|As^sq6x~v zn2lkESe3V{FC3Kp0$q{lryT4NfBLODI%8kDwc*#j8n7FKxd5s@a*GFLLxA|=(%fKu z{i?InhZtQR8Fju;2w{MRAr^!1s-^=#U+J!Ig_Que@gLrLe|cCOUWlK98n=ePcm^Rt z!Pe)mmt--qQrAsnolIcln(J&ykE~Wal00`fX};t1<@NE3_L z6w=fS7VMuWK9?OQqw!7E35VG&Wpl;sH@$O-w<3lcTF?JKMl>U5`x2(;je*gktXypK zLNue0lO)MCJ;nHfDiP7ApVF?IPc`&>g6iG7H+46S5C&YENG#7PP&xO~(GXxed|@z= zc*RWY>ucM#KYGy>p_vLrW7!CDPA({8)W37JR@Wn~z$zMi#-h^tJEUKs3`^q(Ju2}V zw@po$cBAMB=S|u6qj~+*KyQL`I^Qr1$!J8%7b+v3Y;B<;=eN`1%i~Lw?4Bcv1#SP| z^3wK+g&c_F4--Q|0wn1m`_d^NkD_oeNk(e5QgsM^19cBuo#cCk8roq5xBm8o@8%=q zNf+FMJ|TA(e91BlIzvJj(k>+EUENQgii7g^dq07M=f%yKNxsZ>5*6BO$v+98a(xJd_{WK-74D6&fMO#czB|=P@ zy`~Oe#Keu?grq$r4Pd^a$B2aMJN9#q;~xHv5>+Yl>Y>(D8EVd$Zq?WaI*12e{08H^ zi@|76WwiJg(cLAt7toZ|g)-5_WnU0UOU6E%`pkxf>1zjHnmeQu%Qt`u!rkkythnk? zd?p-t6i>Ka=A?!DO{%t|@m6jBa!rdkic-rZ)4ocQ6gl_5E}EBa6Sr0uqIhXO=u{?- zPVLmL#i|HgjLB{K^I_n>*|Vn}_GW9VYdd^{K&<<|G9!gCYC{76~FS~6B(=SfmV4rnAR@@E@PhC9ueFCw`{;hyf; zIO)X-Wn|R3<}lauLfN}r9->-HBD}m77&PD94Y=aGUoCJQ+F^-^{a6;b&IA}7n=`mE zaVMw%2PpT2&gczujDNb$~@mc{`op3$$E3$Q{nh!frj0gRlU z$@%63#K&7?SBtJH5~r1idFI%?W9^idC7F1WBaOL$RjfNqKndF zVK1cUejLLLTXPA)X#Eu2x%g49Z@-eTE_~keI|3!tF9>HxIhfvPU72K)>iP=6(~j3( zZ)HPgFJS0dw`|$j*O7@UC1b%(k=q$~K`0zSD{1|E6^uarDY^&!pW`q-cmbnlh1?yD zxyo})ZR7t~5)(N8o}6^m%5d}JoR^bIiq73xXatq4gvOQk=~X|ec^Kxh%AD%rHNgGbP?8uLHom#{z; zVg*dVgC@{}9$JWlFWpN>A4B&Le>FI<;H1l+#EHW|Oz$VC$P~n{K^oS{`O(Ne3B3!x zknSpf#W{Pv=0fpIJ?S+zS;CM9vZkzpFGzY$>OjaiojYY0``^Mq6aoAMws~<>kCFz4Xz!{DYePj0D6> z5x$p~z?p^kL}upy4cG#qzmOl?b5Qusf809gml6^B<{k8L$2*DJm7Gtg`C*M$%qMtB z*|vJE+>p+_dYEGITBxTh`34{F(fINQkoJ#d;&cz3r{e1x4n1Ml(G){ug`DXPS zAi>%n@;Mc5N+%2u@==6GX1s&%{)XyN00vOY;o-SMtZ{b4rZL@bJFvq>I$nZ8U zk=Xacw*vjakEReVe$2iIlE(+)329~2r=hBfmTltOm2vGy9&24t)qBJvw_>IGt6fHW2A<2*Z^TcbYj(8$@mvqduqKJ@Is!1t@~GA2@6>K~}i$tv!I61n?n zg(5HF<3eupH>kKRy@}_w9W~7E*`B=&=^%h}8j4=Qe}xRI@0B7Su2c+E*ozNENUflz zSk+FZowfMtxgImwT$3reKx#> z%8njxP!$J1_9b_kNr(}8KqDl;m0c5~Au9W6pM|HnRHu*c0i2Maw}*dQaQargM{MLP zXJH%1I`$?8#K(P%`>YGfP%J&oqMeL~B*aix8;YHGsr{fH!LOb?H;{9`FkrIoY4q>( zV*Yn}DWTd=5GKEU_gp%N(`XOelz(^h>YXbm&676t2fJljWjJKvAjV}NnJ zf*R7s|1Oo5(MmuiL|bs`BN8K%LQd6esLJ>9Kl#+?>%)G#2%O;lEjl#!=d z&Qu+VB!w;O#U90&retyQ!cHg1QsbUU<htkD+%rl#ymVPj z{Py+Cd#=p5_@+nWN0>wF8*bChUEbx@)(7P{FoE`e2U(VFCyJL4B*?EHh<`zb+{Q3u;KT<*r{!AtcHy|d)! zey}P>1mAUEmUC*>E;P$A7pvyW#?KmOi)I4uA8eC|=;8>U6@X;T#0zav6h1u`s6X%k zJ@K%#6AP#+F%l8Kv&Mbuuk>8J`%(w-MeO{GwYVN?NW+qXW8$>fk* ztfRkPUBBvcf5xuC;YbnWY|-5CB$|LS2#K8_-C=u<2Tn!THj-pyj>=0Gcah|;+^CN) z0?JZqIhur-??Iy@OW7X1(XuPq*lNvZV%4SZ$79a^wKf_r_0ndk0S5VP_$~V!78Q#D zBlbf!_>UgSVIVzmZ$+6a2nms3Y#R8j{TQM4ohhPSlu%?MUk7X9|?$ao$~WR4S#+za&N z+o0J3=VCq#oaB_{iD@hv_)*Tu*WAUqalT`@sokEWZdS)UrG&1?=GB+#19{&#mDL8a z*J+lE+fGG>L{y=KWUfp7AXDs8*Iql< zkyjgqdsV}sOmW(m?fR|11)}m1JV_9l?{HKe7Dl|@DGkbO^_k$@xqh`|?Ea$E$M(sQ z)aacR_U5Aq45VqM2uWk~Cdmw(6@ExhMvY;1;KHaXqW;2zhm^xY+`Lj2TRXIME&c~I z)J@``!l4-UKMb7@m;$4PJsZwT63Et4q|^)a_xV~M9D`D}@IGp(h}?^;0nA%&CoYJ1 z(_7nUOIu2s5+1F)5?2z@{j5Wr>>K^Q?o(>!m!!3;?pYH7?^>ETY90=-P6dzd7+%)( zvzaUKGu+2)S5czR9&oX_#@vt$oP3zSDfc-(TW5}e7YUqZcJBIF=@4@%|t&g?%hgpmD%yaL#XP>?IIXCULHmaTV14etU zz}U3udD$RPvXCU;wYyO_|Mk%SU=q}f2BH}JwT2{BRI=oS0jmpWIvqs00cp`Kh^eQU z!zVG~Ud@yGdiEgc2(Ue`G#qg)ydVcW7=zRwD5?=P?Pv&8 zx&SZ%x?@SVZeN1&>Dr$OxRPU_w^8MOB35>IU z>T(ae`k$opr-|of5oGwgfKWKmmv3O{g;caR#qhRl(HoFL zTVJhv8|*56KMl6tirNF|+#iRQotrakB+qC$_L*xZF(E=xH5`tw%j%ug%&%IRcgu#3 z7IVD)qkv*C2;=szb?z4ny04zWqo2ZC^yVn)Vs;qR;>YOoe31o-+_nyQuOP+yWi^6!>Tt{V~$=4@^QlOL&BAZxlyGDxf1u5%2k%xcAo6jpga=g-|6%@iz}Yg zd=fb}ZQX)#wtrrTE9 zQ>!36wht7}-4Bf%*-b1I5catOH{7=8leAB^uZUi9DNfE0Azuk9O|*&UP4G!A(DOBs zL4nIoL~DO*8Rj6Ve9T9*EgT2;V&g7+(~Y)XhBAO{f$ki*H$eIN=5e6|Mf>jm8gK;O z=~?#xRuC6P1hPc_G&N+-uDcqZ&7!T4QK+a{l0T#{+yOv57odoZQorg7FH`hk!0MaW zeC3h#=Kv%6c95o3=c9R-!r+zhW&TgAt()QRc&gVs(>ZUA3FNUc(X3n;K;G{Fdb2)P zg)SM)MUJ>P=nphkNH>7J#ZGjAg;v)Eq{ z{Zg&VNS@TXFsHz{@gAuDM}PoI1@t?-b3%PNi$+8PN7SJJ?9EfWZda7kiGV4{Zj`O- zD!w8;I)j|yCDr!Iw95OW?mGip5+En7jqOxZ}dHv58_O9}@>~Rqelt!{DS0 z*@QIW<3Xl%8zzY$EF9_+oMx3bLty{f?5uzr=r^ig{mBjr*fstzD#C)i-dHDT65cjA zEupspvvRHExP#D8@60Svri!^!@Ke506TlAuMLqX#Tf`{RO5Dc6#ISms(bhUrO%QqWd@Pm7f%W_D5=@oD6uW!gW2{>uzD8Y1nRttFb<=&e;vo zAZ(y+0UU2`k`^!GauUM`1hlYo8X%{k_VKU@~YW-yQ+uYFplF&u*Kwdvkg`ICI`Ns?7a% zoq**TS^lvX{yxa(+h0E=;g~2b4u(qqg9xSA#}G^BT0{8xDkk1a;LA7{Cz`*>{;7io z0 zyz68{cgF20*U4dMHh0fGyV+24E(W!JY8k_FehJ+oY}IU$uaRfuIPE(_zIMeF3UnBB z=~K*M)~DJ|Tn)G=7&dVf;1Aou%a6c2$LO21oy|38-N8B}^FyJRk z)Gm>@J^f{l=p_Tge*oE!hY-{Hr*;2hwK_8&TtGR_t>wW69E3N($nL-1#G0zlRpg9+ zLeRo{7B1xjsDN$>ydYueRiINkAP$1`w#v1~%KjCqqJ&&Vx5q)}VKT8tj~lL7tv-7D zY)rzXF%iV*~8V}B^+0kI{i%qC=;uldKT%L zH}OyKV>dxDbRqmnM2ryV4TQ66J3Vggh?^zylN^WYH|!D*%GoR9!5KFpn*KSPMXk^! zG@OP*eEnr06_}Hn8@OlPb_HY_Nx=?9>7P=N`~uf5I99z9`JY4c{lO&A;@4tRvu6At z71)i`9_YF^JrNDOo5k}JlBIRz2edCg`-R}>M}*W1NJHcpi>)|ssPn=17uzoFK>d3S zs6&h=K=s?%+a*)~-JGKNwJRXmA!|`@jPT-KuZp?;X#>2!!m&29KP~bDyfTMldzzlW zT(vmf$Mw6k+sucw%yZqOG=~90M8uTNFWyZAgtab5#Q2No|ALju5gvjvUQ?6Zr5+ht z<7E(}<4dT8w;ew`JYo#4|E(keU|W}?sDj;(KMWZ4hM=t#TW;rAr}KQN`)6TC86>71 zUWli1>mO@{YLxYW+#s_D+s~o9_xgoNW82?(umCxU*&tGXIgI4zhdz6zbT*UrKu(a* zD~cD~sA)R7SPEE?kf&eWXly^+xc_N`9uM^a9(mpko8`?1f|H{dsYwi`_ww!-D^HB4 zSLv1rI#1>fw^!_;N3vV;4JKRV6HdVNKl!)LfttpFdvx1n;?47^uF~$v9G*x!j&n4v zHDYH(NB3;F7w9gjxIo;UhV{Pa|Ip;Y>pWVhs=Pe=z;=tzp?L@%{kMrpiF@Y^`H?x% z%C3?1IS_J3A(^3E0t1b^SoXFOhNdk?mDG0!qlDoA7Vk1dBU#2B(!fUzWyMDThYWX- zHf5H6m5P`B=5L@ca}Dk(0t24b!|n4f&?UE|540j`2JE+5xE!z8v>k{?FtiPm1vClLbDN->3CLSGT0jN= zz}9sEl+uNt_+`{~iRjHH+36x=)}#Ju&8Hc$cUKZ#2GiHcfZ?Ov5T(`+ z)yM1kyG;|PuL)Lz0s2`OW-1`D)^|#$_V0)sj?NJe>ya&efa|-L0TGIEyPAXDRE)2f z`wia}Bxd`j&w|a{fmg4=EI=(oikWrnc$fH*7u&OG)^FfzB2M+MKKs)q3p6x>D+qTy zZ;lDHqKfxU22?N{&iV>N84y6{7@(VYUn7aNghgj4g829SO-AtkP2rOaT?DQ-Lczcx z2^b-j$pJ%P(|irDclbc*tU`V3JB+q8lKZp@}fuMmkUvCH|&Mw)~wLlla*I`1Fsx_xGl4j$!x0;HgcGnKr zLrj0UP%|Ta23ho)0pZ20uCaF?J^FN3Ok}&venxi&wJ(YTX5n9&+2KK~KpQK@E0teS zmX|2`BS=3)3=ca#c(`s#9t^O5Bt_sz!p)k!Ck$Lv-su~rzY%IlTGP@NubN_4 zV^uSgx}DNK>$Wcz2k!mDcS600hAQ9)U&mR9O@73fQ$us%-Qh1vd|fD!A5yOs^!gcK z&WCHLEA{Uhe9h>wQR;ESP&9xTx@!!t@K`Mbh&HS^w1CQ`_1xY^-?}|;E$`#Qs2MrOUtYVR+rthZKsg6g# z5tN6&sA>}RCtf(kv?kCAl3_-?0|M{*UhG@+P9GQ*p7_+-zEF30B;hkdRUWZ6AWc4Y ztNkjemhW3g(vAd5Dht9RTJPeip7t4mLIpUL$A_ptZQgN7t2cRfk0(E$Gd~@;A3u9p zEc#E|M$2Qk#C1CaqiO_4p=Xyo^(bGn92X-|0S==TvK&MHCKQEn?BD`itcsP+o4o6Oo z%{3!RxISO&!V+ln>nsn8dH@!1;Gz>%X%e?SEBPT3 z?}8oAG5~)in7h@Sp*+>1#jnsZH~V zRLW~PQVLd*z8rjbkeq@^KcbK^W&iitMxqC z-gy&>Z}6#N&CP9P_ntKbd9d#SZ7NCr&#|i|oQm(p?~d0NS3RQI{pl(GgAb}7a1V%1ghl(J*9pxQvf|LN3dOM$RIO50`@^kL-*4T)$=2iZq}C(Fy&p zpyF`bQDb~tRQjH~Y$ql7(KG=(7P~&BnM6;!uQ(m0gkV6E|DD=NuBTX5X3Zs>u+F_oWr<~{NX6~n>Ep0N0K>YLs+w^}~i>{M1WWe(?zJN3fy;xE# z-s@?qMAsPFdAk0Cqo%bVA|sAJZ8bB5Vj!I&SmNcuW_QEzv2kaUN8HT7UlJ`VW0b-$ z(9UN_b0Xj&5?lGIc@1B`N`&{G#`}s&-_;f2c<*X|G@KPLgNfS7WEk4w2zvD@a%K6W zsrrnk_Uot91@$eiwH$l)VP~zlt^2#htd0VGf6+P$}d<_3&Ezt^qxm|Q}?S&A?M9^*jh`s&s2QQ2tOp-7yKUA+G*6gUJZej z*1(jmcZ)~M&(_Urm9J_F!re*2E_3(SwhF=Sjx?{ywL!Y%vGp&q_3`)*Dp1;Q~$Eals?K$pP z4_e7yqSJk5y%>U{%PYLG3WbL#d0w3Q{T@+#vMc<|(B(`uzMv|74|FgU>i75S3Prwi z1>tF$8$Nr6^=%BVy$t5=S$v*~xUa1De05?6eD=J62kg&O)I|zH4|nf_bu#+CiKwHV z_qClCF7q|TTec7jsC1E9d8*Uo@*Ka=Gt6hdiFo1p4XjS*va=*U#D9Wt$;a*CDF^lJ zwHE+8R9 z2*IWukj<-(yP3{pncn>h`DT&O8RqlttpqBY%&QT6lCz@>-0L5n)o-QN3Ioa!$o{rS zaTj4ToB_kwbXs5VnIY5BCg;lwg>=6$WSX5c#o_Ln`t#eVm=`nHvhKpDb4as=z~HaP zAESbIE&8KCe?>xgF$PrtYte9+(a52;fia_#^br?ofNxg2=nPk+d*AHk_I7cewx?HB z43c)!p`JBVXD)MfBMkp$x=!3~ea+mw%4lEgZu%x^U3e3=6^ztDBf&ZTPEe83$&k;+ zYJARD>lFBF@|K6|mhf_F&2oO^59u4Xedmo7RNvhNaT|lX)>jh>rg`0Cbe-NiK)%j} zSNRPk|7Ch6i++!HC2qNk5uD(4{`5-Eyai zU=_{ZoDu2JRLGiA-fHoxx?7TW{pRq^;^~%8W6hfaLC&OAsw$x}XXS3Ist_o?g81i| z5nROl1P#Wvq&+KPx`ds&g&x6m4e`ENr*?`)`noz?*ZGP5o!6}JwqHagceC@9#1dIj zDD4O^-`t=_`g+e!5I%weO~2ti;B&l|Q9|=^7LWE{)?w!lckXexfYq8X^_||;9bm`k zA?9_CJj{{IFYW&D_5IF^XbcIHy;1fsW3WMRJMjtXesyn4tq~cRQ(N6Qys#WPsWWX6 z{~cD{El36S^uu~s;Kc<3&b%JQ!J$0F*l5TFgolVY{=1OxRbCdb(v3Szg#m`ltOam2S;Y+==XiVo{PR0aSZfx;A(G=_FfTTr<0kghp2+{6{kkKKC?&{2~_x z=EsQk9PDBy0301zyF&2$4m#!CEV1!eKBu$^#h=>r9htI9|z~*6RPf4RRw`>O1 zl-KSF=uxQ+51zH=nXdGbYuNNO(pAn9Z0o+ps60ZoSSI8js?`ZHY?^7OZ+Y41h;^*X z6YuUf+n(Xtl-goODsG3h#8Ts$R%a)0Hhs9Yxoa(yBbd_E2Z&7gTC57I!wLpHqzT1_ zdq2bcIXQ4+@94kk;3%W`>s{Fe#yA^H^HkjPEWBmAV1^kC3+lmQD{M!C8jLByZh8@& zZQ~B9yP#&MJHFH(nLsYsZ$!H?c0pD7HGx%82k~6MfxPb7^~7D&uk%@Vsk)N+K^|!7 z+EN3B$3rCi_i!zYC#CDg2X?vn3>Pt-%exI3re4oG?z;10?x5;wDIj*XDe&@Zm*>K< zAHu9fsfYko2><&o`c*@A9{!0BqXhiDm{UP`?Pg*#Vr}|JZQ?ofct0^<5ss_CaD{ie zcqgm4o{dHsU_U*qIKP(92xUE)nh+@>Uq1`yyS|LMVze0=Xsns#D*gnG5d_`ClhQ`l z#J7wPfp;h?A^Y993VOU9VXuA)i5M(|1(!|y8r)qe#P(*nXN^fuXkojP;R4~rCmJ2r zNPE_#2wA%eWJm=Mx@%B~@3=pu(2>(?gF-%Ec(bvmB)!MK$^(GFo5^<|jYo*h(A}z0 z)pJT2k|w|Cti`Q+HZiO;YA0=i+z!fmeXXsqIG6bxdiA6?+l!;So~5{GHHXu0W0$3v z?!yd3OtU^sg~To&ND)7qwjA}^kiV?&b!anY<1e?ou3CluESyK7S?X8U_wO(daUZR# zz@m?GaujS2Tu%x0#lsM!!dqN^d%c$>p)tCJ>xe&-F`~fNS50+iuP02!^~0G%AZ|}0 zoh{@l7b&8e%nYIK?!EVGnPL{4K>BTDspD;|Gq<4y1$9>a;$?$-@<-^~o zXs$BSCV?y&M@p&1P%>4E9#kNfy9~k8_^bl-EF(R~a;_Wq zerOr@{X}kGKWcwFuF>4THh|0OHUGwEL{qXU8vp*y%47W>@6I-q@*uI4htq}AJ#sr= zYoueyf`#vqmPtXk<5j9rsCz%&t}vY{L=nS4-{cr$?%9jX8ZYxMED)#9;Qj2UAj2JY zN&VKkqTbUEoYM4AM9ufdaHPC2P;YvS$2Sj~7dJPC!yJQWK3)$`jdYpBe3r|PiMg&! zXIrM7*z;|5acFcfsz}?d86F?;5cN>S(-TM4mZCezz0}ckK8)W4IfZ zQ~U?L@2menV}o8+wrJ`$6eNx}eOo=J^g?Gg!}i>nW0j^dZlSdna=fAi;q%$qx4&Bi zUBw*^uq>TLyKj&b;+FtJp|p2n`EcVV>JHd|fs4NcIxR51ybxGQ_XH*(|C>^sr1_?}mf#RElyfm4BG#fqU+E_7 zfNa=)jT<0KUdRmkRj}b?o6Effz=WO`vOvs1yRAKE1y~&jHlFO%-V_16yziD@aHpR0 zuFGqPPuzlK3OXwN^NV^1i+QF`4%~}1TIhcxGH-udb;|3ebC;=$MO4lUa~Qn>QLf^( zH&~tsQcjPg&9{~hw0@?`v%&E3AuP$X^0855!)Xw5zzhoH7}ZuNMJ$H8^;dzz9#>z_ zi}bJZPVmpd)kjS{)Qp9?yc!rMD)Q^~te|ZbTo<+I+!*n8Uo?jsfv1EDc(C@T0xhRn zXLtB?3%J(?6jy3hjw*~$czw(QR8t~l%M!;ny9X9K_m#**L;t&xfRD5Oi`m~0iIkmd z7eP3O#%bUMdFRSMGo(5@!oRVN^Po!2U4&J9{-=EF%io-D24*HM8+4U1R5J8CD>I#J zvb7nkayJNeN}i)p$SX*B4|rB&C}YHBECm@-Rn;S^O>Gve5iw)daDgzp8&=P)AIrQ- zwSHdCYICi~(@OZ1=xc?7=auKl@e62A&;vwhVWQ<2Oz`LV;z(lj5YpIo%Nub&Gxg0- z9aUe^>>DrRdY)4G;qf)km1w&do_lOEgb>Da5dQ>{2GYO5eN&@!wz|ZM5~daMSr|Ji zTso`I0%Ik3bW$~HfZSM;k;;d{EK>z{k+W=>bl$ayo&tm}So@)Nb9CO1PfT2jCbgRp zMcer%{vW4_f5^(NJae2NflvhO^M#O#KY3(dRl&d@8X|L~`NDgT+ITFfYaVu|N+s1A z`=$k0W1CWxl8-DWc8yyFJoZa=6V6{hP0wnmqFy%#DjyUxr&IWM(Y@iHMrvv7?bD^< z;ICVTRJ~u@nXx$DjRe-3iU>sVctT-415RK}0UuKZlHMWiqhAed z<|iClre_-6Ez+qn(u$5cg4HP0VqPvi-F@P>>LN@wQ;cTpy;W@`_q-3jPO&hPTIYw) zc%^8fcm;0UC~$U~F*7L$ZDS3#9dPeVaqqx~V7Sw{g(be=!#5K%b&~X7Ie)-}-BKx@ zCq0dY*}rX$(w22K(UJFCUylC^qSC2!xqA^5Uc~>tlZ2qd1$55Xz*DM(G9a1#({mj5 zEwZs(L<5)$psq%N{fd!y3qnCp`x7MlfVz>PjI*tjRyd&#)*ryh zqPBfpt|uf+&F4YBXVYsxkV@-KO~NWl7~hvqcHy;y`rHRse3~zWel*B8@{VPP{=$}IDh-M35NmIE$O3k*S>Sw?;+{-vlsG} z+&Go2Kzg6Y=@rLM%BwJacA!UCFZpnUdN*D1qRfS_;DplHsi0~%m-O1ln9?8KKF<=F zb2|1}sYXmJ*O$asTcBeVgn^e4E1}G|q(8vIGs3v6c&%>raW!t!^tiG%%s;(=nd`(| zN{jT)sHK)#am_kK}Zh=G^;?XLj>4JhGWo{k+8!HJ()?p&7eP$NHa#xQ7us+h)9f*b%)O7^y7*HLff z?40u$RRvSz;%I^L8rnjE(oy(ar87R=5T<0X#-qw}M6-~TD4=Bcz!9{1qjgYPWOz^b z0qG@6|H|Z%XY}z@=lyD0Ui!*SqG6xYf)#jnU=OGF!I(f~ph)U9q65gmYq#t36Qwd< z{WAoGDH%-gOqfh93Rk;5I_c@j=V7*GH7l$8tXpbO)}8p7apG%ST|M3P^}Q7T3L^OM z8yDy8!k#@iD*)`1SwL)m>olHhh`qu!=}NhAQ)qs*w$Ce~b9^5pHUthyi!nl&NvM{S z-hS<)j>}0w##|F4L`8Qv*Hk;L*2z3qLF5O+tDSY7x6FN7Rg~h{zZ+h|YEn>>ub*6Z z%*3+ut|D|e363LUW0U#(nDvY_b|Iz-ZG73D-Y04YK?xj#zvWx))Sg-IXB4|+H)EJCEAd);RUsnc+Uomywn}ST7AMjO*+ce@;WOh1Wi%m%UmL<&km}7LwV8^uQz$ zMrbhYkCI(%uZ`XsbR;6EJDQ8T;Tl%k*BMoysXwEQs}IF46D0G1rj zX&`;MT)pA~z)!lw4U`Qk9A0ir#kDEVsr9uq<51e0W;$YtxB8gLu|aKIu6)kyF50a| z7PRU(mQslf-dEg@uz5ZAU%DZDSTCz`+UZ)LcX#F1c){^)9XP$HNGjd<$1C7o($G1s zbu0q(`(%I`;sP-0^uf#ZEBhfv^TRNlSj{)yeZubr&lxsKO)4g5KI6AMr0pJCeBkyw zrCRu70-=SnGbT{S65lUByqb%h7e6mOZSq+3eqwBtKdYALY43^Q_;b6ct2I0H<^$`` zj^brwo3sMCL6=5;mG$T^Brbncs!f#>yqNi)^@?JYXHe~s(6AIUOSyV}&wAHd4h^9|_nYI?P zz{`?cS4JsOtQg`K*T2(?gVIC=e#q4G&dzbOG5d%n1Dm3`ZMe&oU?~dZuMf5HFM+#3kjzmkNI@{@ZFMC zK<E$7SHq9z4VniXBw6y86c7om((X}6S{~uF9z*rkrX1tiQ2Q{y!qq|tnARP|#r#+ww zCOwtLpzDbPg%LU$0P)Zx#KzuLAn=?E2d#pl{xjTpSyP8n>d z@Mi^hT6q7}`=UX>v}3r;N?UB)7G~A^UdEzP0?%gQYint`lOf_$E~D(6D1Cy3X%ULU zc{6^Ld!NISF4@{6=)>i&_!D!lPsnR)U+|}l0%g-5b_XO`I zIU(-5O3Y1`bW#1HGm2lduLl&`5YD`W|HX*=n!?uZLZ=tmfAty7*}4fSi^+TPt)ih~ zSl_9|Fd6k(mXTL%$KmVe3q09ly6LNtW4-7JQr%1)vjwaAOZ4hpM|`lo28T`eP?b&G zg6g~9CQBnuaGu?Q`0^SHW0oj>>gzf$jWD({(ORm^^gLO)u+SJe@n7`h>=!jF$9(H) zJNsCIJDO+oSB=>@iPe|NPxc?u7Izy0IDIZdCO8lD+h@P{02p(D-@MDz#rQMOV<8LX z^CT{Cu~tsG=MCcf%m2R#TF3q%_v_`n2M68w%j<_g<-$*s0CC|s2D_=6I0MQh%0HHpn{`B<&Z1Jl2k>B3P@0}162qBDg7W&CRBOvCnZlnR%+<9_6hq3Gj z-W2_F>1hmbLJbuHLGv=l4?GFKHhBp_v8^bEAJ${!Bu9Ll$gg4!-|j1><0oO(oMuk< zlH%dtjw^Y;I??j@JRtvZ9SMlY$`s^(3p4)til)wSjDX>Bx@#nZrgejRY}mr81wa<6#ll8u;6sU+DpXdw-&hcr|Wc{shKoU zhQ#C9fwm=t&AV0TX6x3XwlhbfPfggh+wF&bm&rH~Y$@yPdU7Eh*W@|%zLRjhl?Fwb zSU$TWhppMu!jD#ZxvT-c>8pv_$e95@XNT!UfO?YU%D?eEKEUpml2&bu{9x_F>D`CM zO#oAelxzq_rWcHHFh8%GL&3ZEo2{lEz#CGrdCkiboJ#NWd#5zev;3PjE3(^d;`5Kb zP+I6+2Q+JJ>gx57Pzqfi`Mj{eQz-+KIvNb?dm*+HVpv`|2J!6Ke5tP6YZblGV)&9p z977jX0C07nadftq*p@idu_yi?JMuB4f(}q6u=9Z`k>SZ!WH|4ercaV{pRApOg+Mxn zKTsS#Be#!1G9^}i^D&P9&kNunO`-2>gBWXVz#*HaO&5Cj}O3wpZP)AD>YpZbB~y&)}V(UdZG1J(EDi_-Mb#TC1a(O-tKzx;pD=_h+$ zQgW}m{j*g&`%IOPPD8FM{|ZZL8|^2p-?C|3BxI3HNF^a>wCpriMXNQ=hBw>K*c$D& zyM1JyZ0f9g#YxLesg|<>OrhGa{BKvg+z4ZRGFF^YcDRe|M+7dXEA+Simc67me{jyL zGqKalRWAsi2Tp6=@Y{%=xu)nco`umb2lAxs-iE&-vNX_f94!&C`9?7(oa{^PvFz9* zTN|q-NQoC(3o){|W4rw7P4=*3GJS}HFeCt&9n3Sl2R*Cis1Hp71;*7xx5WH;N}rq# z6AzY<^_Q^}#Da@N!^Dr?2Hfj$t=aYOKf7LTOoOdnV6?b}`ziRc$6fn!a{KJEt}48J zA$@h~O>FWmHK}{_axVJS2%~I{s_`QS=_jQV9q|F$A|{SVJ0}z>Jkb&Sp0s-MmsTE^ z2ri}n`ni{m&ah@I6w;@=DvH@SE)5dYLt5F{b_fu81~$DM)~w-l2>3B3MQZCX);{fG zoiNfu!)`eJO_x?55)tQY)Vjg2?Q-iaMFC!3Q!$sAqL*CyDX<5x)D^0c%ff3Usq8dd zJ67QZMtT9a?))k{aa<~Pz5((sK%CF%d<;)L1TE%1l@%wN%%gBucbLJ5x^WpZbGCl4 z@d&d~SO;LCw4c&{wR!rGW>ZwL-fhP?WuMy<`0tMR2$di|b#(VqR+14PEHf}#A_9*% zr;Wv2mU&xCSZHS2Q@7~nXNo2J(3~GIuPG7m4nPCsvtG|~Q9QYotBrk;$JhuwI&H?;B=1(a z_&)*sLvLBFJsju1>HCS7F=RtyEL1)@QI_c=?&?n|JT7#8EqkA1S-F!9(UBXbim zaSxsu!B)M<;TcmWn7+{Bm0yV^6ydIVNh*iR|ACK97HC0fW9hQ}0Z{M$4<=Y$A|?}6 zmOpld{=%kQ>a#GGREjcJfO+~p9~ub6+kmh-eym6Jl*o!t0U9E9yEK5rh?Wj zyTvmMNS_{O14sv@=divjl9Q2)QOZx5z{$3L6vpCKhWF>bjlXB6=Mr|zO;zoA(46%I z9y!|qaEty#ZlG8JK)#!;t&1#RD&MFj6rR&i4L{Js;K||=D;xA6^W^NFT6$ry8Y&v? zZ}e(&Y8oyQcbueBU{;vC^;oOj@Sz1fuAMYn(YeRX0<(gr-=39%w_WURs#1a3MFo8! zD;~NI3Lr!*q;!a=cTUSBl)c3RfJaJ>wY^h|WUa9~ChL=B?PbaPIp=5ISVy7GiMbjh z$Lj5#4^R3PV?Wlv?dD)4?J6-hfRda!*C(#ji+3>BrDm@urswRZ1?u+|NZFD09}#(Q zME>)~kt3_E9{@0t|L$fuKYPcLA-AvIzC z_*+*UGgra2vrk#h`c5kAR5Yfo(ldvEibBEdZAMo5fzkQ4#Y%a0lHE`eH4R~k&FUA) zQYFaaBpd+tXr4D;0fjonl$s_*_B`dd_Us1*DmQ?426nfH`;lyy@f1>hR=85IQ~Gwv zJVhl4<_C~I)RfSe->3o*-?sVbhV{ZV`70?Gx3a=Jqja{5xhr=u9-+q~!NCuK9O5r? z@W=?pPz99ANHQVnGZ&OA3RB;~yjJeyR?_c=V`%Qw-lZIJl$&)bRI`WqH*FR;&J_0i zyEH-s|67{I{jQ#Sd#|M>Q|pN;c{==#Y{ z;_u~9r6)6y z0Fue-{C-_Na$-RzA^y#uKu1W&SwR5A*v4iM{*LSEt#ZHyTj~ujkWO@{(n(QU@shvd zGT-AyDhp6!;sizKYQVj`NFRxKd{UbYxJrslW3JTX_5F}`TbSqm73{d&f9)(8GSS-U zVIF?FLjobT$+vtnV==}M2&JBgb!5D`xO3H0dwqL`19y$No6)Vr{np|}n)3ZWCHSYw z*4I&MvyPt~G;7yq|MboPJNL}$RcXwzUzw=uWDcNAvcxGHK9oKAu)a>rRzhQxc$i&n zWxt~LE?9^X4=&iq(=$Bb0Xs9bSu{R5UWWMXdoh=+>IZQ8in2qvTh+xeV+$q zDt|`2)RXS~VE|H0MW$K8w9cROvjr&SW@>Z<-Xd0**tFl*8xSnvt8It?XJF05N;k$q z`ivQSI+N2>MQz47d)%OY>M)?mCUER>IjSYrZBnc^40xGki)V>gbF9$ox5W=-r;tFX zm|gQ-%?J*izc}tP*;|l_rY*G>9u%HTi}CB%O&ncP{EeUY{;8N-y?L|xq2b}PgKt5C zRq+Bz?nkg7uX%H-4(Cv$V4*n z9?$WwcAh1(jd9LdS-nS2L17croe+y{-i1BvUS56XPq$}^aViQ9&d}L1AY;~4zIrAU z3`pl=?oU7HY5lWAI%U|`y0?P^;`D?1TmzPD`Oy@=N{{Lr*MJ|*Y8*7WAX$XnP6-+j~0bYCGL2E?K&^Ox7r&JYWIbW?0&G zl=uyDxbVg9W;bJ8G|uA+{z2JW;zCg4n%^c1e<7LL>)Ymn@@-KB z;+wLto}+DT6DN!g9$}LDVv2l16+SuA8m6Vt*2RinVu88eS_n)6fz`k%b%W<^oql5S zB3H+S{9plH+!srmL~^cHsys>s-zL_Q5A$1ao0PeqEFBHp?WsQ7T&KE1?dg1pYv}fy z{EXVz7zQCcn~nK(6{C{@e7bA%K-=e()4MvKw^9 zEA&du%$j=_JI9z=!xVNno!1A>;O8yDL^_HFW-uyV+((8WV){S z4}Nl)@dpdU$86Kl;cCVF>55&52~I>{ap#C*dL70(EvFeD8bDF5uo#PK4)C#;E8Iu; zKH!Pp*J!#6Zt4emi#>a~?=&vNnIwd82SfbozWMvNe5Nv;3f*RLvH8*7z=ujqJ;(1) z-d5V$J2~4q#4xgx1Of8Mn;82S82wSwtYHz`V3e@oPzBldY(Ozz)!n%|0q}hm07=wa zWb=Am-g=$z_2qg==s z57#xnCRlX3kxAjOthDtTzVE|{<3@}z0DyPKUT5yd+R8O$Xf-NyGXVfK?tXSrePs!& zH;Tduo60z~q!BwLK#_e8<J036o+#W}|!d<0o9Q`7xveTp$lU4wp3cf);n+}%B1 z{&nPy^)OH_VEBLkC&8G{y&+q4uQ}&ZXE{hrUuFIbH_?&s7yApD) zRqb;KBol=vuj@?=tO13IPKaEkEBPm;pR-T)w34Ugx0{*b|D=CjBVa|-u|Vm&yg*I8 z1vsz3N1i)AMJGWAir*UM=Y6f;f$EoE3gfo=f-dcz915pzbtZPLE(&}p6+VK z2QKU~&`yV@UoAmGYoJ~DoT%dYOK-^BiZ5zpa^coIlx3+naTj&&%j3AP9>jAB=iKdF zr88uGXT9JrQ3f0O$YFHB0Ta6`z(uAx)_%fqel-~}-m%RI2LjwQCm2_QHIPjh4}%$! zl#v~ZK^|vH4;;Dm^m2s?`r=+rkZg@%n-{+67fdE+!jA_%Xvh#~?)u#7msZaBU`&#( zXP;IsvqVZI)3-M)=R>hOLiPHEway4jC|Z;O%O`@6KXdzNw9YWlZ`Cmy%R)Kl^CZc2=nebGq1 z(S`+;Q|aF|5(-+@+OeE)JYvJTdzX=;iSaD&YdQk3c^6=baM-Ni_o+1D!4^oxMmnA) z4MAG59W0??%F=KLdGt*CW?V!5Oiv@B*Fk>&6+GYA{-=U*7yj-v_Kf9-;g5xT{U>{m!ByZTfR6o=j&S zeaE2fx6?PyexA)i#_ag@+2I=3b)7VW%*$e-y*`KgW-Orlkn)0@eK~hqSzvj9;-CAw z5>q9IZ9o*ctcsaH1q(gE6(6rRI^G&Xt9|v8Iy&3eV@7cQ4n3eFKsQ@9O5X$LJxbDs zroT}tSZR4(Cx4U-XuV+);LF+&v}G<8n5RV9ZbJdY{3a=%Yqz;isW(J8ZKA*T$>I~q zA>QivCTm|xeQGUu>__wvgT@?I7TdG!`<3nqYriT?TcV2W4ZoCAbcA|a^8m8YRV+)s z454cjQN&9g4DOpB)hG@ngMa)-SXPS=!~Dd^Z~)#5)p(!nG~zefM_mY22~Xd`9*tw; z+vaO0THgMd1jj%8b1pj{X>p5P!pF-no;^#v{GSmP97mnP_rZy+ zRLa4z%%Lu68Yzjf4TUa4N}Kb>^QSl6Dup_ij0ML&^QVg~8RDm3?<9NGpfZe(Ae}>? z_76L8_^E4maUbeSwy<&<=nk5xU#6c@wex7m`}ZS%XK#2`bhdQLSgG7 z+pzZMx;GmO$Bur!_hoxmV^8G{sZbI$k-$PXy){c9JvqF1NLIKiaJ6#@dJO zDqbFfa02hNj`jHB&D*qxTWC1BdEMkR`PQisS?Zj}G@?uWSGG0$%e$eUk>q?m0AjJs z*EMz%=yXOgccEXVViXqu7RR#U|AS~;3uA?Q>8xKlrmpat7elpgE^D~5F68q>Hs-x> zF(I25#-%Mkzg$}}EjtuGzxO2`$uQL8`dv=6>@{tEJe zUg=L~sy6qQflNM90y(}uLEB{zQSPg@C=9ES4N>TeE@OeQuj!)dFzExS(B6;N#%U`J zfv=3>uCD4Hp@`G7B!@xvkPKd;>gW=-Q2ZSs1elc+UAI1h zfJ%Aq`4NZ`?%hsIZ5`NG?N#@?kN~T=-ekwoZpB)>jpoS8$o`#e*8xho^JPgG)nHEk zZTtF3Vf-A@7dmHH@p?hI;K@RDfR(nsR?B;yjO}LnpjNSwO$HvJ*zQ@fc{ApTHl+_E z2TPv?Q$8EgsrCV6N1iw^O5%7s($Q%y{vWugC0f&93?PLA`nEuuP@LSz(KD(rBDTBP z`D>2#7yP@w@Wn+v^H#IR${RB9?8xT=ReKtew;n?TEA+p!ndz|RDabA{sk^1XwX*V? zSMIRG^=;N0^=H1ojcnJhP9zy8IQPejfaPi9dez}RGv}A0G=mGlzADJ$@VtGCq*?%6 zeAzMG6UeF36L`#Q+R@6+wMqMO!AzyJhK!0QsmW@j;HNSBAH1OSX&Wb>3zU+J?Nn++ zTDgF_nm#1+X#0=rLDAW*X{(RjmCnHXCm^yhp|Fm_Y6l@IA~U8(67yUd&3~V&i@7>o zyrW6e>vPWjf4aNnQ0FAltlB7GAyX_S1qLjKec>P2_(L5NGG!A3)MpqjG_O#i*)8B*O^5 z@0?3)ug{EN*k6oo^H>y!r-fPfo>pB6`enXUj*jWrbQu-qiC_(@$&r6g3AjG~K;DGM zj%I|T79h3ZTYn+4ezkbJdatCzSHhlo_Fn4U$9TYOVD8?23K@os<>F>|AXI5CZ|;2> z`wgT*^`C$IIv7JgKf%G=GY)=4{2lNAlY?@{BgsFkj~q;WhGvf@1OyvJ;Ju9WUgGT}k_Xi6*D~oW zuW>M7)}#rO_s5Qot6-C3SvPK76}$TIOcTLs@2;>4eGoglSZyjYQjShjHt!?%VzOms zACb4y0y}arixs37ox6EBHBRI{`~h#qGSZKg4h!H$0#5BMsfJ4KUj9I!fWG$e%TRvs z{M*!O=`v)4DNuc~*hwn~n1=rm1+GNch$J8>2tG!PE z&0Y7S<%&P6TSqb)7vkfN%ae>tkJ2SF|4K`-W^YCtO^=N}1%dWynF^Sa$Nu<=)oTN5 zEz;JPo}b;07~p%6IhtNzz*pMla^fmH+Jc@C+CBs)7ZE8AdpD7*@yU*rhwt*ilY*WU zbUEF=Pl}4?&s99k&2_t~b-Y^+{n(NGJ}9h-GFPRT3GC+=vHO?GG~*rb{(j$ANzGm4eqgS9a5=(dRL(;!$BvUsKPRKy8p-2d%#oq{{Q1QiYOE%n@AZMWp5=} zp^RiJviIJUP+7^U%*@PV@57O-jAQSu9LMJ1n8)ur_5OVS|MPf1-a6yH?`u9^uh;YS zyspb-+4|RA=a17@1}=7cW?sGWzT&6Pe)4jj5DmVVU6zPn$~SmABb0#ZU*vH8&~fIj zXvjV!nfGg`l@1P7={YlDfp?OBF|Xchq-&a3Wj78h$4B(|6oSo26KO$U(4&U-}F5g zPM(BwzFZAg`uy3OrD~q!0L?SjaM`0sW($X;Bl@!b4X9WAt<#Ua&j~Ak5SI36%V%;o zxyl`T=D>U6JHqpNV@vVS(Ez=@b08|a4ffSv8in+Q#7|}_K)IB@|Bq-N*l<}SnEUjG z{jC&3=311~Owtz4@dfHv9c=R+^CQ{k$C1BEHAo0+O{VP|i!G*22OBbFQwJ{TQ-+wG zQ4Z`x`}K%YB1W<2nk>Q_1$Ou=O%~OImZXVHK*XnPj8)P#jmTy6GalQfwliWBOP@C- zrTh5FHQg0C6sTx)AUa@iAVJGKC?);cL%b7cG~R%`l6zU>N%wLZ(M1B&V5XpX6jWmH zFBpqyYhU)IjNNqRWpug8#&!#zw7NFjMu-5K(yKW8js>vIKl#XLY&3YQ@ucp<5Be|nYm5v{Gx#D}5Hv2y*0BQN?+5*s5 z(bC7xMK#;AN%fgl(x1~+C-*ymzo4B|*C@>GVa`U+ZC( zahDw>mv@P$Sr!jzZ+EWg2G5g5>4EqmRUih5^>Ytv^sRbqX$Yf9o+%f1<~z^%hm-M^ zvF`C{j=GyDU?|%jj`HKp(3QNi2x3x{r zW`_7?NxNhz9i^K_0<@ic34z96&^3*VR)+HN5f8|12F-?AL`v*B4#uGxP3&##z`C2X zJ5$}IDP=9bX&x9tP9w(vKbQTdEZnf-`7)H{I2A6^U7T)Ye%ThEj(q#!KU+u)7jfmS zZiFMYYKG3iPh=t_nU9Pq3>}buclpE?o3@6f1s0XJo{a|h+mT(WzjmZ9wtGxLa?_GP zug%s;EPc?*%J+`lSIQ(*OCv7{v*&H%H$C3cHm8vO!>p%HVy1oMTb(@sw8ds+snBFA zmA4x*$K`jfu&jcRT{gw=VfBfS`$7EN=R?>3mXo}Dn+*0z_F=ihMs*tD0eK{CHdsE( zZXZKE-InkxePJtn!9s=!%}r75LRFY{{t!+PXxI91OL5C}xPr#%R}))xM_c08WsKX!v9*L95M{Nk5+O>QZX-H;zinQ7 z&G613@xh-Bd6@FAH_0zK8R_dT7fTZ8?~?6IS)YZ}alm9ee^J>cM{$4H0hpFgjF2V}_r@n7^ro8_u!Yz&fAh;`k8AiUnOi_2tkY}3g<0lHXaeuHW_jtMUm0SDiEKFBY82pf;hbq#Ie~@ zjSXvx>ZW+j>e7#%8=57JdBib9U>dY1DBslfG=jI&@^Hjo3fH5NuvEJ^9pYw_pyG@X zO5&DOau@e=WqIs>)lYZ{<@{4_ev4g3$o~(;QqiRU&-Mtf&6U?~JsQnv}gB7r@rt3l=0^#-`W=_Irn%h#_N<`hl*4TDNx-kuG zeYSz@_~LB2p~C;P&ylh7SSE{>rWFwAP(2F;dxncbYkP;=UXjwGKkJ7GYMQ%N2@?It zHqU6P_@dl|!whys%-!D#YncvL&l^q7zr7nRUoF^DU;OSNr6O%A3HwyY=?Jxiiyw-y zO=cgC7SFf!YXE90Y+8R$;}2FRtIc|9({0}o6gTrl(y&lh9%aFWA%Eb4_uN3!MF#B%MGu@@EW%}|7- z+~u*e>H6zqKKoCULX~Ai^P>qmq$3s4!E;vc%&WrP&iCJj-M)#E^H2m#nn+I=7WUpv zM=@dM9;l)GE1TekPN)Qc6Z8LX%whqKdlJxGiTPM?Cxjn|Jg5Q6E3mjh-D#3`A!d2$ zLrBKm*RbH}S>j*Sia9w-Rz8NS+E~|iZxqjnNWUc2&IM15JB{=YLY=fkvRU zS+qZ8)ds7=N;_6)FVt^LQlVAYHrGbeTfVn6ZIbohU{}9>Pzc9;>v8h60jb5XFXSKQ zFG9K?(8dpRrA6}`qLSK>$5GT*V$z4Tn=zR$2Bj9wTBZnU9xw&9MjQ;aQG@e^sX&hS z<<#GbgybDRCiX6nZ+dij0`*+>U~Vlp#~IT>VJMSzxq4U~;ad&-*O4WwnTx$Xhwmui z60RwgwUjP{9TYx2z@=b&dcVEquSn)xUiSk?3!#x*rzlr1{j%1y`^?fF;ac< zDp;zL&B$KIEYgmIu4v7~@rS3tZyL-Z==ARW{b6>O3xXgd3UM)0vors1na#sDivrgP zMd*cqlzXwUZqo4J`U6j^#i!an5rH(>0^yev>Ct2lkmxr7x-B&*Aft$p7yq#(wOr}d zSEd%V9%tVrMd?=+Q7>y~=g(FEa#0(WEIS4;ByzQUb440=2q7p=*r`9tWyU_8ZScpMw1DW4Zv6lU-rER7X2Q4@uEf`kzhxHXc!U*x&cbfcdAQsb3`0P~Yag@fnKn9KV* zm9i*aOtCuV6P4)x=c+yG1ds~%q`C55V)&K7`d!Q-=ru20a42^0w!>bO_3nZ_8PuNr zKqpVybv*A?pxCLhk|P~j<>5_w;S35yh+d~#*WZLf0?OwFSZH6>ZTdKRY3VlCtaU9# znZ)T%7t?Wm&DJ>GohehK>(lUCq*Kl>Z$F~>v(N{3z{3aC(bd0){M=OXRr7!vu@x^v zE0ATi^g!+R=;t*O%O*nmDDr^E0W4yuN(3=Y7}1CJA7i<5`FTzlvV&6_r;*ITnQ)DQ z(``OWxip?N1Adt0T;TM!0M5H(?efWUUBcuOeyjfWMxTciW=o;Iv_uFze&T1a*dcl2 zbpbfqkO^eUAJ|OqB5r)Ls9jhu$ff{`fi0&NwaBBjNK9{tj~*RpF~2r=cE4H9*QQK0 z8Z*D3f$#Usi;B<~>aM?7(KMdo?R4JXjr4V%ptq%t+bj{0xk024PAM5!{3FWWT?Slz zhuH)_UyReEYob~Qy1+1I{LiDh&n<`}d4J-{|JvR(SgwQ?fL#G)70o?gzXXf7? zA#n}zO)ek4b$J0ZS+k3&6ZNQ}ZqcgO;XQhAHap@!O^R(EJA2>~Rk`=IDrAi)_g3sU z#jVE_ZZCWJ2-}~Egk}o`F9^=9p!*gLZH3Hw>&3L{;MA}O^<=4w|xT<6OLA4lpy&pByL1MCK?oE9~gy$OES%bd}Hj0EqUk^i0 z)vkm{X#|hp$UVz-2U`r&Zy?JD{tSMdusQN6AHIj!A`vpd1g4%5!9TjQF6*#^KD!{! z*mpRDNMxGYep1<FZYmjh_($4j+MsJy!64dFWmLFrpAG&?!%|Tal6F5))dAyxjTl zsjUga1{v2hZxDuErMSp=fX33ZOzsuRo3vyJgH>7~)qEjE;p_QZ%Tw>4_#M5Ty)8t_ zXg9GhrqoMudc>xA7LrLM5Hw13cVnwiCk&7-hbuWRq@=w$C^ZZntcw*J^_vB?o;eS1 zRT+v`kgMmu##a83?BP!yrH(qL9u}4{{!*GCDO<8Bp6gj~3AE>!NE#k-Q~nRVXH?7x z=CZ^R)z5>Y6W&{Fyj9Y5GUxLCXmCj(SH8MD!ttC(YxCA5;k0@ae0FT?Q+PV+5X62_ zVG+;Tmadhid>I|T^?y@>?YB4jW9e)x?G(-t4PtA?0Os>?HR^( zaI?Qa*_PIW!OuUs**T;SB^nken=5E|mu`b%`^7gnAF!vP9^_Z74;Z5m1ntAV^7TWM>gunf@o)Or2AyLj!{;H!is?t*==I-zS!Ykq#8TJpSThZccg+P!L1)Lo|^r-eLw zE}(6A;S@)eYjI-C(z&_z7(7~z{ijBXVU4F-gOV9@6DPq?dD@d=wdvPtMl|i&)WG0@ zbK6~I>_w3OiorgxNrekD+8wOF*1|U7R_B>~19@ebK=bZ42)OON8|&=uTzjzwo$UUO z$3t={HS(`+21HL&1Y^H_iDNe%0gI`mLqmv==7%hoTPg*0H_L=%?lT3QH{IGKWb(ZZ zXPVkm)^pk~`1sNJce|P4YhV6Umt&hLWXc73$Je;gG1=;OLh3zr&0o2`8MQDN5zL)F za_cQ+gl0B79d$J|KQ?z{Oil1l2{6pmbWE{b54cc7QeIy86?1mXRNy&=l^TSVkYXdy z57ccM>|OCIjmFg8pTnE+7>R?^0I)7T3g~x*gw*k%9>a+$!`w~5;{#rimpV`CD{c+HOdS%TfvBLxom76*5lRv z#6go5xqZB{kw8^4c5n6?fA3N_Lueo0?LQsY;~d`V_J;Z!L}(a`MP!psdmS%wNFA=L zsJi1O#QhCiHb1{)w4g-c4}&D7_WuB2f{jfx9Ox1au`7%@MN`&Zg?~ear@df@r9u^elR=8iGh{-I_pcx5znH>T-!Jg5P)px|S-nx%T z?JJvo4Xf}ogXsW04vZ%gffHAFNHy@HyXnTQw_%2w&Shl<_%(CH5r4DY&|aDpOGo&OKl#6JLzqGwlU=|@xg z-{|KlGR4$CO7-@GCepc~b~})FvkA^Pq|mb?`|E&th+7>u!Y%xFh^_u_?sZ?3q z!31+rnJodI<+I!8zER7%iZeZ?ooHLKc}PKJYx40@P>qn4@ypF*Hn!tRapGH#U!Tl; z`y%@RZ1e)wR&I5=%P&uJw^WHYfjv$50&x+PD90?f?T213OS02i_%!Vb?3=*a+mrpz zRaHp*+@RuCx%qdjFt)Z|6w#xH;f;$@T(~O8_RPO+*w_cTZeoy#w{y_CDOcDWEY6d~daIpZIur!#%ba+WNSa3r&YC|E^uSv_wNni3Cr;JydOe7&z(B6TSah)$YparBFH{xtwn3G zG&IZd=4rCHpzXTL#POb#%wo%oEes|jfm(x)TKW?pv~s|)*vnoM1d|kq^4zuDexkZs zL-H+g4!*Oqk~30G&V>zOf;o&2d2Hie;6PQAYSPTnE-KZx*!1~IDLB-kaJN$h-S666 zoDxxQTs)aEpB~`4agNDtG3}a0ohwX_ZuUlxq>0f3m_*}9RYi;EQJR(x{m2?ui`&Mx z;H#I8>b);QP!RP^DhT`$srVV|4HV}?>e7KeDMV#a?_nR+G?ePp4V$qul$lS8P7N0 zjHbSWxmly{kM+O0W{aDT%-Z9fBiFLDH!tP@gyNo~A8){Ii`K zB;vQ^w(y<4hgMdOU=qokUOshn_ANhccaJ3d*UW|?C6r92C-kNR@TtBhlX;oi21XkP z60?-DX#E3E-#Sg6fnX*R)QNJi`xJryg)>4Zs6hdu1rM{5*D5%S>hxtWnVb$$0ZnXa zLlGC6W+z&e6)v>TurWfEjv=Ipu420LQP!_1b;OJm!k4l2XBkn+_ASM8K?Df*ytv&X z$E-72a~Tmz2?)Eczx0#?VLWvK3RBJQGKnQtcM9NzoK!h&WNt+hBBpsVj?(m~g=U&_ zYBcptD5W=_DIdLBxRlM*W<>z#& zSbg5S54yc++nyLa9yD;b9?4um&IYW^sw3M5-^AQLN{J^r^zJ^W-p$gq-JZjNt=NX5 zi*h7(H0_gNPDHPR98$#fTaL!uVedH5gqOf=uAX0nN?vUxs)a%bBUP4<&w8s_HeE^P zG(?jH8MNq^riJ|$9ziwvX&755XwnV{8Iy(6J3{4H(_3dtxltsqBIhQr2Ce=dIj}i{j2Et zkwrzy<@_*yiHGqVKg}UXZhkK5Z#{?sc8#V0EjaY-t3_m|+S+UZlnh7bG`g=dEj#=jjpoy$PHov$(Wb zrpivkutFeWb6cEY)-hSTe=tQKLZ~&rJN#@ubt>UERG+WibUgCVXzyUs$8|c20trhf zhql7<=;5g|vpy&9Gi}@!cZo>xlkrVUH3Mkybn^O_OH4s&XY>8^Q{_K`L4!k(Urf(} zm#2ieLd#M(hnX_i(*xAZxnv!(lOPABLG!3m>9ga|h%R3raLNj@rWq`_1) z;P)lZRRXB`ZN`$B=6el!guzU#j2?$@Am2lS359$*-aST(QKPZj_~E@cE2Di@?NZL? zJ=YU~l30gMp6opTGIKjoQNHeXhrjy}4ld+jDyoP9)Bkt=)M?cPP!98czHkbJG&e8v zE+Kd;UXi-CWa^GPUxpeB%4BCC)6C4-y%e8 z4O^daoQ~eaY)k}4f225!5)~#0(h|8beN96dInBBLd=e-AM>>nzA%P;<8jI^9c`YZ` z9$naPtIJX_xap(E;^^prY1nw3GU6%~oBaJa_BQ>{&1osKibjza>3iVFOz7~3UpC%& zJUQo4`PCERi!N)T0B`5Q<@TBFC*7c^L9ibs1aVU35X?+aH&Z3ck*hk%&Sp668<{f|RjUKlw6T;w#M#L>H2tb4a;9=%s4&P_D4TAu^-I)mKX`6(+G3(eEButa+5Y%{gFWw%eZ3T(Z>AS zKwvQX=hOjx2LL1X1nC~(XTnqm53UpxsPdx>THVES<7uJ(sGkCl5I zGz4?cz_HulN3A#PkEUmL;18ns$w-14K1E0}$ga3~t_YZ3hjMf;`91S}=Z5YYnB9nz z@llxA-A|Ns@I>FJ!-O_F7*3?b@!K<-o+>O(Js=MQ+A<1 zG%>G_XZg%*gO+?X-++CLWKprGut)ev*0IOR)T#zko+|}&7OU+p7@09QzSCujuH!G`I%}YTUK% z7zQ3HmmpO66)wcfKOe#c-hLdM`7(+t)qZf)E;+C``{`MCqQ%stgW{Z3$4R{`fhqV& z`t#2oOB~>w0lmbC@kj=@8lh7@uHVk02)LbtRsXO?qnT839Nu>IzRj3H_G|Ln8}sck ztezS==pDewZmx@HkEa$Nt!?`1#(%ffd$?#*k3LbB*QO%P_x08uz9w_xO9H$AXJA_a z1i}3V#xineC#-}*!G;9jgJ{AfBQHt&;lTlu{rDWi$)y(s6o~&|;VFOxMuAI&Nxejn zRhk-fP;kZ-DQ!UJa}beFuF+6yJc@G;p*NsvGgD>9jgUcd&7?;a==M-i7g;Fzoic2e z2kuj?UEOcug|;`?^i3x0Vn z+e9@}JrO|az>NY(;2(Ihy_h8U+}aC$6b3VECw1V!(ML;_nE%YbAmHG@V8mB0?yYwk zITXZxBaINz^z`qRtJSu`yk5J67@{KQFJ-<2^L@MT1^{_jHzD$KQ3z>(1YDK(gKqw5%zgX3ktE z3Fa>U?LlZAkDoFzf5ad};%DL@`KOL69qD<(-*`~tVSyYX6~qvtR8Ed8G+X<}q&HR3 zjPdOIoT7milSF#aT37fl;|)X5Md^qbP3U9w!gkG!Kh}uXq|uP)Sz+JKpRUS)Q=j4C z;k@Ev^}W44vXBSdJUm+1jp<>Si7YwYy@#2K(Ian3sfDZuZYpHrWaE&+?(XhB3-535 zb_*hxYf-6#QB0EeQcaAEiZY{R^apd)1|#SMhl&hD)40z=o6{wx@g8gUD9=0}@|X)1P5bNjcI_gBMJ%n|v>hqzSLKKAj+gH2xTvK_=%7+OQ`Kb-%|lvR_jsI7kM`=& zIZ3;dv$(33!05DU|6>p7!{4z!JDs=p;G6y$_@CqcnBWwMh%arG=tEn^-0>q93#y+- z!#KH$kyk)bSPKg4&FQSh#+FzTpPvgdz@N(k`atb9Jb)1Lvz#ChGh9$(qHCz-!&u-_ zp4x0b27$vG$JKbMo|)bkN7Fy~ON|D6ku{!hWA-e*)2Vu9F!u=-^C*In6O?XNIL$vW za%w)mGF*^IA+gMQx~wQW@FV16Na0*ioI^p*QDPA`JAGg+Leyk)|>E;$auEa23Nu~dB{fLsGl7FqU^W>4C% z-idegGUO?xwVQBzF!xT5!~>b8#45Y-4E#Lc(JkJ!i#mUiX1Sz=Vi1Frg{4aS`iM|M zUd?FLLDJv?qx^HAh;m_sGHdo<93(4juR-cm06ZY*!y9LkIsQ{}2;r!38A=s+>p2cV zHEguo0a5$FS02<{l+Ehtl0B_etT0@0O&>D*esy>2be!+{S1|>iY(bWUeeqw1_zCgh z0;u$us;zB7`Hz-b4 z_KY7e%V&4ZZsmvob3v#G(aPPw5CUwiOV*`+tkVA~H-X|Qb7L=P|HYKLjJ5j{(ER;>EKSgF}? zxur(-ptb#UolaK*@8FyB7k7_m&y2yqp@WsXp*6vfQ`L|;%rZE;0L|4}knpR)WZkp4 zRSs7J{p=ODn}m8Z1TM;5^db zFM#MtXJqrZkwNZ7{)Unk%pkgg zuVL!}uw>%A(mWz|W1yUk5{u%1W73e?e(O-bUM14f$ML0e3-v@qKy2~7fz+xYo;a&2p|-{Y96QssdK<_x{AW}`M{FM

Hc7;Opht9e&8pF^b|t@H2)s77K?tqL?EP>sS3|UM zzx#{eUY|VWD=AAnR<3Y6OcDGh0aYwz_wju~3aSu9aac;C5js7T`J!BLm0{(p`_4MQ z4O&q$`57385Nl#Kd2p?-2<@xPr%*>~!v!eG{WHrjtl-Uk83PD%noe(NNMr9WJGOj$ zWLi2c{OPXssqMy4`IZeDYxyObXPw(0t7g3>T7v?2b9x5}1SNxh5s(I>*#|rA>Au~1 z-Lr1c(K6-6Y<4Pm9Hjj4zP9g1?N>=phcHx6ili<%IeBsKdSyJ1?h3Z)%)iaGxM4@7 z=kwhbpD4jzG5K;!WUp5*d$d%B=dAyz4+XRp4zN{Dj{C0RE^x*Gj>+7)+EL;(D+Jw9 z-V7|$$~_zHI+_fdOxFHezuZHhDHgK21X-D|VTlk$p-Fm)kM4=egG&?kWuH!9pF5(I z);6GqLnf}OL7c?utdnsU16DP#e$ZjrKJL zfdS2S*Z9Q5)w)%%j=MLQQs(>mWVK}KMW|uu<;g%CYyjL;ZseepPD5gN%13C**)*L;ax z2OA%pJkiIznI4nYOi1d_`7}@#mYqf!@8M9DmWGdAf^5A8h@ekLd#kzSy%Ic&;(@2D zCh;njO< z;R8Fp--=MpX-NDP5&~0Y{j%Qq;#Ke|PeN+2Lq~i3;lUY26Bu^+M}--rX+(EaiWs(Z%dphlvuK ztcK6l?eJ|OBM;b34@ux+3NkxdS@qSqulnV;eF@ zg0`TWwKO@%CA1}$4F;O8pJ8C6*YWhruLA$GjV(IBHj^`ClUOLF6*^hsfY(`z=N^Ec zgkT1sVjhO_JD3lX(O&2Vc6j#}56oN&1wsHf|Cy-b!vR%(>*M|PV&p~0;jX{4{ts0x za4oB^9dLuK1Mi>Wgmt2d8+a@lov6X*ayKTJPWH@V*+E3ZLA^9R=})mOWFV#JQs>PC zpyFwbkR;|7IT7Mw0H<)Fr{#vz7oj;;PrUC45h9=xMR)hgjQ(y)^yT%-W-L&Tyxb(y1!h6<*sfM*#v=3o#G}b$MBnft#4eurLKp1~%R+ zuBy*eZT}Q{QT1=jk*orh6B2}@N!C~sWwK)i$U$xFT+nzoJrtB2Qv^BX$Ijl6IZARn z7DL0&Z}h-7&AAL0X7<1>KQQK3{Gc~oQ#jy{Ik)R|s%x|J8T;=YYsYd$2X2`O%&Ge|c`s$2rYY2xD3JSHP?1m=_$< zrb$B8KYP;H%#!FQIH(Ow+>kY%z$B}dS%qjpW%m$kOO{DefpKr&;^nkmgWUSPKvXx z2~w=5e=Iyvch+z9G-#}d^i8i40)sA&?==Gu2m`-UFm({_>zS5cN*&%>@v`+p1S*0> zcBcH0QerthqCJt{q}Xd};SVX~Wp^0rQ#3JT`X84dM|0lKt75wO$0_^%YPK&@S_xjD z62Z@;`p;=5i+u%+dC}to60@Sn0YO~=Wj&TDxO zB?D7GRWx~cy3K~$Mzkk9 z{BOubvP_psl&0fqh>ollKH4yOce&;}Zk*&;c53T`|Gu#rHG+o+z4;_Ey>`1~6sfLZ z?j-}wU8E`+aMXwq;S*+A)q=zll+a~iiOWbHQHJPO_!;e@RO|++=Vr%avO{F!=|}1% zNBb7D%9%Z|U%~ATE`d=wX5akgJYBRWdO)GFvQkFJ%yMsKm@b-6hjl2Q6IlYQXbn(*ewnFGh; zZJD=TBceHOqb4#X%t(t7(8nL`+#z-UVxlcz(^Ugjd!!U`O7tELqN8BU2i@dKUMB@3qn+|)FI7+oTb(I#$BwO&QhgjcO$?9>+6r@4z@s&e{tnrn_4x~jFg;_ZUi;-xh1 zvTEnWwup9H8yhLuw@h(~{43B&AC-m;m_~}DbN`B_Ry#}}Mt`qK_T6pkaeTL4WlocT z1_?nk**{;f^XoV!pT-%F9-=huxnBGoUW!$O2ww>Z=BsRz=Zc*e+>F_mROg0yVC%ru zR@9)|6gD^NH%9=IB$(B=^*y z+94%iCpOJo>NeH;<#t(Ism3+&a{uG~i1vCn^ny1zQ&0cXNN6rB!E0b!m|_`qx~UE7 z2d!T?*s_{5y)O;w30|MFD(0~#$Tv*^b}r|jk2i(IEjV!UO5?<{iGke8<%ew}~cFW`3$ zczK*9pYb(dW;`qj=AOt+Y&YNIHST)D2pzsgGC)BrCnpVgQ?-w%jo=H3tuKpwN@Lxd zu<{A)n+FVQX zg-rkSX~+m2r5tWz zRQ2asGodv*O?F>0f*{+PCIaZ-TP89|d%(^${UKXkTic`T0qb(-Z83ZUu%~D$7fiS9 zxxcFP$vu9ra=djc>M-^sAiD97wc1L5MqAsIK@t(vAuXkWK^h2KE_WPVBg>|4Gt=D{ zSBsSN+?ZkgDYr6s-1ccHkQRC9y*ZMcgFWi~`03NZ=J}2f+P`*)37{teR{T&pr!=Np z@CX}thK)d-BP5sxAx?gN{!Sh@>Sby7(+a1tV}BNjubG+j1PDsfa(5wg9kbl}$9#(=^A?>n* zak~cZ^%|l!Xw+7xPCq?E=7GsmP5;ZLGUMz^+v3RX=fY@T#v95iB;6tzlpnj(9=Kv=d*`i3=FN&N4cGD1aBxC!WK= zw&Cmqi&JMvUib$}udG@2t1i*rnW7}=@uVw*^W&l5V||2K!$_?OiDU|)T+D|y2Dh!S zYP#r2P46J%ajc>yqN#@-WRB0e#B#F9wFS7PaT|zQN>vLRX8$>D z`nETH+kfAZs|9irs#R4iZk)+~raW+$FGw6hZwD0*ttgPw06u^LB`U)jG1%_?7mrYy?)aLM14)s|b|(1RPKTV;_G zB4}1+si%y=TPUP`PG&(1v<3wBQ}s16ldUu9H;>&O!yYHE*&c|dBrI^1ALi_9Tmh61 zE2UilW3d9e!?Rbbx7;Ty)w8#mOvIQe;|m%KpOL>JiYI&2%KETx|1- zG2G{`kL8z2DRUrKR8(YggfSKPo}bT+L@7D|w%DfJ*HeI2TR}mAhMSvWzV7YK^6L#o z1>8D1zbHSLYNkxGPxB^MAr;NNE#_EIo3fC0;na;e+_3)$IDjCO@%9vH{ zcuX=W)F+dgdo5Jyz38msK20HWMm{GtNsjNXzr#6*Q%Y)&;K`O|UR>j0kE6}}j}SU! z_(L`yz_<#7G)fw`tBK;YyIJXHl<;pe=%B2NZ}3&3(bAz5yJFN3@FbgdQ2^W|mOh(F zrLlm``WISl?Ceek((ppvk%pQ_`g?!QSOmqFzOxU(*{}g&1ag*J-gp3qrHLBMCeAov zKlxq^dy`V^3qtPQftQ)9luROq?T-s9xyYdp^jLiRJP({H%>U@&9*{Z%_X+fY|M{b- zifSL;MHkV_V4-xgNtuthx{(0C3Kc~)>G4XJ{gDxr+DX@8Aw?v8X;YN=P1z(6sx`D@ zDhRiKBn>DsBd>6cUTIIeb>8X|!EY)NFsVweodd_YtLNg0p4HNJ<}NQ|0otL>0IXz+ z+kmo+&Qj#BU%w*SCw<;6R)vO!Mzl-fU6#wL;CMma_glkw2ET(z=8lw-C$8}Za9T{> zaqvEK#lu^NJ-TB2FpW3g!dV#dTF7hys)lTsq&sa1DU|r=!Nzs)BNtTx*I;m7UjfGn z@ajJXE8T@Stz-|HDcxrMvF=_oMxN8zf=H>sun!G7Mn);yH7r18x3v8I5okv>Xw2e1 zz)1*-J}5mvn9c_X*Lnt?NVCbHH0iGH5{ zw>-(*sm5*qK66y=lUIMfFH|rhJAp~_FlR#VAeu?GVEm5Ai6hzx` zhpsS9{P#}|8a5!q0UdgeH`RY@Pv%GkT}_^JY%-EP?9`Bu+RQH~9uOWiT$ES9M{Yz5G*@#6)ByJvK*s8Q99w;_(V@{Fk+N z?Cbh9Okrs$sU2H>5U1u{5`ww;+p4E+wYsXeTmPci#DY7?9FR!;8J_9I+Y}zDLxLwy zHsDy}o>b}j77Sng+P!I)E?&?Tu;ySAOQ}YOX$hq5vQ-qwJ9rrrL2f@Ahy*16vO=}3 z(NGE6KlpHQKd%~|&cU)Szzp1Vh*go!?&eK&S`x!yY3CK_YNl80bPe;da_;n(_*vv# zkYL^{CxAG;j6EQkJ$38AI=tien;SGVSsM|hRJvo}@g&FyXzm%z9wjXGrmSk|;8r*d zk3lxf*H~WB6=3Jbi-02Ipt*R6uY(uoT)U@RdC0K{!CXoasnOw>flU-gWc%M~p^%f} z%^UnG=e`-l`3yMLxBWHh4!rX!3MPl$z~KOxyZG!KC*l2Q2}q;%8NFxKzfgxq=^n&+ z0rbRRp;8M$?e?XoRw`&+EL|Hn|KYb}Hl%*l|bXgPjV;fCkk4o-M0 zwAqrLitCW-R>cR3Y?pVw6FI@I%ott=wJpBU39)WUpY9Gy0Qw~UvBgH5%Y=0<8l);x z-T*3KSk!CFR7Y3WQpytKd{cXx%sW3twEF_{_nL^rM?@BKORy#}O;Z0in&ZGS3=%9k z47Tmi0%i)Z0A*{CVLHQekiKaB+T9Dw-_D7m5Ngdfn4v(o_IMx@f8l8nFsfG|!~U)$ zJePqGzDWoDt_-<&eZ|(~`0K*9R~trMYWtxypc%=+q$db?!Xg+%`4+cDXZ;4tYbEPE z6e|gWO#aa;-o4eW+qiQ-xb^7~>Yv7`Ls$kJm$aNO+*nn=C)9a09OzV`pdY4F zgkD(6v<+t{ee7pacQ5h*$s8qpvOn=d`TOUC{Qw2=1QZOM!Y=mo!&T%F;A4XP6h483 znqHatdwfT&Pt^)8dQ;ze+y|0?+E3@tHj>BPI&Opk2P1!a5l98}Yn;BVVq}2#O-D3t zRPQnT^F6f@zHmQ3g)#;Ghs&+7)@|bH`Y0B?%#uGZyR`LHt`OpxvYoW%TMs_1VMXqx zkU$^eok>j3h!CqD6284URP%UvR=Dx|KIGMuw_$=OLW>vCltB$;eusZ`2>5Iyl0ncS zf`-rVJD*YAfwtbpg|HTh^@_oJsTjbC)XQvwY{#eV1JLi+D8l}gipqjujtbxj7)=hO z2YXC#O!x{GmN#&%oxD7itCKJQe3K46_kgO@34yFFK0-CGX8iN_Gd1F`vAu1S8&3@* zfnU_N-iSf8kr*dH^i1Rie$YQ1_kzz39TxImXbjk`+? z47q;9YobYM=ID0!)uQS;ky+mAsf>qg{Ttg86Z&eYQsb2%<2}NXVBfdhU1g06zAQ0xJZ@{V*Dd=+5U<-t`Y*FX3n6~83fV6Pd~f0Kg2le zEklf=z9+lqLEdF&xpCtfaIRf+`?8^}Z;7gjaPB>@mIkjSK)B*Tq#=?)bOrET!ys=V zn2JX-Ui}Is|KlA~$*W}6`)lKL$lApy$=w;>P4QIQKfmHZuBHB7s%z^tUCyf+zPEzb z^vf%iWdj!ME1x&qj|@HhH?x!H2mL<(ba;CDwt2YCj0z9=P|%4bUL1N%GRP``rG)y5 z-C;@^MlVH0kc5cqEVa>%_c~6*K{}yBzWE)-c9))yDKJx86MdqOZ)I|2Vo2N`q|LwH zd-Xx)WUD0tMNTUq2N;Onu|1LNg+}$yUdypAnv5Fz7V)?m`E9r67dxEY2$W(T6-Om! zKEGojtq3#-z2Hs6bYMY2f%|;Ob$uiO)BXa-K;r&hx=8r#$#ClM473236 zKY(g75`nZBw6iC^oeS&gB=9nyf@ej)yo}Y)i%Y2$r+ENnOo^8aKBQtD{p_$teeff?SEGga0if~89aZ*N#-pQ;SfD75o^~mZ z&TnjvWgB@)c{s!-$_EfGqWiTGw243G_`6mEKwO2Hx6GIZ~$J zMax)!8E>MoPaa78r)(#Ou>?F9wCvReF>5Z&z{CVbCup(UugKElHS_tdnH$ihxE<9& zbMe<07_Mqe@Q1$FzcYjPT;_sT{IkMSV{e^lulNUDwOXwAth}ShnZ#BR`GS25uysm_MF~iaRdV%$z9Zk4}BInfsy#E6-htGL=dDm01Ls}YW zkXjrCIni|Bm}>!>VV^oWHC2eOAdoTihmteg>ot1zEQf^IOYYm{`bff##v(}rrpV3d z?4Q{x;OS5e-_@9?x|PAEm-SgkduLKKQ7T5Z*``m9CV`ylVt29qxDL-%z%PNHUcKE# zfk*|(9)*|f`j(4bb+wwIKy&6~{nlL!e4D+)tjWpEVYWZIJTMFQ0T;|M0FZSVz!PzK z7+|m{qInK8GNUB8!Ls;ILO#1z_>46WG(By@jKEA_dgT`A4?M+vzdK{`nSs5vaV@l) zJ|H584IJTs1p~Qntu3JAaG!fkQnwuqK~b%-p^j?Ud%)hQ#^Woqr495w!iDQ*G~WzY z|0h&jFbC%-?*_E)7@r4DfnDzDm{t5xc?wE}SvhM!h0cNaDg7-_Ke?x5iAutm|BtHg z4y5`E|35dO5;N!H-tGX__qRJxxdE8n@jDw& z^ZiYXp91!ut8y96Z2WtRWq%q!JGy#(0~)D~Jz8Y*);Jj}rHbC_TbpkWZLaq{(nsoC zjj;#>mL>=+!>iY$*;}*wY40^|mgHgo4XKE<~$~;sdh> z)u0gXgfv3`d~Cg1`>(db%f7zLuWg=&gjj=Ia=ISumAKj_69@yHF3=AxsduKvY=8w& zvqgGL`~IgqY|pDg=w{WU3}LbF-*b-`$g4PQ#N?MLaQEY*iMUWLKcgWo^)b>!&|sNf{#|S(9UfbbAFgdVbX@rFK@0m02I zGZ2bU&w+50%39}_Z4TA17}CDp(uSWQ*>5=v2f~9^ku3%?+?YG9?n-Am1?e((9vFR( zKLdKbR{J*mb!x2ZM7nhRZ*!GH{}KI6li9p{#N?2Fnqv?fPH9v~2Ut<-{?^}1Pjf|TQ`yQ_dsByB&7Z3Fd`EW;TbG}=AMtdK{^GF~IY3pAH^l*#n>8=j;`3=`(X&`- zIm3dRFehQbgGF#}_5m|IsZGB1Z`xdxJ?D2;qt)c#dpw+&H>Ij^9fNka3&G+koI4C- z!|bI6I8&SoL)nUhcULSeib;Olnfxv67@i@)uTv+#H1Eg%7&BBjzXh?46aB(n3QO>G zaYH8_EyGG|iCcZK3(JBk`OwED%>nj~Cm-`{l%xztycPLe`yw^nEsx|+&u*YYk^e)j zBT&mh|LNV5%ZKtW?ULsGum;7`y~A7;JnYkU>uMC;@?LBHSK{g9pI1FIzWj2R`waul zd;#&q7$Jzz@wfFqK*c)K9}@o^L>XJXub@A^Vnk?W4RZzOxbS}~LgB~ppJz~gIVC5e zIBiFRKC9~9UrF)7?WXn}i_-r*CYteh!@KqjG0qZ z6}!YKg@5u`0}2Zu^;MyfWKzsCJ1?{OKbI^U0a%^!zxgfn&U6zTxZ2n$j$;S7`h>@j zh~hPQ;JFU>=xyzdyh&^nXOek18|B_75&X7m0riWwdueORJvO0Ty95gVE^xz~RO5j< zUJb)QMXOUToO|hduA)SE4Du~YZnQE~Nw&>-{bu-d_8};ntTl(lwx%}Uxu%?}ecs|U zI`FaAq`z@j;x%v9BO+^QXw2GzmTQ1h6?jdM%J7ahDiErKhBnvH8c8xwUfsr3gvTAc z@VM9JG;p{kuf8_VUd=r1mMNdP#p-@5BiWKq${_gOj8is|p@7lKt*H0=H_flYk3UN- zgB9THfq`e$ry<1q;V(K#^q5O+9?2ov0Zz1$8)i3K;E3e;t#Ce1=;~75K;9ANffC{M z)R^t?S$Os2IN*s!sF!ZmewKeU;9iq8wz^$1QY?caob^VK=(c5HkF4^}v6^HMNBsv> zoZJNslb0I?(nfJbE0eq6Q|OyA8nxy|{G*AO|A=KU3F3|I=)@ioT`KQnTfNYT>-jyW}S@_{8n_fHv)PI9(NG zNqou0&>NPzaExFSqiB?b(HcDC1Uput@7Q+z?)u;E4{2$UjV9j9^y$rsK`=f~ifwL_cZTWp$MczX5s9$}{RpZt0maQdC zwp%kSUvF>KqM%bhx+*UBkBZB}EjA~vyoYNkHwzI65FEr0!nA;WFl0;R1Ruv0rR=2jBIO3SrYW4X9Tn8n-h6*GI96ineCF?eKun7 z!BY;l4Yl#ZN3!Ecokt(gy}oz)TGUz)*a=>L;ypu}E|O6vxC@H#>yL=lxo;AY-_G`AZr#3l3tULU#G+aah9sS9wb^qh+ zKK-Y-4pcLxYRzTZyZR=p(w$hAkRdlaHC#(eXwP792x7z~TNQ5*=JL6*FzNni}(L+zBf5bt?5cYt8>M($K+cz)x0jA0f!X#7$;zTSJ7JAq`>yc?5zE>W!>+Gng}$* zcHGETE2m%StHhcgiwxuoVOCNC|Bfr8yzG~%%Cw?uu-4tSq`J5}(F};DK z^Eqenx02h=*OHnpke08m!0v$H(WyJRh;ls237Ka6{a5nij^q;Py6o4Z#|g40eF%q9 z=t+iIjOdAyM=*dHl%_#P(OhwSnLE@>G7sPTbuMVPB^B#9`tSo>N}p11ZP~sOlFH4d z_YIyWvx=w1a6 z`eTJfKk$S@?MlQk*QL?pA%ArRJu!thrmn2s7?>vVYAwwy|>@u33)8Rv0OM^ zVM|)}HG1JRvY2YU_{gMz-t5}R%t!Wm&VnY4ZC*<(%g=NRF1etq_l5ZaqGjH!b>{C>8@eCv*FYqKLG@~d*DnYFgc!auy*Wnm!e-89YX zGpXNXa4{ot)VOLHT$oDZaXDy)p8i(5P+fi;!@lH#pvx)iQVexhQ8+k!CYwd|4Z$%; zB=;;hbjZeLtleTBdGb+6s-ly3F&Agur!cQ)RsD_@fLhS#k`?wevlgy`Jd_28X+PDTfMMWV?@;WxcL(2j_3C%T4B)-9vsCKJqj*e>O3| z?4yINoJI$$J7vg{$GxFIaTLMoGlE zGk=e<-sbpHl2C71Le_cjg+-{VylpO?89J@bFT~3E&zq>LY&J_ z+3Tad90X0LZiEwV z^MI2s*Ot8}r@jtZM5}X?8OhihWS;0B!-73=O~t!O8qayyyu27wZ~@6|@A56^{XHHU z?e6~5P=o?<+NLRm8XfdVe}rDq&3CAUIo8EsE)E%5X;nA#am+RIGEGm%Zq6R zQ7`BH1)K~QzFZg8NG&&Y0CDX*6Vgu|a{GFYWN@UJsq^=@3p4MvFR@aV3b0EbQ>lSg zGH97ZGg7F=TedlWf|Wwuo$YC*K(HWECzg~&*V}YfN;wHDrm*z|l^ve1@ z&y8L-cj%1D((dr2STJ~NFx{9PQHwVv`u~HTn24~C8VuN%#c4Du6>Xh`lFh-Ki zWx2A#c&>fIXo1s*`qgzNX*tI#g&x+0C!irn4hga=nXynvx54m z-Till++x3_uTv4e*y+Xk!ONJ1SN`m~O$s2SMXxc&t@TJGXeGUi11PBMfsPNf;D6lnE%{E(G>hpTmX z;oK8NsI&lcLxT7o3s~bXojz3qZT!wm|Dg1egTxYi;6XgfCJzT#ZX#&V*d?L=N_nx%Z6-CHB(p51J#pW~XjtwCBsV##;**{9afkXMXESKH9 zZifklu?Nsq?*4;`!hGhX{(?e{Y=~|;1BSuOT_H~D9;rO_J8^24#zWqLrsVaC8Phxsh z@4G9(5t-*fH|Mz-C`IsvJ#!H73|}ZXa0NGrgsc~5(c!qD;!=gc@4eHAkBWM z?HgwoeIBx02xbbl-10x}u#BnmrrBu{G8X}NhmC2o1Y!Yhsf3-iLX}ba>R-MglaH@h zDWX|UTeOue<=f6-m_xamCx`vs$+$A)@R`mWRZ=IRb30{A$|m7WX-7l2$tHU1(&B@d zIzJ}>Dd#uc5L*!nb_fX7h#+^pVt_8?IiYw)3BxEneZDh6Eqwe^|l!u2(|qyxxIz6)%3^GY#%eXHE}+nE$7pH;gH%m?26-LZ>(Np24s?2NM! zTSHtiT`k9yPabp3DeB7AjwUHRVOy*8E4 zm~hz7H?I?@mjA6x)mXK~z%kf@W4X7ayr__)LKk<_?GC3G;syRPOVa=dHkIVVbqP%^Or?8R-Cwgye&MMpGhDZI z6g`^bhaE?@e@c0Yqav(qmo)_PQ_(fc@euZ&QeMz(^X@TlA5O4O07Yv!ti#{{64Egv zoK*ym@~Lr#bv~~X#z8vj(aYg~qYv6#V($ABI}lqSz+gp zsZ*06nJP+d9i?7)oJT&6Q%}Q@D5JM2%H6lRm(^zSph23PWu$Cs=jF5IVB1?uQQA{> zguNNyg1R?+;O8=4m&A=X1hyIHdCL%vZ181Ib7A|-`SW5(;W;;sk$OqjtgHKe`=yJ{ zeP14qUq@zs@hB<9XYAkY^A$|CpGvZqqv;iAiZ=$<)z*#eu9hb)dykB-gmV_c=JQEy z0f(-#mq=jK$kmk3hUc1ZQwslt4>qfPnc2~ZJXMH1n(X!18BkO0 zyTaji^}#Bc1IgB)R4Pd!>l+#s&MNZ~YzR5sf;>Bi{6?1=sWj0K{hPoWeFaz0uE0B< z5uIQ!O3U!t$BEi`xqe~O?X1gFT?K3IOurIfpzZnRx#TeX*eVk&?1k@NHLzx*k#<0j z;D=v?tR`!FoGNB9<8=I!m%8W@t4TpgZ`B#bItur6jU5?mEmyJ)jCbsg%%;j1;kXD2 z2#3`m)Y^&d6)08qG~XDgv^>S_0y>(Z2SU$e@zr|DiVAy+q)T{Gvk&%3N^`*PBzMb- z=S?Vbge|deDs1E;88`}&I@3k(yEdC0Rrq~(deoA=vCTovvnn-TF#oE}F1k)6vWDfu zS0-E#6A`#J*AYc++A{U)Edbb|SA8$%e{c0!nk`daP-%0n(po6}1kOJn=#wmEBC{*X zbX8{y&k206WF(oJf7L9RlT3BhFaD#l=+RshHqw4SY`LA*^--{-#^%$p93%J`l99B3 zg7u|_snchyhoxIUVeZQdVqb=$H1#~t7yvz9OBLZto1=4jM+~W}0QPLCIAQ`jd_Nt>i@UxMxaKw zO{j9|G9c6BtN|J7XxKlv91>#Jn1M{<-%Jq6Gsof4Dh4P|D6wojw zgTd@Gup@O&aW+oLA`wXqCNlGDz|HKf-4j#^<>iQytPEUkB73duu?&r!!WP}2Z&x&P zsj`XtYvJNe;Z3QHSd&G93nZ+ZqG@|Fz{?PJ?T@q~;F!>7B?DY#V>j2g6@wYyFJ^`usZaW$wPK#)s>9Ta z@!P%on>ozpkHQ@o`((m-Ycbn~Pa83$m1~gr&85l~Y2GvjiqY#nqX(E*f0PCwhm^CE zD`%w;l9vp%tAF4(yFlA+N}KW%^~!5Vv0YDaYqExwa%1t>ORQYAw#YT>83q{e z1fi$677$bW4gBJ7!YMa2yt6ZkKOoCJ9-mqY^IybCNj()glvgghm1lkEGNaxv+Xx!< zw$N&_a5Izn>lb*L9=9ZjU-6ppaDzROI9hC~gzG`*KSpk3B*zn6-;*hcXv3>I zNteM}{DkDk*NI__fb=jBN3f=42jo6~JXYiQrwfih8iHq)()J4$F*y9orM_e8T%c>E zM0oFV!A!V4YUi@#A=A^j(qL~KPj;ra1s1-(X*2~2ZpXUku$Vzc*G5@_Z1rMw>BA2rY}^aArZ&1!vNjZn|-r6kHn$V84ITjaQS2{OQ>L zzazX>(amk3*9JzGro7`rKDq@;=rC>qsUM;tWV2E6YNCh68C|E(<~a@Nv+4 zU8XsiJgU$fqI>{?B1crB8yMG8@sU70@91GAs(7mvCRHxMWXkrl9O$1a`c8rPKK zDxAs=PH*4ubE0@}N3faE_40;qTV0fhoLB?`L&<*V4Bh&S_JXaXa_xh9T69(SCZDmT zS2!Fsl#bS6sr;v;mf63#@%r%Sxrp({e!g%iuucW3^Cgis8Rn3(;toc>5EWi!6%vFT zd<>SAw8ob6sPnEgHT(Uhg^5@Z;R==iRaag@TqT!`KK=#3&GetHH;aD(4>M%Xxrzch z@@Ud#GcSs&>L1^0PrDdf)kHr|8-q^}qe!XeLJSnlR`LZ&W-@cO{**kSA|{|Bm8M#& z)4l^zXMR0TbySYd9d6H>j*3)|ejk#z1_}lUZ6_i`mbDbzZ=D8w)@ynz}) zMf>Q^L?6j4<`bG`W5zI+Dcyc9)qH1BVR3M_MDLS|P7DvX|Dl_wneFFH&F3n${wE4vX>bUh6GCouN zsV{x4O45&Yt0=d>N+EmgAfHj~v97(M?=ZpybL63WP_c@|CL&v$eQ{M1b#y2%2eW?- zaN$jHgiJ}r5Mp3&lqNE~1Zp)PDuaw)l4d9TDGL0(5FNAjF!)K$nVf4u`k4@xl5@FIZFvk`E6CsA4sziN5aRGOB7uX(Svp5ab*ai=bC3a z{QL;$)Tz|W6#ByGBma%|m+FHqJJV&P5~ZKQckS4hM3MnT+iR7_H}28#uVYc}qz%n~ z_)r;kPT#~ZjS0Tekgz%FeO#2@e&GO7ogN8R6sVKG=<~Ix^6dhbT3|2JDc~)4{U&5O z(R&o7j5RDvcFiZ1H?VEyLzRp99o(#&Gw{?AY6u|IMHhH{1&9BUVEzxO)WPV9vGlH= z{rWZ}rE9jQYp()lG9Vr{YWRWUOwJBh<{dBS*ke}M$<+B8f*}JoZ-BVOq3X&PS{kb; z{5OFD+P+UD*XuHVNv2M251D$4mT(L~l!=Sst}ZsH(#KIVnxT3_^wMa3166H$$bz#K zuu(&)eGRc%Q8-9g&RQwD#K(QPzjpB6CZ<7HbW`wE^v<$Z`WlR}zv0x^+y>iFWXadj0a~Hd|^|tFggF z6l4~{|H15Jc|$F~n^sV4k7>U?hWA#lc$E>#u1Hfr&zwvp#L zOtmfuH={h5QU&Ir82%c_IGn!ExN<8`is9HC+Vfgdo)dnRoU$_~;1|vD$G8k^zGS9TtUxR##uK#T< z+5fR5yO7F!j2?{=dEH2aCEjC=Bvu=5ZXF4b4}7%O>s#6=#-uXu>{uy0i~u@`japw} zL7ZN00nv=&{V4?mW-=o9E#w0F{mJ>neAS<9)uRf(g~`}ez7nc+t)p2N4GI=Wq07#>6m z*E_tak7`}Y1NX0EOz>~!Tsf1$i*c5NNj zJiV#Isf%AC4@Om9kZ_Jo^)|zM z59|n4Bqouvc5NAI7Wk7^rZv~%s}x({HFUv4LBx~>arr?(M*?9cbazJdj_UT9puAZU z&EBg=Hl#s2?l3G<{cMQq{3qm4WzR)<@!U2n)vH(>`vP?aN|@s8)a-Lh#hgAIaZy?& zK^Q)|fMQGsR*xNacJ%2O>#Xg*r0wB4KK~r&DOTS+`3C@}u~K3?*sFEAzo4<-{(=SL zmol&RUi?^6c8}^e>(SwGbzvmXm@B;K^D1Y&7fKEWZ!zLHw?E$@2&IZNf7^1sBMdW; z8<%(OW|vR0vMbAmNWJUSHKis=WPI&;qNPtv5e9ML9HO2k#W%$VJF3>g|9z;J^uHZp z6EL6v?*SrP*8Bth_SlKwkOjPM?u;Z-gE|V+_`JY!sO!Ynxtk5ov2T*Fh_d%>lO*6% zOnF?lpPQ0753cg4cAQ=I*1BLBMB`a5_T_&RRoIIc-ba=J(j&osfOK@F4hlVfeuoM< zm1l;--ZT>3hnFHu@E8O;i>(33@7gECrrEDj=>vW8jnA50wb5Bp(5fCg?QSKYDl` zd;hd8?FuAR%~jiDH*?!t)cr<#90Z!=XV6OcO!i?sg2iT)`U;Khw~+HLM-3;SVd{{M zOXN5@t$=VwqW&Phv+U5!&3QAh8`0)%w4T_bx*-wPANnEI#+?0}PQ6O%e3eQaVt1;$ zC|r2iDF!bh&-FjG*ITZWkh@y`_&_q3?t|TUe2?O45kOIEK_6Ab|JougxHMPJ_L@Xt z9N^9qBlZgoM0Xh>f2^h|mKVd5iIj+(pL~H~>?|&XaO>EhER_?tcdGC_U0CG4T3-kw zd6@AiMkLP-8)Dpl_&6;rR2o?_e1{YrK6l0vWpy?y6KT9@uo-ijZ8uad;}|H}h2!Bz za5Mx_!X08D$|r0nZ2b@T|DYh@8HO$!I3)hu;dT|+yDr4IAl(L7Im+eIv1OcD^kEit zX2Fnr=?VlqPo==&`&j$oj`h#s;6CI8`OpaNX&{fL8?)Y=Lab(+rdak%zNmchOAzO- zay(=WzHFf`&E@3ws?`P=Ck`=;C1k@5cLV#pN{T}1Yi*`urBbPLtT-D7KT@?GvPL%A zoc`>YIgpOku}IF{qM4WKbm@x^5o!2ytmC3 zM3J82O;mwGlUPWdjJ99{v+hEitA{s30Xe_L^eXLav8uivZ9O^eX+|hJdtG7Rzis)7 zkCrDZ1pJj~6XYpb^u)Q33Wpj~{hb&Cc#C1aoDfis37-cj+w^M#j zk_Di)w&nQk!o{epzDbwODIL6o*&*|Tbm`;GlHGwp!|bSvn{78h$do8N4GZ2+O z6+~*iXOs!9DZb1<7~;X<8%($iw@~9(qLAt!T1iszeF){lqLc;sh&${Zu9ib5-{wy? zbI+d#Oo+%|$NHdlQb}|h>h{Vjv<#i{(m_p~kT6KR-UTPw#l2HG#~GHlb+!7$T@+`u zL7_WZkwTmC52Z)6u>cp{rH2eWD=c4s9~zZ%7EtG^UC(l_7s!)@&hm%~GQhl$c-`Zf zrqAGT^k|`gV{hQ*p;*J~LMpF!wr2Y%w;956@*l(#GYUHVvwGT&NDgD`L;SeFK&~uh z`@sI82uA5BFRb0bOr8@XlrKJzk;Bm?Xrz4;-McDb2M^*GkwSTplivSg!GG--Zwqe& zJtuYDiv1I|8=~?t6g$jHVIW*qN>IZuugF8{-mMO7NbU_Z_gjOlW2Z&E{uW)K`%h0r zeK?a<%@y3Um6m31zz<3nn4HGGC6y}40oFhcE^E#Esk4?@GfK3Ik8 z0~gvpps_3kv|th_t8D7ot4c5H{)We1a6HAyQsjR1q#XlQ_BJajlzN-|PNuEt|jg@T#|+V!gJeeT}D zm}}-Y=`r33IF$xB>7^Z0XOifcsG=@)*ca~a5-I#={I_y|Yni|?UWIsDdmZOEqB6sJ z?kviJwq#H~+E;#2m^!L9Y=f49^_4{4Wz8lt4$%ctn)wn3Jm<&xZ$u#NH4tV|5cgcl z=kS@S<(QmMxmre-4fpAdIln-6%2ZW1Rq~;LaNdeV+FfbXzlstT<#B436X+y=qrP&;;O7q|R0+&_CCjh55TM(I{#KrTh6rl(PG8;6Ti7|%m52VhNpXP@!CPL&? zxM&It0FQWEOrD&p!<`P6^0)RS{sl|pFLA_nM5I6|HGF1~gJ zUJ@q=4STkOfkFf^b5TuRu7a^oA))c~5>E^l3uFxsC!S_-Fh~rS+How;sZIK%Z~lc8 zfFho3kO+#AExKe6f6wfdFKx%;F=*zrm_hUns%A(id(f~M{;KN7LDjp4^5(n42jYkPINAtV9QDS#8kOHz3rcY`$W4=V-q8p zI_?>rxBAas4@Wj+Xe;GETdV){u8-j6b{J$RTU6{=Ne2(%Z+7}7AxjD3d&&&i_Q^7H zuZBEB%h%v)jzoCv&l-X9c-T-l%xse{1Ab_V#?V=# zP`oQ69lDc?xaTzPRk-wSN^V8Y)+;eDmVu(V9zT|Yuc7++c`5%tVZTZU&}4W;ht%nH z_l|a(hWA<(3w0jyCpI;OWy$H0-mKP<=KBJ!!}a5_xs$(pG_gMeNP@=>U>2pK@5zs4 zB8ts4)Wsg!WJvZcyIygWk-(y+V?+6=Fy|l}yW`>d>Zbr%#055w2Q{kk7NjjL9xbj~ z>}THu>a?AWuq#x(71QhVCByvjPWfFJ_=U$oz=15|XN~u@Ss%R(hvBOy9&nSXlb&YR zw6Ibpzahc4%Q#6sRPTl=YK;fi)!rR5j$j@qnl{y(!rPHCiL#W!w&5zo1OTZ zs~@UDBH`Ja9JF>z*qtY&7u8>wIz61fL)sMOaiCHuO9$tEz%qLrZmcqW#^W0|gTN-} zmT@khsdFXmcmiFsb6;hVRpMqTB#`(ITKZ{U_~skYtE40nO*})FcKJurCLU+T=WWky z26uD$#T674!XC;-xEosAWUQa^^7Dn9lMD{`AjwPtIdk%${eX6GHI&oLO^4nTBVy;3uS(NGoA)>qC}=%Uwf0O^U&2mf!u+S z*&=R_8*nkuw zE4u&4P^0=DV-JXs1}z{e9#p&f7N0Pr z=%2M~&Yv}!S+-9P+XVSU%UeLQy30zB_O3+&Exh~8A&Ua-Q6`MM!8Vk~V1Rmf5-0FJ z`S(npRDBQs0>iv&M?J^x$zRwHF#(0>ULi(UA`73*f8?!NP|?tIp0L^6ggmu%kZT5+ zZcj@DpfSX`VjpaE>+3|8J9{Khv{zco;{iVEBMT4XZ3(a%JP|N;>O$nwt}eIKM>5^F zio<|Ny`zKNcc<<2V7gveaArj-3JMsfu03MSGDfAW#SG{vy7eo@* zc_Gr*n1B3Mho8*y`|KM7C{4qM9Jmr@EJREs3Yp8?zl*^@Hyu?Qu=QE2Ybd@=zynj{2Ud%EXv{d zW-Ibssiz4UwzUF!P1yB|-nYv5nU_bJZL5{;wv3);4Jq&rQZNE}n5BlXHeco6U+4sH z9C|Kbl?Zsp!R8=MW~7uT@j@K%C$vRUgDrVIk!?N1mfh+hxZQNgF3@k(yY04rqxK$e zNJ~ytBjbTQ+#=@yM*r@+Fyq)(A6+1le~g}SmD3gb5)YYKlXVm{YwxR<;z#d70VUPg zd5TBbRn>U}pNI1L8mYBlA~p}aV6bJ|9@EFGEw4q|2f zf4%Qg3}(L6W?Op4#2P~5SuyGx%kpCVc%sqBiB!d`gJV1rcy*0f9Jw35Gm(A0JsA-a z`*37B_HuBG(v_yF!iMO|3}|Sm=;qs&UyWt){b0F?WKJx%VBbFVo@kuD6j|JZ7h17A zNzHbH4*M&v0)WyvSR=Rf)$@=?&s-b->ADANwC?nWZLNDq=ByOTTZ3y1V$yYTH*9=mMNyHOf=Rg>xMJm{TR&}%G9jjL!0@<}~I z9|!uOIC3vhw#$r5Z#zJw0*`B;)3XpoV8$Eywxu7<&hHTR&;$3-f?IBCfw~^TlYb`J z>*<}PUHGVxip?e8x)nW0dU;w<|4Uv0awz+%)}4sG;Mw}WOr2w(;nl+J+>Vo(*^-hl z(G!@IA3WEm!GE?^3*Libe$b~&f1M0Ymw-Aka6KomuGOXJCrelVz$|2!wgVTGTeGy6{&yZ(gx4 z3>*z{FMt9}!qn%0xM3n<1B{2oWPT9Qy&ZQCZU`c8`dQ6&!PE@SsaK7<$!&rRh5XjN zxqp5SE2TMIJ;0KUtUfY-p;$h3k68yy;IdRH{8KpjVQ=?tcI8}RQVprxr_ZD2o?s@k zF#U!#B^$mnb$TluJwT+7A-z20y{n<|6Os+yXLD15co#LwX!!Ik7{D!@j*sSNmJWbN z$pE%tBQT2y0r}no)OdFgDU^=7(S3#R6V{AP#_f}m&Hdh03zQ(QE)kC9kwlJ9X8Oa| zv5G;EX2F+*q3S*Dde|Ckdjh5x<65A&Lawg{4Y>t3M1V-p+rO$}$T*QCldT6K@T36E z-%r{7gktoK7TIafN=NV=DNmHZMxm_sm1i#uYuXT^GwVJS zYdsBq%k#n0UhS&-4b*c_peDwvH`_`83KrZG1Er%+qL3r*RsJ){4W8&flhGCB`H)hB zB9xM{rkD+a*z=XTO2hunB{Nv6MJ&&{D-CAhoCiwz1YO_gbP+9YplfA*y;2b~Foq3w zuuf2RfXN*5$#cnT+N)vGl<(k{da4`8d+{=p@5Fu(`6E$w&4e!Bf4Ts2Td-LiYKGyc zS$D#cgpR_S|M-O~pRVfnEMMjwZyHVMPam=TKh@h%E@FTrEqv&)JKg>LG{A$iorgYW zTPmca-UOyM=!yna)x(%{Fm7puhCos86_#XrO!&PIBDsru zM1o+zG@n4p8(Dwmz!x3?i1yITQ;4lHr%U?i4 zPU)tzQpz%$^GS7=-1kvOqbDZ(gqH*To6FaJESW0|z@LLmi^o10{!FpHcHFCT0092+ z0aGZ$6{khZFPw}c)-jp55UEb;>^XO7q(;DeE#z6vGN1Y~u5V5c3(oS8&;GQ+Dw^MM zFg!3h%J;3Zt8pTj4O9tddPiW^S(%DLF1}%Vd6cfgB!k9*y;)SsGZ>Asq=)?!X_@%$o9 z=CkEh#SNl!6)q+3t(UwWu2{*jqtM`JP-iBGUl|3*pm+3$rJvg&!AgFn#kM5EU!U^r zxqhSYu-`tfb5AV2p^4tXnfN2>nz2E}tNPMO8|+DEXGWh8Hq zhX?1LU_~BP>?d!2Q<;BuC4b?@!?Yg#Bt!0%EjV}I2NSc~JN-C^u#XdeU(V}!PV{oP znCX1~yiivj$b@s)m>Y?sy?awKj>nDY=Jhkjsa!wcbuuLvRvV+788qZpPJ-z>%->=B z)ME0-5N`BtxU`4{3a~znf%;Flo~rTON55#Z=83b@hApobkBPre1fbIN0IE|u+_I$3 zcN2{V4|kX^i9a53mtkYZwzvxTnOR^2evwRTMKBSzwI9=}d;N>yV`gYpM{_S|*-3Uo)_9OWg;> z)Ory>Nh7+DdY{=APs(c0U6MOiYKNAJx@Q7|*?+z6smDxI8T@-DAO7B=A=sU!u8Td* z@h9#H1^cu`?W|q(yV}(-v!8Ao_qq`)C0o8Fn7TmOSh^PJ3(KO2pJ?HCI$NN!!U%bS z6IcTiki=Z6NH6axxa1Cgaw5)({mFF|=R0-zRhs2`$8qnDI>E9Le0b8Fshv%tv3VVFz!0 zk;R`&MoQFR*9)3v8u*UH$mG*QrO2VnROp5sx>TConcQFkyZ*ytyJK--DYr7}O$a7Z zMV2m@iihcYh)ENbpn+`P<96tgU)K2NP2=%l9Z@%$p*Z)?6VE5wnGIiTVhj4IN&?ST zf%06@pBvn=Et8ZL-~N5{3SRD+Cz1Ze9(&?#5W643HhNI`Ax@xNyWOCf;U5UYm^%A~ zzw1Y!>W^kcyOaLI#?x1pUN6Q5rur9r&XD4TLWP<%5`Ls9|H(VVb_I7%}*MuT+^sUE( zwvqQ$0C@|R+^uIes=6~cgt0#(Vu^i}Ie@NEtmh&b@K1Cxu}+LB(^+P@)QdAi!aE_6 z4>);R_w8Z4j*itog$!;O5jpyxZ}JrI*Jh z{`1@NbO{7JEZS2q#)dP$$k!nZb473Kn|=-(i#A<1%^SExyA&w!J<9>CQqEB4C?O3} zXWjeuZiX{4vQL%bq})iI1)q!kxwpR}Ob9$5QF!|Jw2_|UzS(u2T_;iVgnXk}q@yeE zhmyAB_eTPz7~Vr*Y!+)T(l=ZiLP+yafKL*t9ag`t>yw_8v$Zk=mR)h`(} zzIJ3H>jmLaRk=L;uH;Y4iv1W)EUEW#zmR7YJy(WJ45_?Ozi9lb_B5e-tP)H$C1-`j zQN&Vi&ZiXwG)z>RK2D@cD{SodoG3ZRTtoOV>+fq&qgdbWeg|)ReGw(sZ@yhHn&bIslQ=!fO3awgd&2CoMgHc&_XS92mIfNfgRw`ql#Gut$%}6r z#a2;L+VX($ddxa@bP^a=K!?4N$6Q^Yjg!^v7+1_=BAqs z%6#Lg@o|Akp&hyt!?^-gZ1nSCAbxoE3mlo)td~4$@AfEv^HgXW@F(W_)1Sz=>RCMS zRF-p_BvEpG#Rs#;Ulf@rQj$CzW^%$^1F-`ZHos!`$J(cHEO#fle3DSp{xyCAGovM3 z*Z|zmT|LqG=nkVm2It5#l@|bcR6cHbD;avlPQ5id=j}k?95c^~>?ipPS`H^&yy6O7 z*)+k8s>Q6!8^?=H+`4T{V)yq~nx#If=V3N_K>!4Z*6)<+!9|n({Eqqip3!pq9i>xY zRRG+VJGa)uPhG?!Y6B112D9TBT^G{S^%xvjXaPMM_wq`Zcm6atD-K*z>iSrvHkDcy z9d9_I^R-pr+^-4Ve3SVzcmr1Ugde_pOnezFT)m##ecO`Xvfo2!!FeO@4&9{Ug>$_h z;V3dhjb`KXFmq?L3v`_NtnuGy*GY{FVY0p6=AcVXw}Mtt62+*>7Ky#9$#jE@xc5t) zMeSM;PT_8zsJ1=kxyaXh2bv*$BRZ7|RRcU%G9;G#@;Q&%>+cPd#5L-l5EF3U4Y6S??^sR|3&wf^9lmdbkFax40o zf*m0d)Uo=_hC*kGirTvvf`7jh2$kKAgyo*-mU^Mp(ZN98-`u*oGUX*ZEt6B?~bmLmvhfG%pxYjkn=xJz`3>@7Vm}$7A`vzAh~~!h4zyh z35CT>omb`u*`-!vZ+_zaZ3fEyu=Obh9h|~GQ#o0EQNpiEt@ko*DZdwA{@gM;>{!H7 zVDAsf!&+#TJ+M`|fI1S~HJ0BWR=|&W^KAW!+Grt}*8`Brc1nM@Lhs_4?`tSLHcQb9 zGBd?t^-W@raToYchxtHJv;5slJ^so88k?0LFXtdZNhYJ{?#yMg;?{TfpJkpIydF>^ z-E@3@E{rctW1*s1^nqKxNo*>(6@+$bc)bM$L>wFy4;lW@(Z}BJO=r&9JmKH5Uz*&i zoAOQNaMGwbQM)>Qwk40`dQoN0$Bd@Jn_YEFruVML$FX_D@zZu2%IhePW?j;HRmapB zwclhnUjC$V)D;M;o3E`)*a#9wDZ9^~(Mh}{fj%vL5Uk%It#)MX`SaN04QhI3hAv;b z|NHmfglVq@X7;{9DN0%!6-R*{bP(|pP9k>@!1!e&8h7FsB-AM zVYC(OY91R6U$QTb@(nAD(_uQzLmqsj4t@X~Saf|0Va>>D^L^iQdpJVsLPg+fo?zx& z=T8sgp$xx`O*x-Hv@=gXWNXs0J+<^CB82C(k@P3i4!*$TN^dXn&`gI*8}IwEo@fTzXM&rBV$y)mNFg8t!dC8wmmN}OyW5rf_1bdU!>hZs@Mv2cKybRiC z5g2$Z8M$dcN|hwCT2(=Uhu=d$&hH0MZV>s{iA2jE6l;smS?%BmhZBGpZZF-Zhsf;J zz<+Fh`U{2Z#&i~%VQcoLX0;476!NLh&+?hue6DSQ-0@7C%UlRi)Tj-!-1*W?>zJsZ zfVl1#LsAQ&mUOklA^sP-6od{cjVmB>lrd5BC}T04ZmXX9p2e7pz1@tezu|la<83QHWaQJ-!G4SDUjI`7YU!(gmLM8VFSj0-``IMXNQicez4jd$&k!@o zrklEnqDZMLNUU}^CsT#qe@pEB=e`6)^!lNS&XzA4v;-7T7m8hZ%ART0s0i0im-&}FWc64vL_#_8x=ZU$aKEjL^ana)&qn#+S$1I0pJnGcV$ ziCOtGu!&XG1hX02+Fph(qDNs|YsgiHi7M!FYJ~QFok`h4$Zu1Y_R)_Up_=u0WaY!Eo8)Xrf4zyG8SjJp}%)jmb;qlteB4TUA3&8le9)zZ>Z zBmC}q;O+(yb4X&?N2}QO5xc`rp{2HnN)hK?lL#d;8$wuZzbXCmO`k0o$jgPds`egg z2$gZ%l*7%CKMWwYGh{v|3j8Q;<`pkK>LfYXJc~v`2sVJ@tN4PuGc&QGsP}5}=Fmpv$)X{5OVV#M zOd!nPvR)FFH{!1)5acdGGiXltsidsRA_{q@7Urt3@y0o-$9iv1+qGQVUy$#OME=DZ zK*{Pv(dXOu>cM=hZpMBwF84NgsYlQv2h)Q_!9H`-99k@Xvg88NU)l!{#xs>>2{%!? z%u;qcc@vwX&%7YvmUN2!v-LyB0pO0=0S4WSyKUp2+Lcliz42f2j`axg(HI?mu(Xzg zlc`*ZTd0D5+C}oiF6E!GXL-y;x^%x=f78^plfQ9;-E;A)-S%{9?ED9uBXypyFI*Hb;ugYzGHh&xW&BY zY#^6^Swv1ia~!2DQ~0o)pZUQLp;2RW!|(Y<1hdPf_(^P3;VR-Yt%O8|e1Xw;#n8oe z1m=_mL+4)`2MHI)n=U$B_A2>*xw?idO|V{VhIZ74VdRjZCro$`g?U>tL!=4uS}xL8 zuBzMm%WwXwID!1!o3_8j@=ywFSc>^0tXjQ{L}}cvs+yJ8?KUx+Yk+;8?Ry?vB?4H( zF)>bz{H1`pv}XlVLwg~XVR&5{EHJ~mZkNxeLJR%99ADH z%yQ14@=Nl#V#A0vFXyLy%*;9{5oT>4%00B6VW!PWZ2!|{k+3?Nc0yP~?U)@j0j~+* zjc2aqaM9I;+m-w1yD#5M?w9X-*uQa*FI#TTe#a@WZLOTg)#&t3b+cYI-JFFXB-rvv znS}tD!zm6EzQ1k4AVyIOiU$qh{_P6SJzsKRqK^J{fu_+m#?_(B8Hg?{2+=K|Kj#t$;+bm>C+L zk|i&N)_!|IKN^hnG#>C=X*~M(?xBADS1yjOF6Eg17;O1f#Sj+q5DfPnd2{X8jhpa8?AtxLQ|<4;>eJWxGgTzs-}qMVP?N zrGKm-3u;=KZ?%BM|LNICN)nXjx9kyM%nIuE{=IE}j&m~2GaexhkKgTgU2Rn?`uo=*wuM=q z;7&QMEDhsOnRWk)jUg$j4L5Dge@ikJUlSn9^@cH8wl^0S`Au^^G0tN~{C(gXGnz%8i}I}TmErghks z)-a81Wn(K$ehD0QEg8x0axs!S6p{pa?8EbsX4R`_+{;9U!O5EUG7!o**_USU%AD&x zGb(mpPrj=vB`5J6QC%6Ef1-h9uVeq~rz>i*JdWk!_@LpDIWg{iSvEhIXs`x~uwTEH z8w5icy{4|`!stK&ZAU+A{#7Z--(_&tYSk1ujw^CF-M^@v&v!_Aku@Ryz zuzPAC{XvG&*7Eq$RB~tyY~E3qK_|@tuy;#=1|)7eI`5T7eXd!AWV|@3fIqvKJG*oy z-L*ky=m^(#i=Po?cS9ApvHUR8k!!4|@I3L@O8m*(nFu%INm;=a`GkIoG-=e|Db%Ei ziOI$5>`0=fV#PaepMutlBlo%m0wG!*eeV$R(*XSK&%5EV8iRxShwbL^ijK{9IJe3C z3oo5^o5gHS1iT)4a#k?2{E4vwfpO|!a1i~TCseAI{FP+7F3wqI5Wo*hkN9xFVpz;| z>0pChDrWWUcIJw(!kbe1Q$^}&Rqy2kN5;ZbL&8*LuilaP^=}VMD7&RM3L~i5p##1{ z`INliOCouWI7C`gNM?f5(>&^jAwANC6|vi0>#m*Y%n--n%JH>zr)-m3{RKUL(c5i} zN7Q-@t;BC;;I}g(MJ+YbX7~GWoP}bMcGS0i4zCDpVnh~J-k4E{wRbp>KT1~|SGFZ$R|}O}&EeUgNk=G#f~X=9xFF{Wnex0F7nnA&d3thvxi*M{#|S+M1%iMP%a&dl50 z&_JzPlcFYeX`zvOQpVezesLz4g&{%C%=}jw|@+m;?i zO#8MrYcZTKSlk@8!@%D(ujJ}Mwp^!s^R`;fL*;IEwc~v+@>GSA54Vv3ek9T(wAbBOxf+mlbvD# zdM)YT*L2W3mPVRIz zHR4iTdSf#i1Syjrpr&Gl7(sbbT_a#1Ir=8)i3VuwRi|7wAV#EW0WMz-$%LQ~$YnGh zbd9(=xP))gJGSD%D;^2>2SLKX|65EpQ%KFmjnSey1;Ywe8UiKILB3(sAz?>X8Yagq zVJYiayNM_>1s9i%`LiTJQ{(}d#Yem4CceM_}0ke3AK96GvR#bKKU%iZP5oTtdg7=DIG8_#e1thM-|Nr(d&`1k#3p-n)ovUUpz}$fKf}ID ziqnqa<)-sPLm$HrfEJ(dGZ1ttHGo-p$?Y5+$63kt3HeK_G~~L{ zkU(r>zpjE}0p>LIGnIZ507)+`cP3MD~4EP_ii_Gc*v znx=-Wf#VZ)jt(C}q<=4odf5?=&VH$-6;^iOo13)U!sE^veR_CfhGU|ML>s(}DEi=X{pcMyj9e-lP@EGfle*+R8aSFbI8mjTQ-ZNb|7yB@O&gANJzQtb zk~fr+>Z#l6d8|Ik{xTB<&QG`RS?*}FGX6Xj{4_ryM`d29s`Bfq8J~<3y2F697-1_CjJFO2ID5S@PO2prF{o5A%@XxRf1<&~c)KQ6L_laJeb-RO8KvRUtpvHo2!o}O8B%cD8O>ew5HD?>ybPgKW z>EFh!VtQ;_K)R)H3yU;??dTX-E?CZEnjj~yVuk)^*f7!+6Q`>vfL=+K6ISIl$by~tW za6%fii+K*^hRtqvtydKlTxzQ2SbdV7ujPamFNg9(KX)7DEu#T#>a+OL|NHo?0e^vL z5H^43&*pO~R!{{>+7FZ}O7f$*5Kgbts;|pxU7Hp-E3lqB%?44@FpSsna~VY#qK@U- z?sMV*ZIFR}RPcy`&p%K7d2MdJU*jGP)eZoo`MwibgvFnC-*%@vy73scw*3K+@++7k z=3N%0JP>p~LYeJD9z*3H&Tk9vaV8vGS`5`;!}Ow}MtEby@zeHw;BXLb?&tu&Mt<}@ zz=<75$XBCXq-LFZ{z_bJm&GHg zp*1LZ=9Wok2ycg&?md-y)+wF#zRf}XyG@b`<|2WvI}zTjMEpj5=F)!@)L+u$D9a~O zQyk^3^W+cL9P{aMp@Rz0*qSxLO3{@7)84|xChwWvdR1<#)Olp!ma zxY1+ZCG^cK8^&~5M>`OJMmJO+`>lHGZzR;N4j*s#sEw)( zw>n)yQ><=EYdgVd{I+AgfriF#O1aUr$`DF2d&}h6ofX_>1Ay*WtF9*Eb5gFlm$3)$ zg||1{&VamJV!Jd%Nm!^}Gq? z&!H*BJ?ttRw|fod`LHzRZ1MpNgycPSdMqay3f(^evuGN93nF=);>EJJbi+cIwCA!@ z=paFKU6HlUiZVBNeqqNJ*$$a$L z3?&Z(Pv!+9fP;DCU5zqwG%tipER?Tk|4o5Gk0Saj(cM+iqLyOKS2LM;2kxic7o+F` zI&z+a3q;%KN=+5RHsjmD4$GbEV5En*#kDkoGof6OnnbQC*%GFwHys2zDEh7 zk;S~=qocCb&-gyd*kT|At4$t=e&`XDMQnHJ29p?;r%2N`K=54^8gu}i!T~SH#oe@> zq2IXpUoNg-Ifv_o#XP^k)~y?)bFNZXK6t>$Fw2dMP)TgYM+p$EPH-bG)48I^|0#JK@D>87~qkxrgBR z0cDm)ssn4SCS+hr_6Q7ms*m46X_d11Qp-Rw;%f!E5Jd`0#k*T6M`pWoLW}UbbG@@P zKGWPKG!h#=GGHI2_+Bbmf}-YAciX!1a|S=se~|DNnJHEw?_YYingjFe9qs?rHyX`e zzS2SihL}2sNga1#HpL9;+O2BsFHSJNS|;_!|bfUq@*POo-2tuY4=Bd=QTIQ zyXr$O_$w!rEWEsvTsvg@oxu*+WfKqueSF@raz-`}!iPS^Cb|?pz?!id zUm#_64ZS6QU=8FpgO9)g)WW*R>}uVmysDsaj7>0jE&I{K2912Mmv>!S_cu#RXOpnC zweb-AJd#Hj>#`_{vm^foCV94)=rK5}A0e|~Cc6@)RpIV*|3Y}yvudVhU-z=o(vkf3 zJAp^Uctb#%~BGZ2dg3 z!qALipOS&tZS=OmwmNEXb%MPhI2~=odOHlbjt0ln9+S^?tE}b1NmuR+F4VA?#lEhP zMa(sWg$|`ysb>8FSNF2bYh33lELPrjAOjuCun9a5xPgzrMQuzWwkYloBG{|Sc&Y4O z4|7ptYB8k>Ew7edi%7cYK!amYa2A;~-9@ zio@Uso6c;&C#UeTcr~%JbUtQIQgpzrBZQx0^(Q%|QQNpOo0U(|x2rzhPa@+<4fv{o zlK#rwFBuv9m85Y&MJyJ3gY+@ZRpO@STBjyT^?m7v4Zo0To=yco<|nW2giYL45|nl3 zON#G7q&ujdi6;fhp1HoV3?i{kGR@3S$I(rHm{2TK>9sK$BPhGy^pi(rG^WtZ9{QsH z$r=$Z1IgV4921L|mlqS0j+Y@ixXq+_CkyLk8Q3-SdJdoCInF-{bVE#wG!Rqcdc~K`re}nxC`Plfx?0t1mJlaG zL^BmVKu;7#^TRAXpD2q=dXYl3U=%Uu0(Uj=0JK5W{)~^pxkq>H=o54fh95zO+#4Yi zC8tX?6s~l=O;2+z(TicNS}W_<(ZYp>TRK0qw&~dFjqTZ>K>*N}gKo?6wY|l5qs7Dq z280N=O~)&X?w7a+zAlb!?uvF6})0dQ`X!EmDOS$!-Yps37{mA{QKFGRRC z(jbc$D&57jB{u0%F7GTav!+E7O|jZP$mY7>4UwXQG#icu&KIX9O!#$J8S~SgE;Zj# zsiWb2mltAZ1>%rD9iQOamJke5;n*B^>U2gUi07%10v7&TbLG344peUzkB2c)*87?GBdp2lSg^cIOpMY6 zvKawK%^jW#?Da{2sGYv~0#?9yicOiqF)*_r1#1F^1^iNMWo4xuUR>m@_moZhM-@Bp zmI@}Z*S%4Awj9gE=lW)4diU$dA z|6Ps+M87^PNpFrK*<)N^Ev%qLFzN7EcaegwvrQGj*WX{lw&{XZtk?CZ0AquyB9v-%Z1;FEQ{tR)V3l9p%~TL$Xo* zi0(0Yt6d?bz=Wp*TR5J0`s0+Z{Oec?s0+GGI}W9bI}1#CF6X_@C+m4EgxQfNac`uv zi~b8YqtG0pFf_I<>c0f(SGP(o@}l3U_rkwN@7#>XYT+n7MGu?eWu!drz&RjR?ktT7 z{fTD!&GA4^Lie4|ss{LrHg4u7_2{lnr>H+hPuw>%W4$-gOEWq%25h+_WPg9x??O8@ zSdLt?_4}6M7Kks4*(n}mKr|J^<@OEN`A44#UaDv9Z~rf`_VWy)T-yuuWbN*d*G5W# zPNr_j6`PXrcb|fe%1MH;3Y%cF7%X)%_V$_|DCu?BBUg6*B{zBGN7=~xg^MbjF>dcT z;5vI=J$WqrIKs&r+47*VOeBqun>@`bK!C8a@Ro=$-ME*nkO&AKyngLtJ0aZ#F_xufWV+Fsv|%s%2RX#Ksk@~dmJ<~;j?P_1+0pLU{#zDHsbN74Lm z>);>7ohc&9Q3@_I$O;}xJP=C_PQ;150BAtL7dyVBp2KiAv|c63Cha_2?C)M zkN%vz8fwb9Pw@^?tVX_~@Tq%wL)k^P^c4ejFEMvnh@hPX-S!kqmiFU)0kepjmp(MLH#B9liN|446n9amModwP6^U>g~`XQ41s4uS}E! zmE^G=i?rMUQ@NCsLkyFteAjCVh~jQ(niUd~n_*WvyA?{=?;CAL2}4OT01cY;X^EK= z1*##PNV()h^_L0#hbz`yJ*6cZoq|0)ZqZOg@@RquhSa$7^+jeGw`kk%N{x4YXmmUEF6@6P4o%Do#?%O zog{A7xDgYuzi_*4V90%0#Bv`zUj1L_S|XcYQ@e^pyq#UP7sOF}7p6=ROSs zwnNKgG>XxfD>E)x{6=52wF?8Dg+07xyRrfe$jcGN-V4Le8Jl1nRbTyJLwCN2{vU^R z53t1@;ojC}Vo8d{4wbf@(nbB2?b(F`O?MrBe_k4y5L)88E}$zdtAG@1WK|8s=f4{0 zQ~6^M>A>quzJ=Ncu>xDBUhlG>FZbn@{+ImBX9Vcc22PU$Wl8;e(!aXEh;=&vidA1s z8frKwl^Yd;fX>RRdtOt@A=4wVT*s5w?b5CyF27R3xTR1;FQ{95*+U;O=gknycQz(f zN;O}ghEM`ON)kU^Eurb>S&!#Z{4Im=AQA2=jDpVNC$q6Zex6FFJ=#H>T-(w=;`JQ& zMieVjLuNPiHlkmIei@fnr0wtZHFuZtJPGUn+~568{;}X7F5-wL#P8IilE{#b{(d&B z>vy)o1KlU&nE+N^2){Mp&@4ku&y)?VWfxCGTN+Kbr7W!^P^2qYQv|D*YPq;h8h9>E z2qizb5bipwL+oqY_TK!?6|z&I@vIuoE$e9heU%%k6|8=;Sbb{6iFx%gF(mY;@>KeR zQDZ!1WGZ{o>tKr@DgoV}ag1fb&ww@fBnyR&^^X8;NA>~j%0O!$A@>Hm{c7La)L4{k>YlmhS zz72SX#W*ui-MtW z>!9^#290Zv@N2vCPmB$J3N|mOz<Bt8vo`BF{5$XY2z|DNbzda=O^LuUgqrU zceVNVkG~NtZ=@~hYgx7Eg6w&> zK5Ek($Il@0;>zy&qHp=BWVf63X9*Dp{H|Mtg+mtA693xa`bkew$hW3lOeH5oRB_?e z|1_T$j)5R`j+Sdvu6%f(pufLBjI*NHPRN?s<4u>x_ZCnk5f-=8ucO_b5}_|SzY!ue zU;J)@&d2#p7-i7%8rE}$F(hDca_uet6zrN6U}=u-&t>hu^L=yt{k>6aC#jWE=Zb-{ z8&A|(bp+-R=bJ^7S+C2FkU*T*e5;=;bCw@0uptbBJ2z5@Yvdw|W|S8MB}3|NGd6i6 zpgnZJ^1rg0IgmtzbiqLu1x5LW7ubA^cRVuU-M58r zqan6qekMeqJM%bwl3eUYl+HQQO1%JKbf3>XHXqanTP$=J6^d1Q+_^g2<6D`Ok1Wow z=rJ?Ed&!vrsWU17R=^u1L$yqb>_Vo{*B}|Mc}yM+NvU3AeaK_sU6+051I_B?@doi` zspYlF<^(QOvvqrgR!+*|j0Vy?pIuEFTJ5?3>sojpnilQ2&rEaeLrX0a!ycga&S`{Z zI3^-1C=idswXN3E4BM@pCaYWd9}9>SNT zP;DLoiPRv%l>d5Eshb-MV zxORGK#qc$Ci`W$Pfc865St-ts5OeW>E#jwf5s>gA`59mK5USV3H3zApm78ky&`V`= zXCA-ZH(1}!s4(L86nI{O{DBk1)ei^2_M353+qSLr%6%~0RYD~^PoMDBpo_SY(du2~-ok}A7u7I2=x zk}EcyeO#dzB7;723rkzh+P^F|WYU%$%DC=3sS7=-Aui1Yqz$?zR6jU1KOg@VQo!7@ z>$#!9JG*(!vL5RCCy|f0o*>2A;jqCFz1~4wYw4^!W(t_Clu0dQA38(yDxJMD#Hh*J zrQinIu(rt%|F7@k3)jpKhHQ;*9XGlDzgk5WG;0-kByGR$lc5q=eQSOoXKFbUXIKd! zm;0jySb!=d6wD;%p``~i`_jJqatr+y(??u2+>uR=h(XQ`OvxoT_Lg&i3y5~NtG=eb z!@m<+Wk3aPa7~t6kI;ca!Ca($58)4fFZb)bh$d{}MXblu7u(Nv@Nv!Y=j@!dHF``crQWdkWKG+xyVt zTs-`Yeq<&iC!|uAON55t_$HEaoO%|t;4FM1nOI#{9r>z7wN784%w(}@$U*!b<`heO z_^Gxsn;`Yn>_<$M2NHt`zp+Z-o#ZLj?<=+?LU_7`szhCGU? z0R}nM-3=iyzxi+MK-5@3nafne8l))DqLr5V3*dHUs`~iYSQrRg5-W?JIz8IxL~Cu} zvPO3IhnM?4!t8dY|IQ^GV;Ok6z9RJ*WtLeevmP5~LuaX}ZA8uwq%aD=R;Z=jf6w<4 zZfbO+DQY~HB5+#~c2!J@RY`uFtN=%LMrzowLENKadJrY0P3k-WmIpFx(LZ*fRu_aj zI%nY^@t#mwy=B%TO#S~FP+Fy{w?F8Kx2EK|1}fB$-JTCw;+n~VuCWBd`%w< zUeF0xE<*!lwJHN$C(ZSgJrx1XSK)*phNa7Af>@H42WZNE5f&D^YyRGwqm|2jsbaMa z5a!TfP*3Z`x=lna^)`Ep#k-CKq>=a$xmu-)UzHlx6xuadkksgJyFd1BXbi69o5t=W z=yI{`_qEqRV{iSGIw)1S15d`oL!+B@pZm$6#dB!WAParA>n)kPFmIRe43`Ta+i3=e zMWJ}UGIi8r17xt&k`~ZZ{{!NkEKmphY{A~JYDJ`%J$Swoz{D=aEqL+{k=KiA0aHPL z;cEU79iW+Ahf7r z&Ke+-M-ba)Ff*RRb#u1SRG6wYAKs5)rb-9_7@&&P;`!3q_r0q$Cy=)SYo65pKP`nH z9r0IM>4sNBY2&r}PoC5*JtOO}d%fNmo=qE$Q@kMrxnp98OA13D#NJ=-oIhD&&G^BXHU$PowDd7pN2p#>);yb@l?GD&U%!)>pcm1kn$fk^#F}T%-28K^n7O!u6^^Kg zR9di#{$Mj!5^4R^YOXBwPVSh_5HHg+X0_bA2VcJ5qy8bnWcFw53i)YS?~ACxk_Cqe z{P*FKPl-B~ye8~<5sLt{Fj zsArDt)5o@#EmOw&UKOzFUGzZmv zFXst_z!P(P9yJ6=+3kg)^q<#hKcBJ223d^1qhpxW8=sbdpU5@2FI=@~a@^VdKHbP@ zdytl3?QmR~%_lB$tW^CZeP;9!zep|gPIG%y-Oy%$KW%MbQi=5iJ8twB3;BYT!#A>* z=+^L4GPI+lzUm&qw{yI8`?k|eTIx*4J=O3t0$QKt@=P1s+Ep=Gkc~^VF1w#Ze4JB6 zw(3lOP&yg!;RvzPr@}&w)Oh#wbE@%~0RL193JR{3S3GlEuIIG`SyeA5;2g7$M|HW+ zP)*xd`lWLnlh1y6mG5^c60h-OM)O6lo@>vfm}Rdz2i$K zj?lk%n^)~W#@&!a8VkBPp*r90F80vn(9Y(Z$)ot_|0{GUrC#ZnL9TH zjuN?wo$FWMRlwFBNa;qbq7$rjPKg@j)=(NS5oC!6_D9Z(pXXP?4rE1-riJc1r6?`a zC`;luDF>xdz30fk+9F1h^Ln1v#g8DtoJD`_^P}&MQ%Qa^z{+*&U@O8Ki|7$KjjO&# zb@`~+^HtvRuy+d9x+G+Q-*rBOdorRS6O)mV{9COqmMCamV=jtjiO5Q2-`@`$*jf?O0?|XTDV}8(S z$Zc}Ee5L8$#S`sNh9zRzbrF&Rx4}l(^xJHReR~}IbB^mwp>FsaE$j}y#u5GNi-A+yNH`jE^dzrNUCihkHDIcI$CVwZP7RT>8;KD*#n5Vg-(d6G$<-Hvp4VK6UPVLRJJvG0tL>0d zd3WNHZcm|JdJFbTw+^n*w2>96c)Us%DtGSd>19Ed@!`FX%B>%i!a6EEHhhL2J^Jg# zKdeGV|I!^~PK?lBE>5?gDcc+g%#+!R$X|LS@%1b_+S43CPHB$U?%tx!fUs|D zV)vcOEA$-OWgd@;%gJx&Ms)u)fP=S?|M6SL6M6IDI-|^e@d4ZCkgylX(k)TPZ+GT6 zf`dx`@ZrPt;v%obqBW;(r+$6xZu_>oo?e{k&&VXy@Oka5cf$5KLB?q&In;C0zS4(* zL-Ia|UEZPkmuXP0cXVaxtU)q*7BKD4^%ekEmt%>LBZN&<$0 znc0#SAC}Unt)Aq*+Dq%t&aZ5(s+yF_J<*}HjcWDw(Av>xi)gsTt>9-7B4zEsjf^E~ zB^T{Bl--u`-4cFx%vmf(@Uq6eiAPL-HV-)!nk&LN-1_SDbrI`65vXWWk#hdsLN8dJ z2x^k)7bo>w3a$Ik%=ID{orVrwR9bS?b(n1G94K*cf)uo6$0s$^M5E@c*=yc`rlM>> z*u3Qw1QK_kn9sF8LBGP?#6t@~=s$*C|2Bq0EzVdbsr1qLP=(d303OHgKrZHj&`xTH zO}Qj{nf$(W_DdWqarxpd?0MgdWVoiSEB#gX3rK}kTJ<5nOVuy_O3y!opMUQ2zEyp} zno<$+=3CU75WASIp8jDoz!!D4aVSAV-bvbXBz$M z(*I7<#i7s4g?Z092-r^fKAtr{c ze~?5fH%PlAP7en4;YMROPfq3{4$`8CoY+-U>$fl8_9pzWWk@*GtoY-}haB0n3|HGo zRk<}E1S8}dQx5?&AG7+ZXm|TEu!)#8v3pHQ5nE+dtCS+ zvf!0}Up+c1_ru-p$0v}&T_~EMzWDY+3wHJ+hy0ud>}schsczZN<(UY0NU=RtwHuh& z)92k#$;H->%an`*2_EPl4fDs)87jS$%AVgOZg_E`4DKuW8XCi$%i7;ABka9AG#Aga zzjL3nbRKbi39`(UwCj_Y&FFX7Pr^fta)|a!V_~R>YA82B=4PT|FH` zf5L4unnoz!Xhqa^PADN6>qM0t?x41K< zp!(ED`j|QG=U-{+gElu9POb)=#Uhv14kPbAi1xFtk+&r|E+=-i+aa4(Fe_k%W;kMq zIA%eax$;rs&sk1%U7BM?K;e<_N6RT@#ZO6rDhr^2q@2-OG8- zXU{0J29m1#3q;Kb@-pgI#RHH1t2v#o;*W1XzP)@(PBPowNUfi8iT|(JNT!OlQDFs( z1^owIwWuH7Gbw4>@AsR{M;Q7gQHCzx{eOFTHcuYm2;fD{|<=*;aO!)e#T2)#YWC z?cNR{$(5FCvO#Dn{(z4i?Po9ZuGK!NH#6SJRj}b;|IJL&dhOoyeCFB8rP*7jbW@P> z%@dEX`iOUldi3E9tV>jR{);x28S4e$VI%aMqW~nm*4Wg10|1ZlXmACuS2!>jNM@#9nTGhFW0)@^SGHw#i9&y&b;J5AWQ?U9?%9?A^*5c| zDh*pB7`fh4cANGZg!Zz#I1aWiY`QDMPfr;K!4#xSRg+EEGixiakHGZ=a#Bgs^aeK1 zc<$p>Q|3gv;T%Tt=?aoVnOE}A3FKyNh{AVb?%eP09EInlY+~{M-OqhMPa}k|j~~ws zdhg6hE)r%VHJm{_N60-ga38xe`xH< z$%MWstcStxh%@_MMvhAKl3eo3|H$sNo+8%fGX1Le7w0(B<{={qR>b>Lxlj#38Ro(ecQt&1DfG1gbsx_1b6TqD#r1vwOFQ}U*9sl-%By&Fc`N{9w3}0uW_^&+QAMc7ScT0}mj+EiDJ7U+_S@3(w{rXSo z`!1Vo#4fh$sTLmNEgvwUH%kqR^Gh$iUkjcN&CNZ##Z2>9zdEEde%)ZfQS;*S?p8LJ zTOaQo6J(9LYw}*d+S9Fh7dG^O=MW<2ZOdNvA{;?pKp{~}6KQM32}nP4Ftl&p?DxKY znsN>wb;|RgAS9KsDshqz!p^C*0STR9E)s3uZ!VJF*QX6+gtBpMNaxkbSRN(qFOLIY zaWqh+w1ub|5!BtRQqGx8vO8A9q5VGJjJCsXILku6b+98GFYIcMFx)owD2v8F>fT}b zq{7PPZIJw(ze9yX^W9J)r}oIfcDAOQ*7sC?7diOIDTgkpMo?1iup?iCZQ&vRj8Id`Py?jH%W1yZ)4qi z(O?PTvmtw{ZdE6RXw2Q5%G_*^KH;X_diQ<%Tv1v0w$krCjkX~VzMOLO>YlAb7w6$g zdnx?*SqKUd8>{ZufQ470h)y7eDmh_@1qNLh_}QbQR5)6zRf7 zcjEC1%);o+HBZYYIDCZz*~+1YnM{t%9xq`Rx7j8Tb_ zMBUOUv*Rrcw;%Sj9(_>%ZqdePnI^L!Pmm`q7N z<(G1P?B87Ttolf^iK%sTs!R7%Czn?(&Ouc0I21G_+tJTg?H0m3IUD0y1y0ZjTc1XK zB)t9xjry^Ini>U_Xb~mBidA*LVeFSg>}>OwrTw4P)Zdi6*=TE1AB2+LQu6j}*}ysk zx-CFdUlBWjY}GrR?Y8xm<_bXH$v%8~H<)O)(JsqINxHU15gS@~^JdcNzH9TYbJahk z({uhqz28(ouY=fY)`=cO{C>Avc#9$)e<8Qki$1E}KhYn*YNqzR_r}F-+Q*?Pw2LqG zYo~*gBK9vMAgPEgnZAU63iyYiU$a+^6`&#)cj!eT`LC4=<8GniieO7C$^`>gq^T;s zbR)GN^?%zSL^#~?>F3&XyJE6J@Q+P5S<>QlQE~BwC3gvS4HXrYn&!}f`vwMrwY?4+ zH{ib>Ja}+I;n=}ir?a9gbNBQ$(xaozP3iU``?9rABmDKkM03n7lZ9RQz4P~{+c*BU z`Dg#d_(v5xqL7-zYkPmGo$c5D$KCMZjj)aLtx-J1IkdwnLbxHAkig4+C5Ha4y0$6B zQ*hu+*bC2F$!eV)zggA=0=xU-@NqQSIgO&vH(V>;=gX^e&yAk>=TT?JeRobq#Nj~z zN6n6>$aa5v9YO1j(hZ|GKh+6drJDS@XELrk;AoKpdlJNvSHy3R+_`8HdzcV~)@X5T zJWB8tzFL_7H8f}-C?L>T_nJraNe5prv(P_au+y`%heW?-->h_`ds71Znuy1`m33eK z`EfB})1NIM&x*)1IDwKppn`7LbW;fBM5&MYCHDsp!q44_ja*v!e@uOMAeDXp|8)?R zkP+EJQb;nh?}|vIy3Nd#J+t>|+9QQBE1~SYIVVDcWba)fdyixM-q+Fn{Jz&8Pxs@T zb6wYGz4!a|;*o4llDqBd>gru(G`WWhJjpgSFMNDf^v;HSoRrh>k+6fv;oJFsF!+aB z9m$e5-d7zges^5)n>+Ynes`B`rrrIWXINKd1a-FNzfScxWxYHm#%mt+gPPy31t|M2 zH|oePUKP7~0eStNs05e2RDx4+nc63+0-2JiqbAE>x;D$N?x<=omQNu=!C|dkAIFSoo+5sFuDJFuljrMV))A9*P_zg z(*h8~Nr?PN`-^c7*7=_i&@M~2bH3v!5Hf%u4DNy>(7lFxUc6h8lL>(vhz#BOo!}hK zrylpIo<8z&1c%%TY&K1_nCYt>3oGj?v=mHd6@EYLco(^^S1WQ`)i|owlyLyv!;vY6 z?>)d@XY%f=7G&rS{J~N^J(sxhJ4aw}sT8^ZiWZZ;qt@8QSyfi;^jg~KTd(AKR5yLz zt*d;fiti{I^b-8=La90KUflT8JwJd)=6#nq-MsdJITC#Ag^91(%KhEimqo=;3mh&k zh1LTRZ;Nbu&qF#`?eLR}-jDqayQ8Noq`_WUg#rd^DE8l4ip5>qV4D1NGS;B&mp>0Q znIEzgLzW)cB<*RHY4UZTFT}6dTVu%Mr5|#>yw*oO@q-WP zCHsdiAw42KDs-x=KD=x(Yda5DrFc_)Om1o4S=)^>JLE8qn56rq{A3|tuz7R{ad>Y7 zkMp{v);)W!FE=eg9#uzhy_TyHxpV{db=N$y#kW}xKXF0z1wcN8oH=u*;G8tq-oH9J z)6ntM4l&_Z_v68Iqmbf8%FmiULp1*LJhL_DblB#fuhsqW8OtBPs;2GG-OA(TEsv^? z5!UVneJKV5Qb%4b2*@XH`=`?UR-uX)yz=}Ea*gy{r+xkU^&tmiWH)4` zHZ(}_-(rL)9mSCQiBo^pZjLsk6aAFH0*|^oPX5tRR?~WPqhc&UrQ%Sv2o5P5JvgMj zYj3`DME<)T{oPA<>zh(#oTB<>2g2rVP){FzmD?P`e^&SD+HBU<3LRqZtPX{1wGStY zq>f1C)DV7hXD;OOcE&(7o;agO-*~(`Ln@fHvx|{g#XIXcm2=$Nl)6$gd3Dk|o?xPN zar#rb`_74tbB9dOpM4hOB*8z^?3VO#RVS9CL|!uJ-u|f6<5%t5u5`1qse?M6 zOWoU$#p!LmkNz5VHL>AbvIXSA6z*ZuaYz zzlMTk1e~olsCw?(btiB+Cd>P}^jW3fGgDCRW2Dl02AxLe zOIjZBdn)PYp#E;!AP0vV%SuF`=u15i*4#mJW}mNY~>T* zUjP=)&w=F%&$XMD=RKJ15kKF0#_NQ?)mBjZ1PrrEA8KmGgI{LP;?fiDUyV^F`-!uM z())6C=tD(#Fp)IZbV_4+mxuwi`#KK>@_NWP-RSv<%jGk!Z$J?+ONvixQMqU(EOpn} zIO+^yySp1V4)Zo_XLuTXx4m$t?5MBSJ2FOeuost${OuqnhmHu{@FaNttH+KVQ#HPx z{*giPerjr}p*?*_J<0JySf7#OIrhS;rgV7ptM|1eSg}Hkx>vsh08daw(h9DS$e)JX z4{UbL1M|j;)Ul%FitU`*&4KGL^a0Dd)G?7}!@kq!%c_Whal69!u&IaPijD64)nsMV z;DC#P9DV$UxT}QKX{H4gY;9{#PtPxj54Gz^aD>vX&ZzCaUyZ#patV=o0d?9rK}uur z!^lf)5YM8UZa;a1X;D=MnX!SCkIUOz^9kwhUACpiNwF`ws(#HcT9a>hSMkP;G2(9Z zU$9Odk|%ay!wvY4Kzj5A1k;5jzg#MIAqhpI2mt3(IgnOSA&q^8e5MFjx^(OS9=-~u zgM@?b{Y;EhLW9SCVnf48sMh)fgv!kO)2kITBB<~Zm=TC+70xH;M#oP#H)6QT8?tvf za=YbsIfR267zxM%ZJk$!f9ZYB|HZTv(6K}8(Xp)?0`{Ef@bi5(m(G?li&<(C7oLvs z7#{61f&-!VD<}|-{{N^N@eRP@SKr!#*gGl5Ax$ZOBq`SLAF6am zS@VkW`4QqiL%0G^|9FC2AQ}sG@xFPg)DO^^`FS`K$=h*>e>^Jg!#hak7{iLaU0rP* zzgz8A3DL;D#Zmccb*1Z8$t?u;Du%c_6S!LeYZ)Dvn8Mp%&mChv{-6Iod=N?DM^gZY zi@i6F9e(n&BFDTXDY5BTa!_6$@GpB ze;AU-i^hevEXOrkexnm6TUbtAVvD#Lc6(4IuP~_;mkTc{AcCs7{#EtuyNLYr1p$OD zDovg%x_ir|s)I#{1n*B+BV(5@vLIJRZvfX%;`}_Kpy`4HhLC&dDH}A>Hl2%0N`)7j z1`h*u6{H6zAQeqbR9j}W$k`X0#Qf_>?tnEC{#n(gQc~N#bCaefja^-&5L;!8FBh* z54eBp3dU&-sb~BVpo-@T!`6_<)QDfp80RaFUs-o{u=M=^+ zQ!+ab(F+J$wD|8j$Ev3xyW^-E&$+kJsDW`2(H1wzuKE#SQPP}E5k$Wa(+-gS2=63g@(V-XQPF&p4w0xF zR+GvZ(yJU?_Cy^$8*M7Q+XHbBOXzmLcBrf13hxiO2` z#Hc?B9=#FV>Njlt_w3N#RI#(x-(MS&jj0EF*ShVUssbp6B zvX5IE&CShT<6)B9td6Hj><2T@+_ZpB&WuZCM#dRmXwEo%_ZqTv#r$tvOXN#2xykaP z;Ba31-`C7hx^2f_Mn0kf!rI3#{C+KF$7SyKT0vhdxe5MM+WOQpOY??jX?!7wC=20-*zbT$%B!9%FK2bo<4e>@ z7D@Yr9Ney#9iYm7OCf8Mgc2h(=}XUd?FY17y-k$avAWS);hJe*wW!PvO=J4dx*ppf z!7Qo_XR25j^^NHy1O_bb?+Y7`sCvS&_+v3QovKP*dc}}NcFti`PMCb1ke0G#(k=9o zk6N33+U%?Pd;E0JW7l4%I&r_py$@Sfn~CpCjaZaodiW3nj(c0&@H@DEyqY;np!gX% z)t+wC^ire(3JA1}jfWXY?5(U?q0KT2%00A_qN!^s(<)FrKujOXRRe<7{0zkHFGS>#Gz1`6aPphRH=Q+%0_3(PK*o&t-P;IS= zJ^brweFVA5E1ft1@_?ap#b=S=W2o?qP_kf;l#~mrI?EDPGdpoH4jP0!7___yI%xIM zFGS0hIAo}NhfIzPAS0Gg17513*HkL%GG0uU<8n6CLAN#}i&sIOUX4OCnjargWL}Bj z_|uva09NgJ`5N$nhM{zmS>gIw0J05OfyVv~ucqdB$!Q4Jhz!j`i~9F?#4!_M3vz^+ zLN90nIH?L=b044ph~59GLd7Pf2?Y;YkQ{*ekY$P*q@dCq~qdJ!K?gBclLn@v@yu_&RT!oy2`J`+D}@{N4tG9QylGZY}+`>;u{ z3qAR-Rzndlo*pu|GrN+d_TJAI<@ZMlKS>;qcQcWMD(|AXvT52p6b&KlOIs^Da~UqFR^=;y`gq(!UKs9gB7`S5iErE;bxDr+32beboG)gG3{fe1 zH(*9)9$W3LeU~=eO)t$_%jVy2o<-k@FJTsgl#guwPVR=9G&F`$o+HrhT6tu>#GdIB zCzs*9d-ot1@fN&Bk_*PL+W<1{u#j<$0iaj2gSs@_^0-yaw{t&<(YK)4W7u&^ZNC&P zub{%@S;R2s79;_u-}Bn8O`foCeTceJ8x6&}k$iVKbZvrUDt7#1ndg~Q37ab9V3U)0 zH4g7y-;r<%N9j9H6MlY{Xy4Pfi)sQ znFTK7ckdCc>iqkeiyzuRKonrgn(Vz=@A>{H&OFINFgq0uV5(p0-kTxSS=fK)f-jw2YB1dR6ncyo!= z%JnQnpdKHh7c;GWT+-c@W0?7blIag%(zZi|MBADLRA_>p)x31+5$La96**tOebds@ z`ylVTWjTU>z#?J$5)d7^*r6p$dMuE~a_fM}FPhw(BI{i{B@9|7fgOmhXJu5t*_=<* zO$d$G3>u|k+dpw}6{~H@Eh57$=MbNH1%;x+dsq3EkAWLe)@eLske%Y|&gy2#+_7=_#KXAG+Aesvibsp{qoL9pWow`Xo9x{V;NnW0|N)S52W=GzO8B7Xim z8q>Z4YHBZ?5A3gn%L6n}1^7sBetnBQMYT7#+c(*ovI>ACH_*f`V51{cobm=IPi})@ zu2^Bv-5Dj`FUQVv5$(Q5)8x%y1F&L&`6XTwkr`@1g~&@sL#r;y)Tioh&}`-K$*{ny za*TtqS{278`kV?sG;yV)l()!nRf1izAR>JnQ95PXgRmWvziT{fyJuMY9#bqI{@2y# zzs7s~#tXK_R!Ek$-`jBi`r>q)yl;ha7)x}t6A7ZpKNg-Tv?`Po-kP4)l-`OC3EOfw zHM=1K;`PUcM}Qg{{zOvxN6TtcVP;*@ve(BVyY#@#I%YdWV_v_iKyU}|d?rL5N_CDq zu`vs8MFZ$sgKn+Ya9zOKf)g)#L$LBpxslMfE47rumQdLN!7#hg;kA#$OH23B^h%tp z=Y5HQLx|!>$F>B;sH?cX^Q)Oc>sG|FQB6hJAqUryp6h*f=IIMruv2T>!dw+wdkVIPlW7LMTZMrIO&hu(tdUuPXi8JtYrx zAmsoVBXM?rgOetoT`TdIid#zy511Z|TcV?y)`}i#V218DH)ZBdS%i0ua74>T{4G@Gmqk5s)bErt0viB)hFBx74``_O$qfvmSym;6 ztmmBVq|uPUH~w88TfRO*LkqbHn2v{{kCS8VPEn$!SeHJ_%(_taGi!>pYR}p_(Wt@( z>Kjsn(>9resFg+ur@b1+#=Qu#O=JAE+P4^~sNFF#Kg-bG;yroCkE2^-ZyxPe_Q0Jq zU!o2vR8baWuS#~zozRtH>sswLPR=%kH_Ed;Rl4#%^iPg6wN^{U&EzY@t>$+I;PSfd z$Lt%;_79ot$i2n*2LURhDt+<&M)Py+l~?zEzu3uIQ;+|+98cLu(|O`j#qH!Xz-(sH zkY9F%rVLY-U+)t-EOXC4Q7pswe{LuP9~vkC&t!ICy=!flCtT{H@7Btfw)YUlFv$6p z5RNl;O=yUioSip;S4Un)dRWr;KWhFtHmFC29VbJ5lcQq7n2|c+^L+z+$aeV~xzz># zh+CdwJFlJ6lz2>cmJ%+B7Z?|J?t=1v$`(RCf+fXM2~FVC2%RzaO#a)$qv#&)=;(N{ zvWnssj68#RVq*(AG$pCQkv-HYOVlxu6c-P)Au}h*THQh)U*#rR6I_jYMuePs=TMgs zf96>;=W0SvcSOffbw=p=^K0|!O${YFxmV=~*=DPW^jBDt8t3$AH9Ktmt{)gg*hGz0 zvbX~nCD4(x`UsVw*Dssts!^B~Rf ztGYmL{&qJag+5G(5ivEr1E6(!?j1bY2EGY_ewBja_y$l2J58ef{bSl zR$$6L@}V){{U@0~O+|1UBu{?v9pXkaB$O%etOdQF{>R>+0B#6UVeVWP9XhU(Grl8b zU%TOVHi-*8Q&?=d`J3Xf&J?KZVDX{y)-&P9LSw{9)56nNoEifNRIgu3F;d|%6j)ZX z3CzgXHj~D`NAaf&I=GZ85gJ=t(7^)%Aq1)anARM$U(xio-OO_ByWMfDiZ2_n6e^P9 z2rG6la%Y95ecI50@*Q~(V(T;L;Ctq^6!UIU6oU`alZGjKv9E@}w0Unl72?P}E2u@zt?l^TG#YLID8h0EZ-!w-F@LYsB%E;G22*auwm4(vKd- z|J9ozqMy!a7NKBdXXrLtV!vh!;U$MWQov# zK3_{D0m{lXKFjBsZ-ss;(ko3Fff;=C6=v|ME#sfV{D|yMx%+CYqz>ym(_z(nC$H%c zgxmug3x%I8TVY!7#{}dU6vQ`Zbvape}i%@@Z!H z5plW6&f>{OJZfjWx?TQBq$UBKkhee+sV4#91z0lZ52lg$gBntOrRQ001X|!>GT_3} z!UnWP$A;o)m*7fEkYVVqL|wfC;z&c96R7u(;?h&tE2DV|jrqTBBR%_!9px=fp%U)L zOi1(62@gl+PJ@BH~n2LtmxE${0V|vilgW4qZM~GA10&4w?=wYeQ$osY2 zbQ#z_{A@5h3>nsV$Fgv>=2+^!M1=2MTg+w&9vb=h2=!iO!T7wd;9Uk`&KD}YE5LnX zcq?6_6NO5Xy$TX89`ZD8IW1=Bi+-l`8^As0K3tHU`RMYsxMlyH3o*~nIUpKG(KS-U zlN>=BsUGE;3S&&hy@L@_yq}N}83W}h^P1~VNg+sM-5EnZy;G@m*_RE?l)KTSlkch0HaFV!f2f<C@9R3&mbre_f9L7S z!aGC%q%!=r)UzgXTULF#rTdir3nO#8RDWF)e!5qNYc!utGqtn(#*2sdcGoL@#oS(j zx*mQgw0?q}{__WI-6 z!CyZVa_ZyL<$6>Da)tQl;`!MY(^Y#qs*=@`tNsix8Z=g6UJ}RmaDulW@-kL=G!uz{TF$Q)Jk4w+1gGD{+$2whedWv8NzH@%y# z0eSRn&80~r=FUV5&bLv4vBQwEMlVGt)G~<4&~seJIuLLcnPHJXL=diIh?0R-i&|#< zd|l7C<$N5<=IjW*x189OxYN{4o<>{3M_3*ETHEDFUrQlVk1zIpS@A+?l;x0%oS7&l z{G3XXf2GnfJU*M2^F}ztLue@$z}A(@a$0@c(w&gR)NJ1= z%&1I1K z1RwU%ftUi=Fhq_3x$bD~=Jma@SHO@Q%sjvRSt*%k8}(4&@=(kofq$4|_ce#&Kg&GO z8Qb6T?ctMfy=gstgDbRk#}X|`U;-3hAL;i$`32eqVmDWFtnx~D+I=5UqVro+=v>{A z*Sj}vE{oU>AqKaTdbR(PQ9oK?Xjdws1m%^5C}-mSNvs;xAC3LjKU;`)zzx^8nfn3MR#ua54gGM10T(|mq~v$ zzQ;#NTYl@aG%q2I{xFiD^w_~Ayz!JuX&Md8tsRA( zz;Y-=mHouNW@C7+DK$>-x*quqOy@F;Zb793D%Y}l$grfg2(@>)@aIu-lbp>5ZgPN;I|%Xl1^Gazo(mtQ!kc}M zp_UpPHsi}L?49v`%+g2f41(Xa=-xpyzswe*AL?Aji1Tq z3zFc&q3*riW)PC2j*)-{NP@=}>!$cOO0Q(Ly_4CNF*@}p?v8T5&i``dvg5Z=L-%fi znaG33`!-kAXd~6N9xxs1c)dbKF2x#Lc^2p?RaygLyRhD z<11we6}~mYaQL5<<9t+7y3&>zVm@ziX497qpF@UL>=Ib4#4DHrV*>wiH=#KpJTP{@ zKb33vaqY+4$1mO>C|xb+A1lafM$SHzn+O^7@RFwk%{t}kUt3p>eF%slKK1=KTYR@U zLmr?_9||`AReMA7&G;b$Yw1n=@cKts;=0BLvtt-PeOde!B8!v z2f}iZm=S~(TlaL_#c>;P^+D?V@=HQqQ8^nAx5r33-x{sy8QA$|MdB6#QHf?7)QXN z6~>PNXUoI2OiaHQgh?+lIj=5J#BX!b!?%7U!QKiFm=Zr!7r<-Ue$;`YydM#KwRami z@C{M`QHjVx<+R%*rGmfeo`*YtafttFJrer&O!A-oJG$`t$J7q=2IynCOpNADFTTN3 zVnyi?H@4`i@#Me*00nP-j8D$jij=0!ZzW2P9zI{hH7q zbTps(tR@^LD*^ zzGw(n5&B=mdxVJZg6_HCxxWokOu1Be)A`18_ga0rPIfPL>GE045m-AJz9~wfjb30F zb0agRUSU(*A577)^-~NWGho5Hi2$j&_FZ!}Lyy%Ip`^83A)1=vG0eBHj%{yV{{T8Q@s)grv@UYYAL~j9pv=B@j-1+Y=uHIj!_e(?%#&tu9 z#QM?v)7@V_i&W}(IBe)ucRB*!Aq?m&q|66bSh`)qm{f}ob(I`iNaCiG*pozc(@fMU zDtteSzU-{RJB!r+H6#Qx{dZJ@=NR@C>Y11aB;#WLc<=8)>f@T3bP&iZ(D}nTr8Oa^Ms(Y3t2kH*g!mPIVm4X^a1GS-r zuUcr|633?~zvx9nAO6`nB=2;iAGgCFGwCxC$}T-da7A&j&3=kK!=pv7PGxPY`rt_F#nG>?W*VhndQ)`BKtvU zU&yI+|3kt4&LYW^ufOg~1z-nE#}99(p*4@pqULwehN78|=JHowlA%+Ltr`+`yN7_NXt;(LROieOdpocg( zhZe{R6uJNyBL|rGrqJSfK}LZJr~!q#b3r=%=7M*5qwBg*VXSMQP>Rmq*gw=%c)Z0Obr1n>h)G;M{ip{J{~})XVd%@*j1>DG-Ke8c z=m5I2H0ZjTBn#0VQF{kpN04iWqa`K|XTPy}&K0aS${qH%r09j1&)j{!Y3a4)VF z4=UtJRY0KnJ%|RVzT~E(X2yxfeT0u9MI@;3Cn}ZILP!8AX^;szBMt7fBeu){>_)eo+>0R9!gbn0E>?>J}1QGzM9KvSU7lEodqdOi+fM0ug z-!Fi#`U!klLy%igrPvO@PT2s9V+++UgL`LHA&$}tNCRjCKD0psD*9HG2Eb8i{Y!?E zHm?AD%`7-1mJOlIUf>p<-1)tu^5^K*pxhBTz#SmAAwi|=Lw1n4iH?GNE|&%Q!r^gH z$$dEBSGm&0UZMMMC%2f@!42H+gjcG3&yf?Rs=8FKZB-A39ILNT)Y8v>QsGjpd%J(D z&|2yCj_aGg3|wO(MQq>N;)k_=G7lJRy+3e+*5=*~m0I(o+>v>g4&HtBrAg1v|M8*c zk*eQa2iGrH@Ok2lbE_VIDW4-qj|+?%I2$KVKhNO7j3iRH6Re|EdS$Xe&SJx-?vOh2 zj62&2EiNR?s?U;}U`*DmS6c&JGkGNB668xjXajha-oDlR+66FrWKif)lp1gGivP-$ z#R*B=1r)xwa65uPAdI6(>L_Tsh?rQ%pd^@4&zx(kQM2@1^~!rp8UE?c&xSW7 z-7~pbJa2ahovi5VO-44(UFB#CZ9*2329N}=TmZ}xUTt@{Y_RhtkisFzGIYW)g#t5T zO4Mio%SMKMRbsU8km(aZ9FD&YIU9`IBj6%jr@LmwHYy88W?&DF!(O!ZK?yJd10ibB zND1Hfm~&2MRf`b}LSYG^*+u63e13j@8Dz-EQLrME-eeJI2Nbk(49e~7v)MWFpyNDo zV_w+1_Ztx#hz&|U*k6ev4AF(jDN*@OU`4*R2+lD*Q#{tK(pgVFva8?c&5FW)Dfa4T z2Tt!@7z^OM&Kb9UtN0Z&30g4;i-in^*(Dm7b!N-0@ztQGX5$4Ew|5 z2dAxFKU+Hlg?w6kDp_?xe&r2KJzy3bhh=&xcCf1OoZaP5AT`(^>0xC6$EOD&ddz-=A(8v4$q&@${@^O25BWH;F@fJ z{;)BWma*RfC&v=jpz&Koz9q=5i$r#}7$xdlM4@TFOO1zK9KM1~7P0Snm&%B*f-b`s zwWpAekc1hwX8n#xY~sa?)L8cs>r@q|?6=kf9cp-NEHk5ekpx-~p_S0P8IlN-9uDua z{3zlD{chMKpf+W-hWb}|x%x~lX?-!Xpy~-G+OzkTZ%M8lgtHukBAhM)Oo8|i#C941 z%U}wI(Q9>7YHZ4Mgxz0(o5%_%kXu#I;i7ABTF?&`H^AQAlUe3w*ljKq@j+Qoi(g-Qb{c$O( zBY!iw(s`oSQhG9=`cqvdch0V+XZLin)=;tAXuf*NqRifOU)iskQ&El7D_ZPJs60m4 zBlS)rx7wkShKLcCWmGK<5V`L4&`OpJ^fLeg*J*9HZqqoNJmae5ukMx{_;SUS-hUn{ z@Pi$o7z^dIq}(Gpm;G+ep?A>{wXWoh%u{rqQ4yX$aiz2pFR^zS`o~{r*69PD_DKhCb|dWb`=slgNz0qgKZw;b7TeNcAs7U~E>`34jcXr1bQmlAHG z1o1?bep27r?#*a(6R9_}M~8@8y5(Y|ERr}Ye6)O)yxnd4c`)8t-u?!2s}(;GpU#Yc z@!OILk#c_8xP70%1*&1Zi#~q*xbYlF5r~X;D8=gVcJpv3{MGR3gU0B=-Ac0__eSse zmwF7{G zyfx4vfpc+0sK2Hoc4POCI;!hmOtvQ9qp|yUi)S65>{SXZgVRxGC6Oz(R2YBXdf(pl zCsw0Dgm2YG!%g>dOX+p?W=1cLQ=m|SphT{~^mcEg8gHeRLDkkcN@v*uXeo(>OC&{BF8+@puksz%f>?am@+gVkEJ_y5K)krexK!}P_f*) z(d=Kr=V_4rqmSFw_5lc+Wgj08K|hb*DT|qEOygAdIlK_3?PEg=qkMf42Lo-YEmEODLg-jN&AdUfiU}T=t(#oj6^yze5*x7-1 z$DD?#XhV#S`vy@~SD>NMuP>O9p_}pS?rbaHzKqLz)n{xZ4_EU{Cv|eusNU>mV5X`c z50*G4jI*eQ-JAoXIF)c4r~$ z%2%$8uk|}b0RNBx!2RVAA=m+-I0z-60Vod!fIujO6#wj9mL&Z%^ZA&qRBW47=>1nWeC&!Z$IC3OPlfp|ox zKY)tqQW+>UoHCz={E;GaaE{rTPJT9Sjn-&zmMue-E_($+E*zyT1b6GB=pG*jtMnPG zYlXeR?#6Dnma6&Upzwe|z1H|_*}UE`V&Z`3^aq*<6Y0|_n2pcBuOuwf&=!Apn70wT zou8VtXR#E9E8`D0F1sEiO7tQcP?PhAQ+5YxT_K1`-)R=)J4}jJgZa;rx#hb^SxgTi z2qIeX6&)#looy-j=YqrKPc58-4C@N=QL^@L@3g2?bfa+gGZr(+oQS>jN`Rd1T%7m! zhk*ywc*1=>KNSq0_UqA&f7-Z2b4X^o?9te^v6psG;eXo~@MXtYg5sru+3X>Ncuq*` zjA4HdD=4Ws31q#yZ3s}dVfa=OrR>+*bCm70yRx;j^peHx-}Z@F0ZOSyqgv82oq;Wr ztl@;Uov?*h$#MpucNcBAzi(cy=*0WCQb2jJbNUDC`7AAZxBVJrO^RgMkRS%99~cLvV7Y&|0x!F} zvrq?Y@40W5+%~pUEbAx9u^|%a@H~mIxdYe`w!6+fyN?#bW90?BeJ-!O!+01NXUDB< zffPzB46qN`_+7}YEE(fm%|U?;5GBEj5)OcdfN5rJ^V@>(1#?^wYiZ^g_#3ubUEF!x zcJAqpIiT;FH~5yo7Sn3yxDwh~3{BgbQGf(|)twbflPGgMc{>{j=R)6}zz@k8PhFQ? zNmtQj@yZZkT#QyYBfQPpx{Np)k>(B2!jq6ma)lsBj*i2VpoNZThFN+$q<;JDIsusl z-`oD;)3Xs)wp7Te08Csh{NM#I;Cr%vuGCUSHmEFQd4_h?T0-B{jt)=S0qxftg$u(1 zFX`+7yLm_8Yqj~@8!b?z~iHn zLEE`ow7+)8$t@3pZq|$fO!gtSIIlaIvrW6!+pFIqS}MA~r{<`AJ%XeU_QR@Wi+9KP zH*-iLG!cAR%gJIrC@%qAgFk*fLD7(C}6Y6XA?;vHboDsTfn0uvr$}6&n&w5Jy^Tz#% zGInl%FgGRbVylNCfo$?M^WWu*pUPR+;sKMmvt~v8%QzK2$j*dzY7|N@dOmEaEJd1& zFOI~Y5~owB>!Q0<_)9<(N${A2I_$K}R`p-Tz{oeEoq5c-#!ubnPln9%M(V?G;6RA! z1Zu;cb83czCytss`=;E~QbVscv{6L?C!#o#z(O8)6s+{uysNE0Pc&aOIxf6=G`=SE z(S5fM0aW-80lT5%Vu+}^_%uAIFaF#t&dAw)doxv_u;Kg6e%9i@1-iLzOAN|mr_v_R zr`;49i!Hy{ z-WSWf^8d}?v||V~F8{3*5Tv0Z5>|>g+TPv^WaP`kXI?4fw1B$)+LH&M=^b>ECnF%; z_7uan_4!z7<7Zt830+bo&;7lFDn}G6qG4Aogu_U!di?_Gfnl}6W3AVYT&sKW;~8+C zQds+M;puzL0>~?db&1>DTL9I6(q~=wl-1ER^Gmm@mdIJJFow+BtDLv8?d&ibi$5DC zxtq;z|7kAU9BM3VglEOtg!0i?X;T!~NB3FZ{`oo~@y|U{#|DdC5h47wE9^k!BB?2( z@6ez-_TT_Ld#Q=WU$y6^M3lX1av!T_cFw}=vg@pHrOcEhf1;{nX-M|^ z`JZ9clQ_4#aulTAP0>ZN%?#9N0|gJ1VC^<wQJ3q^wz>8)Z72;Tb&Kz6RDQ=Ell4b7xocFlE9#O@c^MQHLO7(%=Vs3T)%j zaNS2jQ)sNP-hZZ!VQV%(PhF8Ka8es^Y}tAzf^HtXQ99}?7ntsSrCh4R(cZot{G1hA zO75QQ`Xk}^OpD!x@SdCVcyb#MH`HM1ckX6WtlU+xL%ttsp3|R)HxUKW#<=FTIU2)u zSjO$u`{B(goAaYQxq2*wW)^-YG*O74ZXWC%+H7rsnwqhijnoJ~1y9>4f+2h+ojv)F za2+=*(EO`9}SvW;I6SBYgL~I95=|K>Uhx^N@E#K~ zt`gzsmyMAv;lsd2yC!p>Tcp=c!Os3AZoZ*u`nu*9E5y%QeIpik-+)cp{oHid?LX*T z-MwmuoTUQ;peSZf_MJO~y6hT0Jg}N9*S3KgQJRQU3ar9T|0(dJ;em=Y=!i8dyg3Hh zP$AJfE}#@&2p?2rJCZu4Ziu`6`gl9oIK@F3P?c}7rdYI0hWLB#6q-$$5>5_#smbLg zg1~zVevW}a82R||sd*8;#p zu!ATJ@gVu%v=YT&>wlPus$KVBYmc2_{~tC^z>sk)GY(M2T5rM-K0swbhP7BFvh^W~!uuP>e2hGnT}aMl`0o=b zV~-v8zQ5b!COK1jUgES4fyZb?hgNv6XU$lx^`#(^P~znA?WGC4^DCAVn9d)dEiGZQ z2&(+msynYLEZS%4P)aX`(V=g!(cQ{!9Y zJV`qZr}k1G#qT-m2k-vG@fa<9pN$W^c{_;D2AR9QPpybbz1h_R5V271TYgp(+BIPK z$CT93SjbmSv}@r)vQ?THW@PTEO+aItpR#85<)+EP=A-b6h}XyK6JR?V&OMkFC1fs+ z>IgSWp9Gw@*Xic7oQq2UJ1#T*FmUq|ox zoiOc<>(Gq)ivl|xM5FQ*3eBpGV7R-X=bYt4&QZz5I+tn7RP-QK_h+{@RC8}%;vf7J$F$g0Y;h1L|grQAU6mY-fe>V4B8V#q0Zp3^&u z9USB<_iLM0J6sR1=r^)pE9sHlPwxJVxV0~wd=c@z!-M-Jej}#`W#mzXaIr9&1Cd`F zxv&^5DJQvgULycius4%7qXH!j>7BmaqXi~6kID4wc1Lsm<(Xh-&o{C9w1{KLZ>b$y zw{fS60gS{~cYWcX0k;0B*mfYbfR$BQS(v3Y-fIsOy8bRq;O|jGcZXJkXyTWjRr|-R zy$rMAt>DWq?^8dk2O&{(dO(Eb?oX3)gZVQZK|_ADo@nL*`Fe=d>bfYoTV8f%^zqk; zf{20I5u`Nkc7H%-zp;ZdF*GTqH{cIQ!GL(EEkI}j3ks^2g|N^@gc5l~Yu?fK** z-^p#K!_0|BTI1gnFt4HqhF3;H-IxITz&N-Gc@{R#v@v}*#d;^k6SUtZ79lhpZ4xvN z%+s3R=n%v^sc}ARV=I0c4WJfpBaU(+$bgO;BDMNJEeOQ(eCm+P51RICjU@QQ*@d#% zU8==}r%gC|o;#X)?BBO$kv8R5XB6@rP zNq1d2R5nSW#(~S*65QDcYrx5M_@@mdqbOARD%5xzzWGc0{@R@=p|p6MoYgL0)V}GpqN~&Dad&%2391dbYLq4tC&FtBzd8Jne(fB3N zs2cq*{cc{pFvtE~h4$^1R_g&dDu%a9GwU!T0f&qBlrJ|WCk}_gTtTBXS_Pu`;rtSg zU8o$S)k}G4Q0>Q)gbG2t-|3X(IqRo&*-Vg|8=hH80hPaCEy=KQgnHbu%eU!RdT4)v z;@#TpKj0-Wn@+6zE|+Y4K9+e$t@_fNtNi_9b_fTD(3-_e2hT)|7+O1ma77ct0M_>s z7>xzcGBE_{SG7Bxacybi_2;yo6xzz$-HqJb)#%fUfanmx+aJjl@C)0a{>Gx+auA8# z^?3){`_=rfxAQ}^zy1E;C@C1;2uL#`8VbAu^%Jezo;m`wEiztye@(Q%$2Ng}j_5if zZIaXJmM87gay6DVxJoe|1Fm}vt=9FSyDN?KIzwxk`Q9+X-!`Gga1Ev{-&p|bV=j00 z0u|mDoS1R@^7){RkzWczc4vQxpnAr@X1*bf1VfO-O-|~%;Ae=E5mJQwj{hpmBmzJi z8=$m%*g}E(f59$DEN=-6tZZ`_1b)J^ zn*+NX5(pEO=-xc%(6L;ZozET(+i#-G$=HA7BaRlO3%?|6lU)ZMET&s<+*-0lR|gAR z9(nXAVF#q!$^f2f955k?;pqPb?*LZKW|{@1T>!d_dO(z=g*w%{Y|y~#1ZXm!&?qEf z9_Jr0j6qg3M9m5V(VUv%Wv|;h56!Jf7kDv)59lPu6$;Lnudv69uLR%b46WoCWH9z$ zW)>+_kh=^k&XJ?Xg&42`W2@-YiM~@|;`B6wL4h@GoRKRzm@@5J@69iR5r+`b;?$h% z{?1VZthbesrAA}#n^jBip4|AdEkktX`2l3;@~0S~+hdTd_A~I?{N*%T+}!}FI5Q6q zkIL>My1HvADJdu$Z37@gB(Hg2VRO2i;MQlg7=qgfA#!X1F4y5^P9!a=3dy5rgcC+QHfUbFOR%o&52w6q;>W|cG>4%G1x z92?ngc^PKD1#0hMcKP+^1Bk&;HbKo&w8m<7%cJvjK+HMT$;fcX9dm!RCmsF=CTcn2 z6(_D_CX%|DsD4yVAWcRna_(YruCEX<;5gJnGP~Gt#JwQT;roXenaVDY_ys^3g5c*B zPG6S<-?iSwZ$M&=a-Ap@*D3T+U^Tw>4AY5YOkka7((+5*l{{1LLaOFXX$xt>do~mw zd?~u~S`i|sV`|;GLAdSc@jJ@NjPPwfOJHSfk&zx--*xyTPkDH-B8eUudc=aw?7WHw zva<9fs|ZZj@6@TBs*Tost3ig98Gs;L{sj?4w#OlxSPOg$@F2aTp_jQ4eMgkmU_2u; zr;qXbpvb$*%-0T;>iF^QmoxhGxyyygJA%-a8(uc~He?J-N*y@7l|39hyqP#01gZS; zY;O$y-?pZn5pJ|4H}XSsvQC;La=kz^^Iz`o+tY!$I|^3a{q|?GYd;POt(s@)E_=ul zm$8jV8uI;6XL&eaJJ8TXl@hSqDC;IM$yEz-{h;-vna;6OWE>3FW2x`f|0 zi_DPo_BsdD_m@E*=Qxo`{<^G){O)2zBfvyUFZp7y8kXj^j32I|s?$YVR2-=aX|6d1 z=x+JK!eWW%CFpa#MuKX);T34wkE?Uunil@mbz!t~w=W5b`)JY30wc>XB%w3ZK)k0= zVn#;uKar1M61m~6A?y!%oJQ+neW$6^Sis6lpiNKq^D+R$hkUE{w8W==jmEgl*Yn{I z2HpJCB}xqsJZ!}IO=p)9lR5xHY*_{6L}=tb(`;B6;aB@U5vu>6T0#RkcRLNqTm+&6 zb^OncW#QB-CvH6tGNX<&^bp$kq(TuF3(91O#cawfqaH#^<^u8rV}8&@VqQc6 zFi!gp?}YaoM!M@X*PQN-pNXSy4BZ=oNgabO#89*F3w%a9e{>qdB!_xh=T9IE&zz+y zNlakhPtJ_J*MfS4%a^l-$3hiCJZAU4#C^|tP$OkJDz9hOXg7fRe0b{nwVuTfE|%Jg z-F6zn83045_w}Wonl>7hS%~Xh{^V`sc@bny6`u(>9G>8Gwa8R#+i3i-ExB`7P{`nK z$nDk@JhEY6VDv*x{f( z=?*HOj3Z>1R0h1~t3_mGtJ=M1vQBtdjE)B3x-G@V3cj5U0Yr2`qty(Zdhem-Bq?aM zbYD)yVCVXJ{ja!RL9GwPG`DV(=1+)YCDmoZUE3M|```VyAEu0{GYv<|@2avYpYI!l zKwP1?a(iP(uwCM2W2R1HXQ@JhcuB7QQu)q@fWy&1&_F9OdPr_XMq zs@XJDX}H3;IlZhmyAw=21Q&l}Xhry8?%=xh6wdl%VZX%?BL5#ijg%XP%#|5F@pC_N z8l{Cqxp>g>2EYPo5KUSPmHHWZ=?+w>-N;Pc!xBKlgutjJVX9b52kxt(?9EW=z>Ko@ zgoewnE;tovLrUFY+a}iFzN!Jx2`*OR2$jTVfj)XBD~U`#M(xiGv^W>5;xK*n$5k6b zFMu}Q626x7wanP4itD?cn~Kk`2Jb>(^+mh!@zgBL0iPHw5u;KoG5M`ot=@5)V!8Fr z&w7oV45v72jM4B%3B)?hzY54ea$H%^PrbZ5VI=2@M14Q5O4f5A%MX>Tu<6f0)kjwj zpn`ZT#}BgsYen7JN4V!t`~;$}3IgrB(aKw<`VjbE4_G!PR9Aj*PLOf8Z%UMr)R0~L z_Or(vJjn4X*0{XJxC@G%$nN4{MYZZ!qf@Zq38ae;u1v)mtd-<@fj{r@p_9pG5D zVf%R_8pfxD5S5C`%9h!%LPTYc$liPNwy1@Bm%2-#cNd#{)OdS2iE{r__u z-`971@yz?a?(06U^E%IiJ|H`dp(fUmZVScuN-{WY_7DCLOL?4D2ljUQs4H(lVL2NF zQ&yb{;fiHHt6K0|rG@Hp&qkkCc_9G78U^NW$lXT>ma`6avX*lKJXnD%H?UA~772|_ zK{=i06_~pvGiv1G7^w#SnQw6?V+6cr zf4=1nFbaU>;Nv;uKF&RQS&ms^W;YGoy?%d$7ndR_JSk7X;qD~Z-T!TccXphk($;Px zCPj@KMFtS0>LD!5d3L`fsOwOlOUU-N?$=}s75tIB3ngYzn-;;zTJ&xkWVKg^E~<*X~YNJDugZo;Hs1EfhRv zlx;d6NUhJ|knByodHB?4nB5t*^)dHKBRrbaT1E8t70Z^Og!3qk!P4y=iV{X&0UN?k zm0lyuqwjX*t+)1bPxyJ2q=5AxEdt<7a0nfeNor1tYZ1Gm_pSZ)hgM&Kxjdz0zRcgI zbwc|d5^>_Vbm&Pv{I)Qv9f!b)Lo!jRH*?+T>&POW{6;Zhz5#7v)EmvvD z{nM_1w(o>~x>>|$dIh>5go=BeCQmj9a_@e~1o$y0yUvog{vw0+ndPZ-IfIeAhLZI5 zdbJfkjs^K=5v)B>$V~et+uqDH*S>JP5-R2paz){J^#?E zDyxvYrHLIl#0N58tibV8G*$ldtA}fQ)|>3L^RkXqErD*cu; zfk4^fEv?Mo?(`Mo9ON)A%H6>)5wkme;2!{zGM~9!8*2)s+-KHa$LuX?`G7+$p9nor zIo@nlo2`bU=!}j&&;0uDirXtR@XVVCq14;?x+VxeO;DG|aGYSjSIiSacU zL^JKrweGWedwaWzWJIGDf@A39M)kq^X`f+YLu~ns1S*d}#QOY`bH0N|=nT@5v+6J& z2@(W0izW63@47l_sQb5GAzbFZp2gA1E@PS1yHwZ?wlWqrCfX z`s5Wg{+8&l;fjr^q+dnb6;MKvx?4N5I2mBk#k8>f;Q#KDHIlzedN0FBE%^2>RhCPuj&4BO| zs}>1b@RPSJ+RYKzUMk+EE?V@yy&16kNh)$pqb?Hz&JBJ!dEL~oqa#V*_TOz2e;;QX|f3yn^Ab;z-*{AwvyDWO>tHq|=1ussi ztwIqWdRytNWT=i@GqUo=?|PFQ$)A`ye!&PdwM@EKMV@_?xzpy&_Nu-iN$RcNu%@*z z5cm^`uxYqgmLUMasbo-<3@^xU5{=Y4oV2g`yVwGL4Y2>(oPo8nGdO z*8tt%i|{Go08T`i*eHa+ngpX->q1mZQ3a=RhSC z&$0o=s2;@PoTop61lBv1^}Ev5%A*+&ISoNKZu}VLKu)GUgUXjQ%h@4gPyXK1`&Kt1L z%{DSV1XZX15RLqpbl)mdTaHs5Zv~1mLr-7fQ0-Vr`_Jl~{ zkKTyD5)6z&tc?YGHAF`Xe#FU8#HnXLcPx)-@`_)t5=T3tsmltR0Vy!Fj%}N-4_AgJ z`t?;8^Z{cII!{-|wAuJQ_mL2pRcQ>9dOrFqPmmn^9S@VLD}Z(=ta2d1X@Sebk5Qv? z?02&c3l-C<{6V4-*7*!NqbmjfoH0Y#FCcS9%?MH+($}Rnf8D+m44?P=hStR|ts^~# zO$=m7q4mc5Jw}x`#$IeTrV_eNnleT>Hct_dWc$Abv~YBQHH(OEkMYm z@rCO17n2kTtV=N?^cIys}yPg@$m3$D-a~Qe-oV;v}C=J-nR|cnswqc*GNms zx<1qVcK6-<@-JZzku%Ud309E8PH;%oY)zd z6s2a4vR5h_CAE63;JNYv@1OepJH)P|2-L3TL?OvQYd%QW%}zwq!l}VyvdfP9v=h$i zDijrWaJ|#KJRbqw(*&?PUv-HMkb0(nB0x(h_;G;1Xah!z4O zu}|KbiJbkM+C6L2#8$ZG%!g#VHNW#ai=PBs`MHEwm&3Ccxdoi?-vU}-+IuYKaRhw)9TYV8s3}q%O-JOPa%cce?k`GMo&ZlHZ z!zACJed8nX$n7*zvC>7H+d#JQ@A!C_WJa1)bT9GLnK%|CDKOFllm+1(QcPQDS(qBU z)abWF76x3|i!sjWIrHLmPYuu@IOVsia#wR%<(Ff`{N3MrlM|2)84>Dr1Vbfk?+ z+891_qt&>Wxz~>_Y@aI(`a{grpcqa}b1Rvrpy(?;>W9czbHTcWd25%ANOgE*WnqjT`e_KxpRJ-B=50O zBeBdC>zRA4cKOfd`U})E{ zsW8)Fg^HqOp?9*U??_}K7|ho|@wddv{F2`M`u6zAm+Q7kNvl-$Eoyrv)~=$( z28Pn>7r7uPX?%>+SI=0>*UR6;1CQuz0TY_$V8iO5 zV1AffWUWoLz`WP7l1ykWn*oG6HyE1Vk#Zc)puXc#6M*X8boMlkxYc_WWu;P3FzGjk za&x<=4sC*+-jLhU#On#w{Vmh|g0RTgnP4*{S}yI3%_cc_10PeDCgY9G?^9_eh#_s0 zAWJIr$^=--nL`dL=)2K+Vg{ex4Kg7=84}n3)aUS;b=88d;y7v=Uw|6|CV%0pX9{2r zt1VA~Y&Z)N=XT>)%Zue1Y4RC{JE5koTLtD?FrX>+Qq>{R!|MW=$awBZ+$)0kDC6Bt zO((YbdM-}Cd9Ae3Otfde z^)V1)8GD1f5n;1fDzEkH4I#pZnX)-7rVp;2X1JH{XdI|oXsP86ns$DRpltV{;>yJ_ zKz?Qi2>W>e@0yQcu1GemuepIt6-41S9h`2eu>!*iihKH`P?O2D=RyXCN^A_hcIb!p z>gdK9JtzODW-sdYRYe*mpEF4Jfnxs`>0RKs#w8n&H=800_8o>T&(egTXhZrqK$wBT zWl@EIQ(2N}d@*EZ4Ook5kH>J6to}@s4EA=^3 zpebS(Cw8zZ766u(^>`qsL1>5qHDA>Ob0aMeMs!HruN39^L%fK{dB9+R+ziqod#6wu@3|+g-cWjB;=}JpUb(F5}hC-n?iO)dRCuia+VV1=pn!b67R_d6++g zv)_iakQoC#IYwb4eA&w?Uws*x9UGt(`%|88w>d(-0_vFto<(+aQ*8J?Q*5_*|#`iusiqqmcL{t<0(6-|Bfp`05*0tVj z>&^|8S+C>CBhN9j4iuK(N+iVc!b)MU1zX}oTALQ5i>BNChV@+GrjYC8VVtGb1IO%+ z1B7ZPNKCSJ5h=Txf!XSLF|qO#%K902WZ6hM#;y0 z;NJyVq-13EfF2bdeXfAs|Nho^{9{?GBpQBUVR{v9m%sOG8o@8Mxq=nXE?gyT#r)r1Iaqg@lS!+ccb`E*$oB$g1cBq;%D-A*B;df;BAlbS#v1E28 z<1@y2{8K`AD_!`nxG?n9BT?retc-rrutdADR6#%(kWA8k&q3GOj2kyga55p|V1n`r z>(pt<;{5dKCGb8dK}&{(9v0Abb6;TerNy%m6yaTNU}OZj+SY<@VdxH71{X+9_OhjF znaM)P=6_TkM>r*((mOLgI#Y#Sw4+h=%cGmnsWI{G0r#$N>u5=77tobizX0RJq4^!M zG{7WV>`)%IFIZa1Cr^u=HF;M3BQp#zEsAt+|L=mju}zo}!`w5oe20n+SP@ve+|YI# z=N7x@)2%Kob_E_5=H{#@x;lUR8^}w)gXfdEQy}E+-k|e=_C)m74(R6Ag7wWmAl5YQ zm<1n9o8Gz#lLOtsXg^w^-(W8<(?zt??8lHOB6qeK(6*!K-G}w5z2F6MTiU$0l~7@9 zgizX6(x2UK^1{vP$WMQgweBdwK4{jpr!DOC!}$ny^1CO9v4xE$!YCN`OZsG&Szdi+O(%{9RCMNmHKfQG*sNv~JPi0z zemFMJK&ck>uf#zTXg2hGTZMY$7WCoaEDkDAEOykJt^ilETu(O+SoV;m+vo%r=MS}Eny(Wm|GjmHWL29beY-a#Rqjr5|G0^;#E zfo0x9ncyjjJAgH?G-OpUGXXo)%Get!oRl^A!qN7lgSbMxG2)ySiS}+Jy-Oz`DxpR^ zp^!A>(F>gEiRP}uvPuW^ug}#(MOqK6>X%bh%1!%G%~v`x=zS|VNi^(rfa~|`*P30d zJsA8|tGM*;EcY1HQq6&5@NwDkkk!tO7p6F2%xoXtVW~0wlrs+JF#gG0{I<3`q zA)S8SkYU6kp++AWo}?c7$(Hu!Nj@Md@{Pq0Yo9q-dlADNFh8sTy?Maqo}N8{-g3S1 zPAEGs;&rg$Gv3OfMnNtbxNqdJ51Nti@sLm`2=~s)Q?(C%1RHN2GFTm*|6bQAo;O1m z$^ylut%D&DDibPK5!y7*SBHjNN>sW4#l7!EGa+mDxO0}jTtiuxoVSR(qyg^u4Q3ss z*-36_*MwKa`u6fdljU18uL^dPIq7nsAVM)!=kXn*{l{Uhxo5I)4UBb-`2j|Li)m>0 z>W=hs@m*~KYb_)+<>DmvnfheE!y;@0_I_3F3rN&7gB=72YTOw|A0oL8edhNEz5{9CGisw0l=%?lvT7 zutzrcw=yt4k(qZEX$f?;et5SQh+_>Q`%`Pq3&a(tH${d#X`VRe`NH7cJc@|lN{Jay z^>{^=v)vc9u3F3|M&IAPY;@6p7ct_AS@;t!*ow6*J$U0>r?h)1^hk+2XpY0KwhY(Q zlv`7Y;yz}vFJ?W^SC4j6&*cxTCGpq2J#$?THeP59^B>SZz-R?%rvNX&`hGDG@AvCVWwEsEx!c6MYul za0-AR*54?&>-CFeL9;4Y2T(MHa0EcPHz|HIireUZr034G&CYbP)0!yKcD>ZBWEixU z-~$|SEF?1HySTqwy*B&!=2^M#8W%B(a4>ei|edGNnLkp?05!bPu~vI71(re2*KGo8Cu#@o z-3|sb^A!Gmw>Wr1*y)r&nzpnFVyqNho#<{0?U%ae{yu8S(gfC&Wv2k z<|2+s@v6LQFN_Ea_f60`ooXWM&q_E<7Y6Zc=@fN*uDkLvU($7K9{}Emx(p`rr6$l@ z2EPJ%V2*qzf~-lK-ZA18i&SYnpn(=KU-Dl5og`TTYmbB;;pj3$o&26%Ezi~+y;bZ* z+W2Yx6MN@6{6};6x{E$+)fq7;{@eR$iRUXn^s7AqffN1ASA<@g%sbSnTclYKS(KI~ z(aDh@0iFG%NC*&IozFw}>}BIip8jb-#^*l~eRegXRkW<Y z1Ivzof}?t4HdNzrVBvG5>S(wh=J2zIGa~Hm$llk}Wd17Ad7KAF=C5U7iXiaM@*1uE z9)q;^sZQe1(%A?G+U8@iP69||KjQw~^Tl#tH>=;<7h!ntukY}Yn`;TPCx61FCFH&m z(P`_O4&G z$>~0XuX?YXjG{8h6IqVj(9z)0eb17Qk_yK^xzb@qxM;Cxb6E-d`uPykoyi|I>$L%H zz7ymQ{Cg3zqcM{1lOhx-IPpv9Ugcg{FZUR%kEgs=yewb;s-<)gDRew*ODcx8khKUs zOjBZ8gMc78W3sAlU!~}SlD=UDlFjcv4YRPdU3%bq209CMKYxW>iNCSc%dqz3a1>{3 zsc*?3k&Dxq%Kjv|-fsdrN8D$)FTimsCRF=o(~i<&PmAeocDrU@W}b{|n$%{n8L#|A zzdyJi;V@xCT*p6TE4lJ$2K{sonks3QYs+2qPwwH`GXnvZiiF-KI5_hU$Liy;E35c+ zY;nwo^l!Gb7UbIW%YD8~JH)>7DKChK+ZoM-w`xB*{}$VG8YuO2UZMW@3(<`2g`JR` zA23MR#9~8K%g*9FqP^tof8MeiQ~AUyP22GglGNX&`9Z9JPjN{2$_?R91&-$^4}nz^ z1w62tXj%USFNY$Wn9i$oovCfdXV_O@B+Nv=q%0|-H>A+TrAAt$=i}PsekXID@`eW zbBFnm-%@ajzj4v)VH{uHrK91tMpQjz?#(j}IWyl#g$@p(I%RI?;#Nci=ATI_9H~;C zh-+#Qqw7vJSxrk$%8dK+%WqqsT%e%LMNaP$FCvT=4})|7)w^hcZCM2k1H-~PPf{MJ zJMmTQuV-z#(n1+Z{S95TGQS&CB2oF3C$^7{?lcUmyERqZIu#`T(=@2%Hu8ps<}Rne z>lamoKRB08AEkKxne+8Y{}*)U-&S*yJb$6*EkSjw7OA0nQ_K1?>GbUl(%T#5r6p#? zm104bt|>E}f}2C?l`)gkQYoFqoAyV8+;*ck%aD5!Qk&BC^2PIl81=@^#KBK3+L)@OwVug+qH;bO8 z#Re+>DEdQVd97{i-J&c`%0)2Zz8r{N;z2(6HSw#cEa_hXe~?7VM4Rx#c}#-PMCz*< zp?0BVRA$M{H82sdDS^^8NFy~ZaKj6Z4jvtrxOJ)ueji#bJ48ZFkRIy`o)r%z?$GiV zC9iM2JDCKfF#vMJTP~9lR9&D3g}9KOU+#q1lZhAsf{teQQ%U(vSh{7&QX6i|5BJNe z`->9-ZSJJ8Kg2Uc&=bGawn?ADv>&7Qw1(RQr6hZxs+e?sc~AoOq@4o;k(0gKv-5?+ zU3Jtt>A&KoW)Ib`K8y=w#6W>+`|GT3?nFl46P_#IhoK4sn{aO!Y*%XxW5wASsf#pf zz3SFRyY#vFkqC~2g?H8v`@~zqEdQLcr$G4127F(xEbql<#}tPaTx2#uB-t8#2gz{qP^Wi9U* z7)Teio0vjvD#7M>ZK;O*dZ4uZ4n1T~A(!c#W|f`FOoiENho7K#J90Y-R4S3|zn@2h z2Rfoep2UiZ{iR9Ek$*!HBikWL&3%(qnGQY%vZqgvkbz+R6KKX6CmJE?uCFJpiZ<^g zczSh6S2XE>W^wY@Ev~;)jXqSflN^~m3>s(uGfbgGmBnv@Y`R&uV?Q54cZ?8Ri%}Ef ze#=sM5FGCU?qwWkKcyRMJPUyVGMia?A2nV>>mSBLWiGb#$xS0!;{xCWB*kEO5@Asx zjySc`S0kIh8oNDQ`06XwQS@0(JXhhD@gKdtt;vVD{S%D)G08j?VdT%n&>ftKah|{4 zzT=WP38)!XSh~J>i18~qLdTEztma%w&Soq@=lfNud%upn(|n@=>hGy#F;c__>oc^? zS_QvNSr7N?@a>jS#o1MmAx0fcZOJ%Jnb8qiZclzXpFJ+%3Thg>;EA)oIIM%hook@3 z^(80ghSh4Tq?T3`04j!ljAGiT2^DbuQlf;Ml1TS&T2M6!`lCkECM}VIJAK_1pR%S2 zfUh#hk=0eNMOCUNdm;$GWFT%~)p=KIh(==PKkG)g-P}C6#S|BtDe3{GwhTVn?i7sk zFRO&%=vh}$pMT`wg?tx;FZFsoCCJ-t?yfBSb(KI3W;)A{>B8zZxHvJXoT4&&Q~hzM zHQp~{S8r$gb0Z4Zl_VZb0=7x09M>5Y&A7Cz3UyHHnx%X#PyK$d z(hJofq7VTzB{em*UCk&e5iOXZP9$r;0z7%Fh666m_vT7vRqUh!*mwqYWm3;I^h?+n z9V(EooUU#Ol)js5)Y^smU4gFufF}Wh{kqxxTPVFDd|?9!$)JdkK|+fa;o14J(3j1< zOPZo*L5Fq944fGHGx$^(&6*JG1+Why0~yNd%!O_1mZ64ww`z7@!3e$3F)n>CLFsL~ z6;?AF)XMmgz52eW%-c(c)HFDG9qI+z1)Tg;0ODp;DtA5tv7ZW9nHs*-99{5=QcFrox{3wQ zF}yT5v0s3jRPfsAC;`lv$M7eO&IABPD&eQEmggG8tUDhD-zqW??4=D-be9(EMi!{&CL%~lTE$|_x9JmT z3Nx@ih_qD8FYD4FAObNIb@(&|**BftzV0>Dl?6zm5vbAB{BWh1{yzd*p^t;mnFw+t znrJ7+tQi3ji6T52>Lo_XAY8O=2G%k&T^SMZfz>N-$Gz9f2?gnSjY`M4o;bkz6af6| z0yb(gh?JOYul!XnwoMHB@wCq+?`Lj?JzEu9mdDuXm^Rd+Day9-YNn_Zf(-O9`d+sz znfIV0aN8;6#y7K4p2_N(h2_UWA#zwN>ROFq+*?P|s)&PyW%FZK;PL-xe*QIw`}X>` ziIRV??axe))l*l5{ORbLxvchk} zp*RQb0GI3+hqT1DzLBG*O}Hs3v3B4`#;dY^;ycFbKt|xS=OEJuu5jS`C!sLeyG(B} z`C-~)`gRk%o-%Y~pyo%>EuiN>Clk^vpWm>yVvOD#qUg;v_#rW9TBr3=Xw&2K9CTP% zkJw17ay;5I^P`*Z1SL1u!;c9(&uB_W&f;aH&eOP}uY8-1cObp~G+2^bX)OGRtEP&Z za&EM?W2$;QV0{N8^Y)>OSO6bw1nJ^@zd(Ui{*F`Dk~RKi!Kqd*F!uW$shI9B%mV45 z7!w$?C?NN{)M*jQchAJd{m1imXSQa;h9)nXk1!iF$ZbF4;4h_l;AaX$FACSZd%`e#Tx&j z&^w2c#l3bQuVgU77l6t1VWDEz(vOz+n*K4Bpa-hm^C|_CW-cILHq$Q4@dyHEwAa4N zb0Bg&|6m)4?AM3I^Q2q(`QU|Bu(lsYqkrBo|8e5alFc(8`QnchxrjAupzzwNY6lig z@lVvW0H$BTo;c<>&PIp*Ky^8f!nZ)9+uZ~amDE1!dk4nP-5`Y1wiYndzFn8RU%I`B zaJp4~h0O#@0NTij9_JZh^dx|n-1K#w?YAJKbPjcGqt>zygn3ayLQuF=f-BVTDI6~r z@_u1vX6CRvUuah2P3j7AZakiQTLT`}2tt!R=z@z$Cj0d_h6ctpdfwRYF8R7*21U{W z#^4!zhH%Le<0a8Ecf)5~dO1OVfBUI}^&-d=AXu{K1Aj`ZY{nRf|JI^MsywFzYxNX& z$bTlC5d`5J+d3e6Ie|51`Rs`Hqmtc|$`6&F6po^MVmPqX)e1X`e4^_q3e(ClJHccO z!e3y$l>>b7y|%~tqst$BJXNFF30YILbh|T{&Ve-lH`Gj;z4*^5NFl%Ft{y=~m?J8$ zwT1~ui-}Zr?fyVdD_;D=UfIw!*RUU%ld1{DbP(xID}vqh$E7EHgs`_m+&|uvnbmP} zA_0+m7$jdLdh*Y&)6exfc(E9J4hLqZ=n%=(ZQQdO&=+Ob{EO4uTb;3b;d zzinyxt<<6I)BrPpnU$T9Y1>N)F#($*H?k|-WD}_8Mx4my;^dE43#Wx)Tqp1^cD5Jpdrs)i*lH#>UqY20EQ*( z?6}sAFS7^yI`vOW(p6^&w&6D&QlUCT2ws|xI+Em-!RCFyiwPp&gLb`93C>p12k5yK zZ*uV>bXO?T394Ky5i)Sk;;&OyYUDg0MN0kx_&$hqyiLfi{u-?*@6RNR0C+@XWwka$ zTDT0XF{*yQ2->0aC%*SJP9_Rc_xX{kxGV}a8~V5e?P%zs=(?4{*j9h&o<<0g zk~%?`c=`Fw03%he^ehMC?kqq?jX_Mbuhc0E9Z}xiMCXK^6@NTcf_ajflJda8A>Y*0 zlm`?!;V0$L1P?k;k|>xYr@qAdH?BHCb$`>mOAFOSfiX%_R-(g2T13?RB5z}*9~lUi zzL)aS$ZqSOZ)iHAb2)r~QGaRqam|nwXXSm49ioxcq4wnvS69u5)=SZOUv!AR{>qkh z-J#uG4!pKF5hN)brj$EcdGIJubEyB{S^OQEtHr55|M~*%vsugI4U=xyV2w-5y}6ySHex((vbgEWs*dC64zI9L$Jf+1Pm3H^#EC7(QL*=JESPCcdsHp=|2}p zMbnk+K^D03y*FA&kIx(QCd6fyro4arZ%nK6czWd{6=@as!7gb=e?@DqVBX5oF1n4N zm4OY<=(XvAQa_*Hiv=eS?nw+F!q!3d+XpgCt;TM;n++c+3!KF%6>OtOW6ZUuEZvLR zBV3-g8B-vcZ`+T;InX1R_DB`{VSU-4C`mKu`6U2Y5TuIfELBa!Q2J2|jpybIi)9*B zRv`Hvdo^yBQEjZ3Ui2;}{8W|755rQMN9BpDiy=FnwZ^KfS4GO|J=Ns3k5p+BI#jL& z+5cQ-ClA{16EI&6gQCH(xz>WEdtM*hgmt#y6XB#Q_zEms4^cGj*?@Hw$?V}p{*}bn z`3rt@t(#7Kq*XzG5`IPm!(YEQI_`@sWe3Po?*(*PV3*q*b_x0z3oD1%8i_{YI@+zs z{`_+A`ksX8F=SRhPxmIYbXiJa$&kT>-uT|sM)4wTK-#|&P4M9KhYw!Ij?C5EMQ#nD8E;&&YepuRq*>is3>YZK>R(L>!sa-$Aj( zqby9)+iYC=ySwL)OWnOoGL2shA#%s;bNVL?en-0aQ1hL-0o`?g7r@b1hw=u>Ydf zz~k1`*QEqK)}?WZ4#RT9j!pwL<^Y9JwZ>u7i;g3kv{(Fa=}vZn=6}0zJ7X_S{tnJA zH3D-0^tup~M7Db@Dd9gZ*BTB=w53U2$NyhJhCz-*Fm!rRta)i}@W_6nGzPDBSfz6u zWUf7qb#r+!%giXB{{3F`(FSq$8T(!W#g10^kVO;Z#LXdBFDq%5)-eAl8Y~i5yt!DJ z*vJrlpE*#@WTQqlqo(rIfBUDac$slTB~s2pSt}NW{Sd%F9uZ_4AOfv)!t1I2s)PDF zAfR0&22lZv0Y~L*4+87zy1#=B-kT53Lz;n;ET$WFy1UaYUl{^f{^6iw?LDiwIOB@2sz{-@8KE54&2HCwwP4ZXfOj z#9g%qIRw4MYDn;z#O!8T{1ZRHzA}faQ?dk{hcT#^5PRprY)9`W>#nbWJ)W zZssT%aO^JE9DK`7NjP25Q_dXy=O&$~%$1)*I^5zVdeI!CIx^}-o*}dP4^<9h9o))2 zQt&-R6YUbG#mv(R!Vl1`{6hJrHuQff%FD}dM?*=(i zu|D=w1;v%Cj+le1OuJ_TjyL(pGvHy6C6(&6Fn942-t!7ZHZIg;L~Au(;jtGyQZrg- z@0~v%wPjG6Q={;~mE@-3*4pln=U0fjZ!I}K8@Z~S z^u_C7e>)VC>Wb{+$cFuB@HgoqVMm(qRJs5-ZD z8Ie1Te@U1T#m?W;0EWHmkXmo`+ENLseqhoy-p;M_;jyUGpG`(y?VDg=*yqIt6Q%Gt z!mO-mR732qKZMY~-Qo_Z86d(c2xkUJ9WrAe3`zqY{ppB_W6?a#iBAc@S3^A`cc87N zZKtp58G*)~Z)^ubU^X;72~xL=uzDu!x}mcfIloBjVD}rDd!(Nu+dw`WPn{|BNX*%= zINEa-$5bIUCx!Hk>%y2vZhm(_dX`q$X&XnAZc4S|jHf>ze0;noqrUnz&mhHKch{#< z`D*D{{9rzR`utk3&dygHN z$C=lP-}kuRG8a4gkOz6sR|YL^He1qS5611rc@h-z4|fajn~E&(g1rkY`jdc3WCm8@ zsB}CkCk~R>g>DKB=dF_pMhYC~`ykbHmEkB~Q<^pV{rflA`RbJ_E`i-ICE02WJNSbo zu+sW}KU5{UvJGx^n%~h^?^B|}usxZ4LFY&n&j%QcTi1G@ZtPowoswH~{Oo>q9l_@q z;lkUG0^jfd)vuxagE?Im1PcIT&ei^N5y+Aa&U9^j^~#if&F&5-`M9fvW8s3(4?J+**eNRG|wi3cL9$KopRUpm8DWbU%m^!$7+${`O&sM2sst?&_Gu)Wzt!P3JFWY$YN@PK zS+>$}_>Ha)#j!sVPfh5%gUsYvJ|yO5i5NIE(6q3RWH&C?F)d zose0vV>;ho$dNYw^u*CZQX=LLGUd=T1TONg02b`n*~xxVv-Ug7^AR-v@oTy>L%Azs z-0)2Au}>?s_$BXqqJ800e~F^}mwcwFKR;9agmMjjjl@U7QWDhN$>-RZ2MaFW=KMd3 z0yK)%dUk3uJB!_2Gtb8Ze!a#F4$6^bgV~c)m{$A~r0DH`c{|l>ZA8!>x-q6fOWBHg z-{SZx!*p84Cm7Z`)BgESYKY1~C|wZ8fIjkEXYy6Lp>2lX*k6J9PU^cEX~(% zAhQ@Od32JRy%QQeGf|tm-HrL6zQQAg^jZ4K+46KSEBMU$Occ7U(R2~X4xC8(2|1Iz z>V@~73@$;Hc&L2q+OMY@p46C;;Bl7eP?07U`1n56-(vraxw=Cj31827G9-WO@6|9) z#?x#32)%Cv&IxwW=m{Z2FhGb9T!M+D0fd#s%PG8jLi+V2gHFR9v^>U&$(x(A-3qv! z^$xH=M*+bZ)VAZ&G!zIrv%GL-xa9z^hsw&zW=s6aci@!8y1CPL-&ZD~r#>&j;h7oo z)fge0upP~=d@|a|N{f9VN{Dr$e{Hhf7q!!~R1wXHhEpypSP*++8pmvNo+H+DVOiV6 z8|j^?7R2cRWxKJXmBivVulgd^-zyCq-#oq7?CrJme>IK9BMOX244ZbDYT=NpS*iE} zD1fhlMt-|X@kv858o?A~WhRW1*wi{I_Nr*J)u$Qk=o-mo|OaWWzPvZi42mxYy z(c}S!{vt{%LXaWpO>XftB3C@bni>kW5HE0G9Ywc`Z`4n0PN5_xE@Ux>E;7h)r{;-Oy)l1?w&CEQ6L?IycHa?5iT{QM6$}kgV33CZ0jrYb zpJRF6_7I9Q-o8Dd;4kL6=L}u#W+m{C#+~}r$=2>(BXA7{%M=v5_!-76A_&MpSOQq4 z9Qq$sT{l_yp+q&>6&vxYCW+r=p9p)s8j{R%a#F%RcO9p)rOYmKv5{>-c&0{mVZ#ki zevGcKyxHebC9-jsP2I_#Hd3>UX2j|N0jCjfYNg|=H@;#;BYycIj zYV6(5xH~U^)6~>qNBH6v4k-F<&@9T)U<1V%bODrQFRtxag-wo3qaKAEi}az*Z2QWX z;}4i$b#G3Zha@+$Qr+@7;z@`Vqg1%*>Qcwo+6wPmvEcDROrBM4Z>Y5;9X4Lg{I0TS ziKnA|(`5Z@Fa<8%pI%|7H140qm+}PJ0hkdeLeT}Jy!(HV0){JNhDKp#huIx(lI6de z;0~amQB&tXJ~f>j(*-%iVpB1K7&m=JRKFe3pvTt*B(4u8$^93t_=30sA0a)HM7lES zW#8N}{P4!wowudh?@WdToP4Aj!v!7uA^|b8YpMP-PCCL5#6+#0FZbMiOQh?3-T;E2 zgm8=`YjkHojGI(0qqeE=r~gWB!dr#B7ZAY9D?7{rUvH8Vs-v0{w7jOlW6MS0EiTVL zm=MNol$w-OUubs(d7r0Rgl|}aIeeo`C)G{0?_fX9raa&y(S6}H19x@)C$FkY8q&UB zbRLyLisCmnd3HSEiLgP1meFf78IJmQV6`IqXpQtdq-ym)@(jy<)8>n|c8+{2$8h+1 z+&EawjXrx??Jn20yDnNNT&hW4p7YC;^$@^-u`j%|hFN-0GBOX+35)&P-el)ez4j-) zKG|(O>GMA)v^MgBe8&;S|E2u>a{Y^{s%D2%rYOTrUVSq)@6WC2-q{2lul7BfZ<_4% zEnWoHoX}NqBce|L-f7<%3+x?A7BZ`_(}e`oqP6~H zQ=z(#*X5LJ>Wy9#@LT9%{7vBqhLQB#&AbjXuY=uT50Obg@i?a2EQ|fe(QVNd`^Q7y zDMa`~)@~veqT92<@ki(y#FU;eIXS;|wf59d4D3l_)9DAUT4-2`4Z*%~J2$}iDlyih zY$AYWfi^-K2)X15E5pFFy}i4X6+Aeha(I2@tN%B{0cFQ-{sE^tshmUeUX>x8G0QT* zA}S15Z(Kfy@EKS)Gm?dQSiZSLTD2tJ4hTdkVtp~J{ds<==DGMopD?%+MJneVWXpJ} zEsj>iH7|jj&LswlOBrgpFnGvlIAaIJg#6>77=`~t^uDk94r_fNY!$H&R>n4*lim~#@h4L47}p`@FyB7k&p=&0o;pK4^KpXcCb+P3oQ_}+iN7Rys% z55(OOENN5SHWz|K%`u*!(qj*n8oRa?U=ZWrYB5~lQ4t9ls?68#2iNW%#joB8Az7Rj zRS;(`Gz`~gUMNp{czS+kcNwl7uPXf8(oPyqPjio_H{hIr%nWa*@pp~`tB+Kfg;wYI zEWWZ`6CFx^`NA+p<2i(d3kDQbpk?W-^HU4i+Imuch9$eX=-<2Bihmg+ioA-m8m>UA zE*jLX`7g1HMdM`6(IOf@5(?S=Q4qt~CwE_@SY)^joPY<7dN;UR* znKjFoA9viGwxi#ZV@B*_ZYw``a8GS#RoHrA{8?+sG&MT;VW(2u}B_44%nDas=i zP*k@E0WxFQ@B(UZQW||8^JVYBug(L%?&l>CRP7HY z-vzg^;(BjlbV<5EPKVV3TQ3ohKNS4s|DukHH}7pv6DV>*MKRiW>^LdCK=yk6r+=27 zA3bRgwgEGcyLJPTpWgbbtt}SrRH4*yerC-K*a8Kj>06=(zGFr*OwWZ%D?U$XImNjL%pUf{r1H*^r6mm(r(NQYfviWZ%f ztg_X$kL^~Tt8}D{qMAlA9tG%A@bViSaION$=67d`@_KjWe!lYVBI^8X(tgRR0+76R z>6;V2tS783&{zsdk2_3i+pVIiG12yVr-SAAoff0|BwYS`Tad5v#lxW4hJ64P+#4iP zjWX4V*P_Xi0QArGu}e3Zy0zS*GD+q(6V#d|!ZfvmS-N@*0_||zLs_Q5^ z-r!)d7_yK*Hu4&^mIDQesYtt)2arD-NO;Au@lZAnZp z_6;q(A(Y{<5s3AZq48JGFC@Z~5r(Ce;mdAl5pH$0%M46P9M;dKTocOy2 zT*6BRz-ak<7(GTFQ$Wl2mdDW6H=x^7ZCpSi!TSxa!5&J4B7e%ogGGOHPZJl@>bQRO za-=NidB+0VhJkzG{7ctpR_4}r^$aH$AE;H6j-z)5N68;USuf;MYFgSlth+N%27f_B zO51t0wtwZXKnq1>pTEhdfIoC=CZY8>02%}j_7UW7oxR`D!v&p19J5Hp#TYm$sbsmH zx`X^Zq4{d zX^*GFjG}*mK4qTnw<8`)--ypPysCNfyQ^#FCwFUSNX6P^l+-2|3ADbT=_|7r4xh2@ zl{+s|dJG+C+9l$WZ9YUJ_IjV>(LMNk*nPiRPYEA0?6&9-ZC8m&IcMxq(QX9pwVq-W z3N}%sC*AmEy>`L}d)^ny&TZ8FJW?fcO>OMoI2C-|^X4(i*gz(!84%;^0NYDunVZ%l zSm=UDg9K*=LQzmcw1``()8Y{A4ZWAwuFpGh5g}D<9bm|#16l`g{Jp9>RASJ)B-)-4 zZY=%6?a?#cL~(tNVNlCUSy+`g|JJEbsVl__H_V-c(d7pgLhfvh zaWVLvp4D9OVT-1_98_GMEdHj4bJ)|oEdp8imh{qdW#GiPjmUrQg9g6Lr&u)l3oM#8 z0YYUt4ruN_C!_I;^imOM3q0>HJE=hPxuE#@d)sar$C`16o$g`Qhq+JE06Y`#l?~;6 zdJO{CwGOlVx7OcxH0yp;%6l0jk}d9vMq+&Q4jwxM^2ej>x^>n|`T1x9<{!xX|M~Zz zK+>N+1@)>kHRT%Mg&~^vfotGtR6P^=8K&+F=v?pY^WpR+`^Ct+4kZ z(0WO)tx>E65LWvt>^P8Mo^c}GU99#8AO`*X)W5Z5&P>lG<_P^#p|Jlg+8wPHo%+#ABBINa{$Z2$0n0lGkdj*P%?2XKsy6G={2-8!^GRdgNz zj{2RW*$HX;PhM86hUKKbeM$M#22l-K@UZZEY~heI0`DYt;F3H+)dp!*J!a%slSRqX z?CAh7fre}<^d66lzps~-f7r~-T3X?`ws>DYjex}mXB@%R?eM5WzlIwfzhx&%wFD(g zHLJ2^$%aI&cQ!-(#CtlCgem&I zukl_Esq%Vokj0e>LQK0r~X z&bi)P2M~%#fed*Y)LxLI&9Gn=s5ao&eS=F1Px{2k=zfwcGKq+71`Xfq|K#R5B~Eq0 zCyJOvV-DW>J*{!eX%2oFt7aRobnC?5*-slERA)cnQ@6zEGVUI`_$L)}==;?TVh=zrp3~_&-ctcRZEv`+tm#goadh6xkHVCWUM= zvkBQNduu8(vNvTVd&`cDh-0r~W;-}I=COYFQJ=oQ`yZSap8L7ib=~jleZ4OV;&=&x zAQp60&cz`0QlO4x;Xf}2qAyei<0PT<1L|Tx5dh07z&;72FhZ_f92&@vM@6$+ZegNV({}h$6O-dEHwtH%#lZ zLuf-{h-}*y%+py5QuzkPOgH2@?}P3c0}H(e4H3e13xI=+MDhc;5sPej0qNZ>m<8zK zM^C&Wl`CiSIzlp6^!*n&pRYKGapZ5gN4DA8yCQC)5f0QWoN*A`{^XzJ+m87s2+Ymv(Whc?2B>Y2wpII#gd%={N{?s9fl zw}ICJqG-c~^*lN^-L(IkJ}NMM`Hq5lAelf5%dW>3bC$iu*ybc$j#KH|!eSykPB`RxMFTvdLjQ^sD*+-}m1AHWDf5KW0|{9ap` zJp^lz$t8+KJf}WQS$oad9AYuKnSce}Hf>c)ev>Yke&$a}p3Jg3`rfJB6R;kg(secw zzy>(6RkB>Z&jKh(1Arr5aFtza=?D#X7(PO1Ui1L>Q|#rCACNw=sOG^DC7|T8Hy;(g zTva2*j(hz4Yz!+!^jFMC*xvK>Y>)IZ3-!ao5pnl6#UB~35Vi3}*Kp5{Br`a2*GTR> z;@rILOV8dC5-9PmB~)?5u_tibWg^{y^&{Wu@xvP>0G;OnW$q!Llg+lW0v)hgu}yW- zgAs?u4FDc1fOI#Ah1Ico2BsIQ)@(v&ErFkhrFsE*1Bzo%EfS760{K|6QBMC`Z$e%# zDMA<4eUt+a+da~^{ZDUBpq-W}d>8 zpo)S!;6MRM@;A8j$v&R#{s6AInG~ymYy-MRmu|atrpf`iQ`aCql$(`J-JIDIiaMM8 zvboB>2^M+w6I+k!ChLiEt2of>J3@Z?>7+@P+q=nx2`;3De-|rkT>iA>JXRB6Wwg|y zrl&ANS#mmN_+-!jR2v&Xcdtj&(h52MLBMj~a$a9Ca zS$KU+r5VY&rS$z(3SLLSeck+{VLx^79Nh%kvq&1ia+FtNn_1iZdMNMv*5cT$&B6A3IV6@!K;D~@tw*nY_zfEGO{Ug&3(&)6B{|?|Z zvw|3Y)*lC_I=oXU5)&HL?SKEg_S||BI7p1Sj|0mrULEXvyxQL8Usy!z0GLDOY=2HV z^liO&pfXV4o+x|7%`s)|TOGs$yoZ=$eh-F=Js>8U2X`rYkF+uSH0p?V`sKJGlD6gY z!fB|M%s*F7@HNV)$sj=%TiF^7^9OW_ zaK(7oUshDWFQ0k~%!p>+@Kj9qemzCb)}HVVXR|2DBL1tfhS)mzl@13tc~ z0#Om*T(wpmq`GVV^N0jLuv`v!v)rF;1GvK&5F5({Rn9X=k1KqYgefkZ0EK`&;w#K& zccboPk+W{sn#G;&ct?6*U;93@?<3j%!o8C!n1GkJz&8n03h8JaJj;NKBHHS@$o2Mh z0->0*JTl{}5FP(Rs^c40TMe?Q2k|b0)P3=%CgsIlFS1@A9FXS*y>@Yd%Of{ier_jB ztpZuJOUEwDWu~NXCs|RG{j~G*IR|N@hhi6?HlU_+>5l~fJs<;WfK@y;LmYKLh7tpW zlD>d=V>aoraA-f*^(5I_+o?d@5o<%RbZS<*utl^UxHR&&IbPdS4aXL01u>?%;Q~3a z(2rbxieJ}f;hRc=p#mWeqmyA{N$l6R*7g`>uyLY*7G_SIWfF3QYh53^>lB1%p68re zBKr~eTe^xged-@o<2fsTeqS#T=)P`x6<4_j`d|yzBGX_>a&_--x}v*k&-`1lPXn#} zT`DCmm!^islHL?12B)a zc%|_N#tXℑ~Yd4cg_EH)^RfC&_K^n1tv!`rt4KkhEzwP@6zq20SQ2?Ja5T_oD3V zu$HyLM-pH)kXxvIz90}5ozWpHJ9WA$7(zYJY^m=I2p%P>W~7bL|8HSHJkuXfjt`Nb zY$W6_t(B)iRsfXNzO7SHh;HxCQ3k1#RYW3d8~2U*Uv?0nL6K`z(R~)gs=K>hx$a;S{~a6&thHcxTu*O z;~oT05|FN*JCRKG_YnfJetWiyb2Gjnlk_SHfgz9I{w95f+PecCoutSZ93juO&YszR z?4vCuq3atXBgLjWfS$4fvi5oa+qLh^vN%kNCcE^>RnJ8z0N886#}AC`b*BsNPApha zeFzd?L0`&&I|bGsT{y0uX$SrxM^i=McZY||N;Op5 z%SN@&b{3U@1B-noXn`QT85lejKQ$~fV!h$i4*;hd?<9@ooh0gMHfD*Tf>*x-3VF<4Ub&^@K;?%Gi#*#d8Z&!POz41^2l8^;4v9 zt}}Q})N73Be8(D; ziRYc1R6@@){D9q=!|uK5cZvd9f8&_qB^L@7VrIczvZAesn40im2{A13!~U|7mgP>x zaqA-JGPu4ETS__Y$ z1Q#?fAM?Nb5wL9^2ASNxsJacnP8W2SfDMqUs$MPW)O}UY`N>Gmiuz@x?da!D?goAJ zEX7{%HR;UT_@D;T;KY@HQ2-|RWoKg6eL6~Fgzfg69359J+34Z}rhHhTGvL)QnKx83yOX;&fh+`%zE_7NQ8Anja)p!D5|ieT$Mv#r z&J*%8A{}@};AZ~=hQLs9jO7H7Gr@9~uqr!cpQc<2ISr~cu)%$-;qy_ZhXTre;Whqc z^9p=tv?P8`Q=>Jh+_qVRGvZ%ZIQcOW4gMhoO}~=vOB0mxnqW{%7jC-Qrs6j%2<9J3 zp#n}OvKTS*${QNNvgNt`!*-Li);{JLMC)t7oM77=e%PG=(J%S=gJ`%!AppU(Oxr@c zgo%!@T!YkpkkFnVHIoo@@oFRXx5MKRN|Cq+`^62*Nwi^90i~jEyT0K{j+Q0G1D0)H zs{!fXd1P(2;UgEYw33fAqL+DTPRGMvr{c8fB;8C&+L(1J{%P9|Q&Y3aMIEr$c0sQj zu{2fpV1m6Cv5kEQX!o4}(P*w0sJm!rYi9#B^+zD3$r4y9OKN;jzU?AEjHTQQfs@Wl zadt)qgl+Xgw$7=GS?_apuKNM6Kx-;?Ib4j?2^|UkThz-a6G5(NU=xduwIdkw3Vy~r z_Ao+8x4_`I<+}>hm&E4I5GDdP919IX4~Oo{U$0y6!y4`jQ4)ez)xU$-`GDCubC`hQ zyK~D^UO7fk_UVo#$uO#KC#=r=zx>W6d0vnm`CQZ*>aNh@Fuw#N8w1Qc;hrc}z-7Os zf#2W&s~C`@HjJ&Pz0JRFb!sya7DJ#E@ivutM;t~T2|Q0v^Xi))0;wl{TwWLs#1Bv^ z3|Si%mU^%-JoEmR4SSCyiKH_T%Hrcr_pmVP5?z~`OPoyv4u0o5`q z>WU*8JirhDgSUe+G;yteIap@oHS^4>_t>Dpp*TbJjSHqSGqSK-q8bAVYvF1H=MJ2*U?TVHPor0^~6j_o85xuG=G+Yzk3v%Qsh*VMz$Xq^FERdrTuK~Ux+ z(#BD`W>N2(S#{wJn1=AdvE~^uTxNHVb)w<+Bg2{~K9Q zXJzO?RtSwldzL+|PsZsMkxZ zVe6V#c_m^q_z~nQ5rmXWz3j?EbD!$+LmywP7*deyY}t+2mOTE{f|)swS^y{d`A91f zi=LW!&f?bx<(9XeEWpvuRh79)P#l4AStJO53LV$TC!=LYlWV6q&YnvI|=uRpC6*X-=~8a zl*E^U?bOeU%}s(q05{29qp$f98Cs7yyq$2kv%F$xb?sJnP5#b$YxeKHUH8lv<&(bv z3Q55QRzO&R^Oc`b>t0sTn^kv68=vXh2G9}58wIuj!n7VhS2QQ>ehl>3`Zefv5p?{W z{JS7Cza$#?zaXdC?L4MHuTnWj<1p}{A3rAH1FAPY(Aq|48y{+K$mkrx$UXG-`K=9g~IzAA z7{vU%-j!&otEU4R6Zr(m%_Zs!1UnzYe5A_D%dzBKnTEitFuxEfao`KpUpb*q|rs2tOdt&@7r(o1=+PwL*3@3 z_dt00a+n+kjbqRsPt45Symtm(4cL8N*O#a8OHje=i`KBC(8$Gf5&lZ7R$8YpMj4D?&F_6&pee~ga zFV&VE@evuV@PKU-7M_S|`5fZROxD-n@0R4H`N%g8j{H%!gGws( z`T2*xsNdQAskaUK5)Nu}M2QtP*8|4z%D{>U;OFW3;y|~XpY`t=8SsrBo~2ts!kvH{ zA2sVSK#@34`W5SwbQ+hYtIKTn10GXCn3%2mLw#pT+W~17vgIv{{&PReesZtz5;;H+ z2mfkBO6~9VnW+jbahBtq#l9SYeF5$a3$GALm&#i684U2>t^jV(6huQhiXX5B54;=& z!hO<6_hp3!gN&&8hM>WJH>vi3R61O{IDFrSpHyqKreaQM@0z`v>IX#U!icvj1&?S4 zyR!eB7Oc;2?7NJ9c-H39t!)45Gwem5v8r3cwa{mZg1QYJPMK~3KR8?IpZ7;PAeSpA z`|)B^RP{-|s~hr(U^xX(yp|<0@F)`c;+@$0dpNhVVz+24 z*EWK86_Kq%4-!W|@y{XpR`hhNPQh#hJdM7a2a!?g>76YUihF0PWQ=cqf#;6(6&Ts; zyoY3X)!Hk&B+M(pP%3SEe%BtDLDS#%jO^eA6t53@o$R+iiAReMWQ8eRNvPd>d5 zT{kbZ8xa7^SHLaLzd04th~jOdiEO)p3#mTA-Vy^&;gh~?a+-A3H2%+?S-86`Ge`@+ zdx^_a$ixrtE9uM&%#Tfj-rr^$rU)7SBKINT$(6$QyziN%LWrz6ia$$nGs+TX z?oH}cpniSxXDDinLD!>%)cvR677`unwTrbP$E!(;z7TZtx!BtdS-@L@-y`?otENq5 zIY6v-?s^@~#T{&?*Q|UjOit4?ipvhESw$=`ckAbJlc7HGK60&?l+n#ZyPbp5K6Tjj zRhaM24tIx#9$JHZ?M?tqE_~{FtB>2*=HmEe=NI+zVP5tKBcz`=2YZ0GGq_+%Llq#Q zUq0cLcdNzp($#C<#QubifNy4mAMm(H*lpG0e!KffkqMQkN0Gd|{9Q5Nx0UF2Y|xx< zb3P-DL(Givf<&cO5ZP~h-&91A9aM2%Xf?H8=wbD8Kc4XN9*ScS#mregGDKI%IT9}N zhawQK_HEG4r)9x-0q0b4NmWHOqp1ApaM3ju{O?~U`6JhqC_y%&2Aw>A4 z5_mQe+Lk|CCx%RK=eQDQqyDZsODca!sqbSY<_cNaz>X>d5Hj>Hnz=lC@q;Wqcb(*8 z1i>^EYJp(>UA_JxeY?Sdo8M5?rqKP`V$W0wo)yGw3`$ytmpHgjyc$j|yI0rsc{jUq zwZisv?eW604W3%i7VjelRLF4<5C$0r0xS<yP*wHhnxLg6d{=q)Z)fHNFe6~4 z8{e|>Xnp?rj{sAK3Ll>TZl%yV$*nsp=v)4YGCBz6d6}l%%_kZLW4Bf-Sgh7U*)nbW zo0qZh5reuuUL(i-kA7Jw!t`B|i74O#h{Ve9xml{wuHJj`rfY`xYNaJ~vSSm>XR||w z^ksxU;fE0PrGo?CXq%HpDqr<`fG%L$0gz_|Up~a8lz#8n$9`hm=z1wrAEYza8b3%e z0ZROzBVLN6i4_|?LKeHqsc0YjzSXkLA+iX{m~GDVog;6^7BM=JrF-Ewpq&`T+M$TIVUn+~9eu@H zFYK=k4?o?n!rqQ#)ZVfv|M(lt#R&4HkCqbQ;rCG>(fb3;Jy$}$1r}2a9xrhz&l<&7 zN?J@v=rs7+IJps0;Sxg@nThRy_;4FRUw9%EtnPz^DQ^@tBoYH)LJEy_1;(aT2(aML9LUVKP z*7)3FlU`Fl1zy=B7yHaj?Uamuf@;n`N;bgXImHUuK>?TgoncS^xZMoCwy$!R=R9%v zTQC=b##Y&>A`PzBY`$9X;P^V_x8vdJ5L+~|@WTFd5tnmHZKgI^HRJ4DxVZ@N6iQfG zcqIze!pi}zAy^N^rDE=nw_(V?15`*XodZfGl|d4_*PdZ1uQYLXj18cJ*xOz4S{{R2 zN==0h9iG7(0QVL=gU%Xd`*?6@=4n~5BeuU-{Vw9+y@WbNevkz67F7RhB++%XiS4lw zNcvnDva(i|JZ2_e*gbWzClB|}0#{ogEhPMmBe({3zF?U%sF^@qK-y?e&*fY7yr$n{ z?#oq_T*K*ygQ_RR{r0)YUn%fzx^d0-9%LMoXO2A>9rlZD;MoBmvCN-8L~Yqr+0dg= ziSY1j_-ubvOTBGj8)ay`UM$7(qS5uQFyccf_?A-lkj%YAB*qv!pfG*CCDPON5GbzR z!STt`vsggA$w45>k0KY~USrYKnmmQ0hBtZ?!|!zn$j@?D+PvnL7hJ2(np{1|d;MRs z4agID&U_Jcr9`@8L-fwsl7fsG38@3@LJ##H3aeF-HVzG^H@sR9PwwETY-kJOysA9= z5L=mwLERSDh;$PZ>6cX*-+ZVK#{9FTR7;Z5Y%8yZM4q-t_U53gXckHLhqlZK>a|wN z=qIQlv?!3e`TULrxYK9tWb>Ld_~yFY4d#IKzf57@=bvy!&@YKc_sO8db@mdL0h-@0 zwc2)VQG9;rbt=!%5sf9P`Up#7d}u^2;hZRW3sPk)o{Q$P6ET!n_sA;pj@s)MCGv<# zkgs~GtUQ~G#C;M+@XdUNeb4A|2M>Psd|HtKd^L-Vnt5Nvd$|#O4^5}q z^fcbQK2xOL-06*7t)k-mcGPZGk9UQ#?}e>fH;~JL!$u@m|CRDhSqrSYO)4Y+!W+sp zeD#kI=0Mt-`BLTNwcY35ipPsiVlEF-$%a5Lh@opyX31stS;zZvU`v0ttA72j9|Zfs zjNr*1Zjn+4=-j5q_M)%-cCB^iLJ@beVVDPD9op-UfcU}gEpiC@@>x6W=k zM0j}>n-E?!eKg6~X{e4)wkT#$ENk}=K(JZ!@6wmku3%#PjqwHLjoD1mhHk!|^W zX~KJx$JNU8+OINVbH>0mU6yPSgEqe*maHLg0sO-Scxc1X1S%W+y%6$XU0rbUDZ)Ab zhR77>o??wXNtU_8cjrF5wzUJy@%80{+|2k{GE!)?qH~nPavr_M#u~JYHT@N2GZ9lt zx?dIOe2uR1hlT`7V!86+tgNMPhaYZWA`M}~l{1Iq%j^})zr3e>6qRZI)dam9_!gyQ5aSSQ^tm+SlN>T9N!&&1(AF zQ1d^Q$3@uR^PErg65G@MxU(bcO~=l4wg?jc-MuDK&w^yG<9TPbmLaiIm|do8HCb0^ zytg}Be<~Ms&Z7q2Ca*AV_(a<9HQO>e`a4tsYXe&HHdzV^Q)8#)CIwM0wx#$14}McY zWOwq2Qf(*iNgY>iO&($%chb3jla9#Kh*!twYYcQ2B|Ke>7l>K36C_alF_}_ z<*R2ganp6xK@4!Ru!|EklUa3aB;h(Q=Yw~DfbxLt_hxBw?F&`h@6s%t*e8`ie?9Fmr0;*1zHhOs8L4kTcr*rx4?p=cSX|0Qk-v~8YVEtZCo~Y_CD}Qtuc2GiE+pQggrdK(qt~B-@V0w8#(A|CAe_^8HZn&FST|( zd$L=ka}7UfBX$TuYii8~tcpKooak?wR>osys(_GY$Pn`&#l|8oP%Zhv!0yba0=vs& zk992gD?Y<=BG-M?hf_VHxJ2u-Klfgs4X$}xn9)Q8ar;Oo_=KHy4r|JD>od91bGZsL z)_UUH=W_NV1$0NdW__!j0kPBk(Yn*a{2JLn@<_~wn6W)!N5zicJK`&-?U=54{sn}% zY%J`yS~U9EdHtfW9I0_p9v!>hUqLj*E54PRVluK5Zwc;RJ)=@$-{JLtej4RXv(*e! z>__d=gn>+o6w&hLw679_jbJ1a=XxoSZ3|&*z_R#p2ktgr@)fb1X?>2|M7nDs17{bP zM#+blRANIkaw9JI;8RF>2ux95N7`gwE8wTs)@H5a)55eme+O9MmSl(hr4ZlqCOAQ9 znrq>Pbvg+z-|l<<@T}rd3p~eYQ>eU3DnYiUz!S6b4> zPr2jFO8W)dKm6s@{n+#OE6ZFrPYQQRGvfWD!5;S7F73kztsg38W_Yy)t=F@Ns5GNR z#g29_A7jd;TTSiO;n-IJ?ff+yWAFu-{!Ua< zw@*-R-4hKaFpiyla+ua^LFn2mcPt{b>fLbdSz*6OFpRK-lSy*C;D8P?Jp6P#qLEx? zV(93M6X5go${jHX$C#;bs+wio;_3RmzFLdDqXs2okri$pZ5OReMeU{C%9v2WL+2X)=;mAH+=2-C!8wt8cu}&UWpw!L4Z$eo-=hSs!&35tWGXr z_shhHT*ElpC{g+$;|Xq~X3Qtxdt!QpUb$?24AcpMd*2|FM({)EDzd>tas~FOd(`TB zTy>7+dJoHNAdhYG3^%c4Sh2ND=DLT|iye=Dn=9^*I4#oxY2(d5VY;osb_coiderIG z#9R4m;>;~UO^NExc`r+>gl|kK#G`DCYVaP{mL|(L&$?U=i}hkT z9=c#={G&KP&??9QMRheQNN_m3^~R2hkNuErYi(qL4>7B!BVngMY)D{FxM2+c=s1mv zZ@US=(R;t(F8O~dF-*N*T)LC{(%=fH@!R>Sw>43s8+Sj(4a{3wZCu;qyWa9UK0cQe zPQrX=#l{HC%7JaH&C@_K(>=?`cgP_$q0Qu2aze$^njN>HwJ&OH^Q;No(cjc?UaO%UChwYZ+@2Chq+H@o!;CoP2Gv2=!KFr z*(zia+9P2`0?zQwypU?P8mH4uz2&OYG3VMf%dsFk<=KBMo&VgR|A=|vl)jG?e2qq~ z#7%sYksn$=)j`myiGKX{jka;S3a;RQS7gOt=}`6K>!@JWMo$i2jo`TeqZ?}R zZsv=w9O;4?E!I=Kf&!d!p9Vjuk&=WXL&ZS)*)H|wwYc0o-UjX{${G&nRqMG4z@Vq@ zg=ju^kxaBYVA}oil%W0J4f1VAfyd(HB~OEWNt~=ivp!!x+r8L5`=4*kD;5hXq+mZ0 z43f&&t;>Ylf#cXzmbH{$wnZsj)SWeCo%)@+7^ zWVBcSHt(Y8<5y>D`e{ZwPxv>xQMG|7%x<*nGjy#e;)?M>{7BG68L?>4vPpC#bE{KAwnJ|`j= zXf+Y-YR9@#h*R-(Xtlf|uS)h3&JW)8*z*Q=)+|v@6z(~7&jT~ zX@M4S^yoi7{GR!|5B8(R7q!L-Pkq-q?vZb=lEj*wc)%`&E$5&<^r=X=mpy%acrY-O z?J`z4HH0o5vbHcc2)HLI%NDSqQBPPz^aba>U_@x4gBjj&rv@b0+dbUE7D63B3 z0WL(qVgNzZ=lvs)EmhSAzsp?h5$E!M7k{bWi9f0Kagm^P>hDxWV7{xD?jD~u7T9U% zQ)r@;%~$%16?O`WgWcS>JzuMSb9i{0Z1UKwO9BtqqUnE;pWg|A8x_b!gic)HFP!-#6`TCD)VXt4f$?B2{!s6sr;}R=hf3@L* zat$h38nJw-rxJxiI*;flVMU(U4uf`w<_xI-@Ynt)A3g=;xHAf`8S#H-Q6PbF;_;hn zbV1Tg!X*keoReiD;cJ}ZPq^d~YTOoYN>Gp2<*(OoJRx0QFSK$du{ow!{yxiLbBwpB?=?vJiX!`3u_xyh-ma{c@)1 zQHrV$FbIJk(7C$j9=_s*{&u>N^a87VdDfn!hhcfR^`0pfK3wJ@oD}s#Hkz-Y`gZof7f#8`53N+wy!VLE6a4ltuu}IQsbkhq|&% z0D6?+jI!QTyYeircahF#*aKgXvQQ6I5h#4VW^hkl$Lp)qKii#WzpeYBAH{3A8g<1Rz9pIOf*_?!x? zBNqxIGeNYz-t4>g>=lg5z~_*f{8p{uO*%H!Zqi08GN^5>d6qD@;GVxk>a^!y0(Su3 z+0AT&(|q%VkLe=b*-3RiZt=`*Froze1g}x+kVHV#1=DLVSUtzIR$wLMaqmuvd}Z5d z-j#Hc#JX{awB724hPZOu{*u7rVL- z=p3BFXH4|qwqAS86x|@!^mfMy1;Aem8O=d-GfBS zw>Ef1ozC_KnWOXRPOOxbQ&W;(Io1_8K!Va)Yy6XsxBu+we+kf@T%FVb!^#5GS6qdJ zM8+YsiYyqZVkxohhFvbuL-c2b(6 zPUzMv&9XgkkG_DHPES2GV$n0mOfu5R(9yTMT+Du~Lf;GJSIUc1aVr1s5+^GWXub*- zzN)2dkk98N#j`yi_(b?6Q^fX+(XTcsaqt!jVHR*|uPVQTmQU8|eI8G4e~mi1*f6ZU zU-^kTIAy4({Vvkej;rvouP+o5fF0;hm!YPaqsf<0k;5{m5$GO-YVAHiy5(d|p6q-C z(rvHNan(B#1jt{e)w&_B-%_U;axU;e+{w3&QQ2K>=V+jUum6HhHS&Ye_q}2KJl2yzS~PMiTc7=fy4czF zR9o^i5&631&)?eI?|SA6gYMvS6orc~6G5@A8@|1q^Zd#+D?_juzItP`pT7n36@s<{ z3sci(>d1ZR$0KU}!s6}ah8OjlJGJd2nGIP7<2j$-V%>*|T8_Vz#bE_9&f18Lk0%yr zPrD=+d?nuW7C;n1BlR?N3$$hQR_U$~N>MWMHjb?zR@$G;c5SUgS&qg8`A$g)2oHKC zvPfUEgrkhzIp|3kAW_qKEd%c>=G>C6C%{4#zDL45?*?*OX= zjvRf&>M;)ygeoXbRRQ;BDqszE_M4t=rbtM^UVxXy!ycQ7lM-4-2tRG0@PWYp`OmX- z1OQw6Wh@CceJV_fk?P*F4}c6Fxo`sqa{Lknc!RsC+}N`oRPyH`eSBp^+FjT zU4LD^Ax*ieLH3D$=2xdlLxgPRZ^OFKFs`A;z5Ic;&LP7(XmwwHI5JzeWzScFO0}H{ zBNx1ZNgk}8Z8_&P&EAYRYCq&is$`BfCA_2IaI6migoe%`P5Hv{JNZ5;)l1w$#UoPP zz(U-HR`rCb0uVb}zP&+IhX+TP&n7`_M6-*ZrN)okatl}>n(M<*(NAy+m6w^M9M}Ig z-!-LvY<}q$_dm6qMiA0wP|$Z9HCKY&YMpg5aB8_)4fJsa>%8~);1{5P;|NL?N$K>Y zA7`hpWg~iAPqkU2b`Revadz~=>p;r7ul4E<#J0{2K@wkQKDMxdbUA8H1=s$tmHKq6 zNd`GJ#qap))P~4H?vXDm)ng-_cn=?ub)7wbmJCs|lDkPA|eh}Twqx*?O z1fpU8=oPl*yE!qqfPOE{gxM5&1z@V~R#OtK7|ti*cfh@8!B@jrtpNUwpiUkkF&)t81H`kL6iuSuHi?mysdV0B!=scwWf3F9ybjtw|S5f5( zq?%?6$RfJaxY+qrZPb4lZX$eCC3aeF4O4dZ_~MnleWdxqeoMVKOz#2+QJ*dmh^arX zsi#Qhu<~~<%zcZ<$y36fsJMS74!mATCv|0q*Jhx$LyVee7T%0!U#MmQHL)4nxtpud zM!>xcj~rAm3gmS89gM-35T+RFFm~I~9i6Z)T;4&-u6)av$j>Cq@Nd9tH`u{MAw1T; zp?r42PCswzyE{}x@)Z1^iftepat^4 z7J1wLa+JxY&E4M>FSaYf8yi4W}MOJW<*o(ih?!3GVU#uql0V03gzuxF~kVT5`QK#R$`W9!p z+fJUZNRK+5w}|5REZZdkiHY}+V?f_1l$2LKrSf<=Mfx1g#KG1hFaP-CCaK%fNhyB= zXpMCKCio?ara+vPj0jg7aMZE#`9Kjr8{yDkFhB3XwR4VetM)Gh1t)46n3FE*e6f@TgA}!u(V$|GnSQ!xRK0WHnIPyKVvTg>Yy9{; z$sH!{7Vto`Mnt6I@fSCTn3ThM4I|nf0`OLxdC86u10*I^+#bw{3lQ1ssqQE%q$47WhEw?SzOC|EKBLq)0;q8=eoX@r!e( z08p)5yBS?pOjYfrm)Se77k#m{G|~VSq7VdjaOvvxTd|{WpYQR4*#5|H9KF275l8sK z3c0quGZnTt(pd{&$5Q@AsaNe*6s(1bYMo|f4E&FGsCbO;Gy9)|?$eb5wrqj(gR@_j zEVb_FDv3lj?7!0(yBR>5DI}_)9SxRNdNLdCs50Mgl(2qjoxG8^?N`INILb~X>KHK zKzXKsWc~cjq@9 zB%3uT2e>s$0P`Tj?cWR8A^-tNi<(6T{6wY#k(`##xJo%+UA<4mKdW3M0cFe1+8r~W z5*)Mla*@pZ2c@8(DmGab)a&WPnVEbmX$&H3-aO3bb6 z#q21DHKcqe4#CHU4nXd92v2PO#tk`j3`xOs-zjG&U4MPrm`Q_I3x;KNhH5ExT<<%H zrjq9dJn(h#G0E?G|Dq?ws9-Kct)75VQZ6QH!cGPf40+(A57J6cx8}okzM0nKK055X z_)NpN=?PKVPv24efMbd5vW$|UwQ|hBi)6e6tY9)|0S{VOsPD%J&PS;y9FNY&8gT(- zFpuI%FC?c@0-u~i!*K=387xCR$Ik=7m{OtCx46dGziY%9Qig9|AiK&>evyxB0=S}A zATD(!2E=<|{XqKssZ7*~YjvxyP1Ms-3?ay@eQ|V27K&>ti{^RRKTdh_29%{}@MtSE zJQ!gOAASoJ-A>%onyC{AZTk$az4BCkj;_1Dkvp@_gv&PRnAd!zxF5Us%3vn55MHAu z8C(E+qe&G4^$4(i0ZpJ+Q3VQ!2c>G&rjFO$cLvl|tUz6X1dx=A)xYzdAu&<~3W@i` z#Gv~r_ryLvh#)6sD&R$icjv7-O7fL!KI4q2QP$6M zv)+}Mw{lmi^TUjbib>em5#3{B00DevRDV98OmMUHTt=KDR9+o^TzT9!-MH{~Ri!y@ z{v-&W#cJq$e?^D{A{rkTJ+Yaa%t{GS%T_qhmPW_#A39VkXTPt*-S-3pk7(e}9z#`p zX`qbFc(WsSmrh~qLSF2x9g)0fnccOt7ZYPEO|#x#4Rjn$Aa-!oIbeEs(d@cp$AgPt z-B4c(Y1g`83mMkt=+6(@AF@D6GB+g(E^o%U3Zk>GEH3}>qjmMD=?k#XWKb)>F^&ZA z1mp;0ICG-1zY3!dN8k-SQbuCMm7jZQ1hdWpiU60{**C*$X99I=nghv)H)fjeiCqOF zUm~Q<)EbDu&RF>3)^t^2F@Z5Vuxx`CD$ss#@g6vRdiJvB_1FN)_2$;{i2&tt;Npe8 z;YT~f9^3@_&3@P&aY>3OqOB|$EF`d~Nr1b^omc5vDSdH+VFGbGsq%4L2};br2^69( z+)D5|wwWX_5U(~0_&fS-O0dK8UvK~^>1b!6wUlthCSG(B+aJ)v-Cqi)p99~VV~D>i zK^%mw1P33=1|O4%1{TC9(llm$NXPWXzts^HTWEW zyY!|4W@xsb&wP2PXU`oPE}}P)Wbnqn3^BV{-~IrxRlbqPiF!cnim^qGYtFkN=%;Gx z$ZQOLmxa8Hev`UWrc5CeVpMJAe*YfpeOBOHgS-C%h%WqL)PT;I;r!`L7myZw%yxE( zV}Q?pcQQ%`S5B)7GL^pPSbBYXV$x|=N z%_H~xxhLgUU>er_{LbhHRWFG?ZN*hwk#|fWFg9vB4_!O3nddC5K=>o1KCah0#)U48 zk6DXm*y?Xvm`#yk4hJ-`bc`pjzb8236@5n<5de8$o32#nj=r)#9AI$xHvJ(y00@gM zz|MUmNQtw zl)89D4He1&=MH|fJ>Z`zrV4m@AKIEUtHN^8Z|MrA8cKg*>YjouJa1TjEor>y;xho6 znuGd}T8jUxmCkLEpA#%7Aj4=EsGXsbeG%~U}6u}(ufxfj|nq}98MqzCLUi4*T{ zbUx0-{m*Kwa{VryMkt;ya3#ef zytK{45hu1F!J<@KvdnXAD59+Z*JtBA3fgXYv}M|hzlybA8}ZSqxQ(I>n9I7*h|v>x z8BUdR;^hh78J@%&Gsdt&qnm_Cg`lU^r|fOZBn{pwgRTo*QS@%aw2CKwc}ft^$E3X zrXv)HTL>CfFE$i2=Aa)d85Ml_;e(JAx^tlic4?T@f-bXDd_uczY7>Ja5u9u2%Sf#; zp7v89=Zludghu+YB3(budby{3@Ye;cAf>+|}ef zV{NDDnDU*Q8US*UdqWYoeFHKqv8wEShPWkon^|!5zyzLVZ@1Gy-n!HV@9rI#M|=Rd zXy%+J9m#0IhN#uhRAxf*G9nvjzVOkFykvLqDf{W6sKW~vIU5!Tdf8$`3k=`1UI)-> zVEQAv3k!YQx|AdQWdAySNIPOfx+A zV)BL+Z2)po@B@5_L0R8}itcJN`LMbg{ZcIy&zLPjiib0;C_1H0v!Pjc`KLozpZkgM zgkX`5da4?uvS}{2$gn)zS4H6E5&iAs!^tcam%>Tb z<4qT<`I-g99yJuR`+D*2r+A*mmgbt}F7YrVdCQ)arHgbrDCQ6(ElT>KpjT{D!qVzD zQkb{8$Aij_Q4{00dVp8I*ZsN6Yc@Tk6*0yF3cTZ5--wl$>tsQMOrk^5WK4OorJBjC#A82}s>oVP6)r!@2Z6hFz$g4Ej~4f>dq$?h@Y`P{AvTRxJ={8mTu+!`WX3 zmhN}bj#eV5^V!^2+b;QDI?}<_S8eUbafbBiURoKfU0SgT1X=hYxNhCUhE&@IN1}hE zp_ek?*gijw6~o0QeuKNg5U7+{=6ksNjC%^eFv(skIhgT9@oW;Vs{25NTBTnR#|#hH zhwH?~*!6Y4BA5?r#5VI-08s>KyF0@3$ZJM-nSFMbFiKnb<1-1XhAu#}HasXOTZ#;K zup(S8V%j@$M?bLI60=I~Xl$p7{-VV%%p>J^V3f5Cu<;dvYvlJxD9`m#%0q&)Y?Wqi zJ~tIIGu~^Dox3;;kD077qH;D3K+o_d^P0R?wKCmh`LJuAGuk+bnlyY`H(HUIbools z>S-R!V+wvcb%VAC7wUg`3XiPC*Ph%){;F8J4xJ3wk}7i(zh^x2cd&2qvL%}q+IqR@ zsax%mgDskc6?XvT*sy9aZm7wLxj1oOjAcvE)#XI97#&cx5nDD;>|}rT>z6MZV)j5b zErG}6C9`5&8djMHtBVOrKc;>Ga@aS!DeqUv>iGPoCH*RWb{z{(-kPc6?vs7exVxu& z_z9s;rMn+dHth*a{@#)IvYtJH{VowCk|KzjLtUfaN8wnk6XRrmW4%YUNks~hgOMb# zmABazNOB_y$;S=Bsh22!kr#Y#E^2aqV~kL<>c>6YBrzlsglO&)MIXLOR@Jp6h7K?5 z;yKEtPZ^e%tL0W|>Nr%8k~ZFmnQYT+0v=ZAo)+iVv72@$f+KbbK9iQ?(CThgYQ@vU zoe?R~mD3UI2w|HKR;=S|Ufuvuwa|S0_!Ch2*3{AhGU>`7#Gt056R%rtoe5IfbJVky z<5R2+^~$XW>(fx%%l-Vm7?-t?Vy6E74&odQd5}w+ij|h&rw-pu2O{R=5=TW?%}^}1 zRJ~q}qzFkU%)7wg{)FN`rH|TJ!ZzRD0Nn&pm9JxTzbbaU7W$?uqDe>_Lv*&hTHOrt zvYI`CC3&o(VwA6-yt?LKD)~B#2(m~)uEi}dcpEwy7@N%c

zQek=MvroIBI%BB1J z;m}C8bV*4{ONR&|AWFBQq;&V85hMf=C8eah`v6KQ64D(4(%tpV@!tFXzgY{{a>0W0 z%rmoR&)&Zf3qBWME1IubUG8dUeU8HoO?#NyZ%?MGCEGr0=im?M3Frznf7|Ids>BRsQ~0pFV7ByY$pZ#l10?->XZye zkljV9N!reB@BA+IkSH;3_R0rBQtLp*Jz8`TE7hSL8>z1WNF|i}_OT|ycGF0gWZHr4 z#=nK#yKGz2_0JLwo!$Ve&;*& z@7;>y@6!_f@WDE=P}619gdwP6M4^gz+^V7A~vJ|PT|AqLwXRDgMDS@YxB$Ozb*!scGgtas(M_W?g7gt zRE$5sjB>ML}0Wnb-Ql=721HRB@;}}?9z;Dw6S$`5lLG@&R9p?|pu1U`g0liUt?x7xJLg_9!7l zBhDn)Jtuf6g{D>eSiRT!Z@}cCkdQvNVzTa&;dhuVU`%COS1=)NMEP$a? z2J(@>kup*}W?Tr&ogO44BCeEx@a4L-934`ELJ*kmlJkzW_)^ynq(XGHH4*zkh8y> zyRZ<;q7n4p=tmoL-HkkozP}|57L@)%?0E3(GjIYSR75RHcl)CSkl`ttI~90hg3wgW zO^qt)+I1<7#faSBHXL||+>FrMK%kjQ|A%_+G_=8Os{pC45zngnlrzEl-tJu?+QXy5 z90!MI0rS9Hb}aytZUE>_3BBwlL`q+9^7b!|V!dp}r1yE!54KQc;u{4fWE`#XIdej) zgq>fmN|yqjE$2I>ys9cqKmi>Bdh?~oeiD*^4+LC)E&8zmUAr(kFZMhWRGAM-dMQOj z|K{G^Zc%_$Rh2Tb>6ETAfG@3fzPOW&B_@&;-YJp4j4|Jwc4=BIb&*_KZD}Up-%r4F zimWWu&qhy&9>cJwF(_&9z@6c$P0g~+3WiYKm#|uy%Wn1KPuUV7f@U?W=p-c0cWchS zFS8Y>P?HN_YajcMnvt{=Q&2kwu02ofx;&f3|<7+QRKCBviWs zYx8bx1xmHZsEU-VLoPHRSr_c)yBx2?l8LM_0!gx-L(O}3NY$RTFUf$`j1!4H9mu4EI*lP}43LqNj#?FueK;~h`~th~u4MD9{}5Hc*G z4G(LkhM>&bH*-{PJeT58gmm}mk@@xemV>V@Tdz5bNR?3e7!%$)lqrrDB_W8(Zke>_;LQWW>TO6>*z5Zl` zxqKyh_-8Sacl15SGoKK@6Kjs{DZ|Rrp5vrR^A3J*e{Eyq5==S|8L)b?c^dvO^`(dj z3~%s_9d1qiHGu`|jt6N|GTGwWh;;P?#^&6=o_()F`m%#pp?WPr{N_&&Tlz3Xt7VJ+ z36L7fb6n~a^8N(&`$i|Vz2K}cd~?Y&%{Zk}O(Z(qOhTCcC+goziy#{T{w0+SvP4%= zjNSI;WiN*7vA_H_`Y7tc^wp9yE)$oMhv0!>P#796*s~v0(LJt6*85Wi zfDsiWV%@nkG;Ps7^Dqcu4A^S~P35{4(-%O(M~!w|Z;vv!Etm;YYO~x5YPtG`o>c2* zfmPYV+ye@AeNES@XT_S$9ez_$Tq9w_NRvBcl2ldYGN+@Vfi%sbbrpsu`w z*#Z#vRbh?)FR#4C+w=tKSB+H6ZWoF-@jCpI0VGAOzlIZCwA^=H2W8_|IY>csVBl?i zd=H4vjG$8(nl{Ho@-!#`1Ef?SkaW$;d+GR( zGAI0>B0XQB&xi-q*tf=mX=eS$eR*V^u=i@#$fqToJ}Lv69J21blYW1GfF6x-c1BMx zE3P413jl%~@#u&bYbX@{2z1Z0qs;%nz6+(S)C{G>0+sm2JC|4Q-D0a&55lRh`BeZ6 z(7yW9an5m@bTC6-#<{|~nTxEO%NcL4#bh??LwE-)O(P9!S*-TcMQ6dujPTYl^!mE- z1KB~#zw1?|4(xPZ2_S>m0Nk6ZUDk$B^<7S^c@DiD#%qE8D^e8E6=*zK1F|l%Rf(J{ zAmnkET;QhT>Ue9a8dx|0mkC9rD@}@+v!KOK8sEdghd_i`($qMr8b*Iv**r%r?bn1% z=z)#V2J+9002=pF{c?m&Nxh;`quU6Gza!N)V~^F@EWp7n85KHlvi>VKW*ZnEtX^Fr z9c51Uma4%DQ1svSOxvzsr9%o|{=9(2-d_4rQh_9l3u0=A{9V|h-C;{DpFyxt)yTgZ zH%`Z~qZ0!{pc4KwJV=DmsxT&c8LB03YO`0P-+r?D;jez$V&_m78>ftC!QDa#YK2JK z3>+2*>iHw}Lid$m*Jh$_sp0d9r+p<3CmPfG>k?1m4u6E%6agB*a5Ur)UU4J&P=Z`T zkSPb(xvOV5EyUr*b;bfoQ;|rj1^w<#&!JE;yD2wpXzWvK%l~{Dk-VaAE0Ele09pTH za4ZW_U)pjWQUfN=>v6tRw@E9c+dVQjbKM;09}si!ATlhA%=uJ4QlVA*)B9A%(DA{S z+*s!tAYX{|q3SbUIi9lDVS48Erg_8seNeFGeiq!n0&TLC znl{fo{%z48VRg;L46ywZ2G-Uv@A zjhrgChY2krcAXo3~lferX zj)v9d@vQhnG1~&#g}y-YHwy2=yEOG|u4&3a10PUia|+d#nnxI)K1YKmd$g#IZl5_h zj=vj~FXY-5&-q^+KDem-&Q?GXGVA>-Jo#rZ>mx*1MTfD2%zlR@1S?;|CP z8@afu`X{X_GcA8JBY^e)bQR~eO za;6?l6-Ss^f5-kSdmB6FSB@F@At=U}^d2iXOWsKV|aF~9mGEA#kBIOncG%D|=Y`M`g`EKB? z1%E&Gwb7}**z$TgHu`f)CU)rNoKh@g8IT3k-q3W0Un@2;Dz6;!#m3 z@2qZ#L0Y=KM9KUA+S2gYYzacR9Une?ST86n83K1#q#dl0-`O(f-Min1 z1yT8dRq54nZR-rhOS^F#nx3Qh4Z=DQgXFAh;b6sXj zPyBs7Q(R^w)_UD@=(^|~2KTLNW1lw;)nT~XuU6p+GC!Q9j`?GDlUDsjYGiYD6a6lk zB2@Qgto59#ajSZZ(P+QQ<&^Ir-y@CA!>s(L_wJl_BagFX>c4kFNE&%=d!*$8;haAp z2^s87xO)UlXsv())TcDO-)OY2f;*ox?|_nZYy*#=~XxNE*P@s}DXA)_q zLH14b=-)o4OdXO2fe2akT%T=j?2M)@-0@izw+1qdUvl3I=cfB1=f>r4Xh-^iI4&ws z1u!a~16P%#t21z1$WNUB*+DC0fl~F_2h=hDnJyTj!@G8DIqL%bAD3Dg?cSqSWyOQK zat>pv>6%A40?>4&?YnEoW##jUTL(vpHwMoIYy4mO&L3EDL0rnn+M19!=TYK!b1UoCQG@UCiZRtFz6_WqsC>bbo&>m5EWJW}xC2 zYEC7JsGdzr@iTv}JDZcOI|gCm&TVLb z*=0aZv9^$h!%2X1yf?l&;%j*~?-zRA5r%_OtEXI>tstf^B5bC&Wu)9@o4GFjq$Mnkszv{%Q^4Sp{ zAao>cBK$PQ&n&p1W;rEbV0mCs6hKqvZaW8;Tx~*2D$m!9eE1B$@ckQ)}HZdB9f zRipsqC;krjAUJfohqCcd2}6% zaog`P(8`jCH8$$sIAm^+Pd-#}MvFCy3uUuV$f~b|Ng$_=fkA8-V>Hi_q*(R& zmHz7NodjC)p-zIQq^8uynMMv%y?1)9o@WD+_If}mu1?rJf41{P_S3T9bf}Dld!owV z=BO+Ge5o}NT`KHxTIUEJNr_L&F?uto@*Aq=*KR3+^1np*j>Kk>nN??B~8@Ztd65yPayKD4g_0Mc~a}yGYDl8pT#X!M1g+k5-S~(tHT}sTkh!LW52Km_hK^nca49%`)kLpMKu zZkzvN#Ab{#mIrppXbMDMVe1QeYL}@N9hGzWtF)`0vy8`;8M$d`UJ+qoWD4bXm58i{ zas!v+V#PCFTzQtEsBu^plNh-tO%m2NI3qjg^f8>8sx%J|YcLkp71EPgPb_ zxX=f+N?k_13vZ9y#6b{wz_5t^j&Gu}eta@yK^z_^rrdWSwvC&q7rOgTLW)!ZZ~Hfy z61qvap#0o*9BS1Ykort+i9S!xgYDthL)X_u^vJQVYeeK}?xMSOb(_34q^%a&rS=`3 zOTM&l{P`^~W6=hYjb;M3$)DS_Fut|q2ei9)4s^CJnB8a-=5#7T$lx8u;U>?><1e3O z7U8$>x@Ug(F8M$PPf*2}cT%=2<7l;K_I7JKlW(|doF4w)V1I%OJ^R7Q!GV257%u33 zS+_%yeosKa_5U95*PTjOSvPoo=CJ2;lNL0(;rE7>p}17aw)ReVgnH;n-q@$f zYBFUXO-2b=gR+@;C#X4C!MWF;C>G|J0ZY6t^cWL{8aaE_hJX$eIkf1*r&>dDF!ag zganz6l9H3Z07VjZF0QXuxv8PS!NE@mVwB#kuUn_r=4NOAk;3rzJ*8$Q3ZbY+G36gp zKWF{>t1`#UcHM?*qEY74%mTJ<9a*)8d>HXZ`8>t&Sw;QxN^H$msJOINH}TS256j6X z)AuvzN4KS;Q;hB-E+yv| z#py=&SiANw(TYay-1_oen~I39zc=9nKgi!`UTA|7mltJLZ(vE?`|AsLi^q3#mn4ukAY?Jg2~N!;`Y_%RBiv#5gs0%E@%{Q zUp@1%wzS;!@)dne(N*xfugb_ohk|^Gl_~SM-Pd1UL18f9B6&Q)#F2C&gDx0Hb=17* zxGaiwB+;}A|H^ivh6L}8B>$voz+jGvmNvD5PwAdbsY?G`W}Z1Y8am^!l9rxEs4a?A zbUxIn3)hI})@|w!sC&BALHr1Gu6Iu;;U^{kpry;nr>Xluo4QgL^mNV}~ zjP^-C{jx6EKRFyuUuUBE(#4k>7DMh;_?53h`;F?$?&~8PqZ_2S*V4kW#r-(aZ?i{W7;XJ~g`2*hG1D zZ%V&<<)NSfem9-GXVB%=(qfCE;Rk2pDZfkE;|7IU2jtAPA+GRL26d>T5p7i|sHC9b9fCE`7!)`@U+9 zJXN?bvum%3%haJ5Z@@#~US3}IiF`eY^m}o~SM+RNERVWX&=hV0x zn+IP+t+BUXDorWPV?(@zv3S{aXc6V;1Gv-;{xfD~^9+ zV$r*^5&lgjW7d|q&;7K{*xPgc_&KRjqTbvXT3kbS>hx3dzWAlPUo@u16l629vwKsl z;We7Nc;cf8ej0Mf{%%FcLUFF`TUgiHJj0`)TzfEZae6OXm{uXKnkMkK)SxUe+Hlva zrI&K{G>^n@S#0~l_KvN;`Fg&HeIKUUH;@G@JD)R_8lRJTonZBDfZJHk4(4F)PSNl+ ze_KvRKbQwEZa@Cj@G-p#SyeS_p2w{I)WGf@LG9jGVwCg8a*Vqk{0hovjuN@1a;bNC z=aL|8;5c}&8sX*)+MDp>|s_TyxiJ{P@`usJhH(ABvxgJ-WwxdRBicRyOESHSHSznSPFz zOpX@fm;_Pbg!0U*j*o-QM_wx_m`4ju50?`)S^urHwiVHbk^Q|frnmSQYGi{uu3uN> zT{zO4GVeP=h8Xd4%j;W++%Q~Sqx>dZ-#`sHwZO#@4okUT{^>m2TuI$ZB(y58~RW-+;DXYTbdQ4W~)?AM1+ zT01&%dQE&)(DL;ZIP7lhF4hZk_4Okt6yu&h!o9EQM($cdZtaYHdioiwvhB^D-okB% zflQp#B!>KR9K^y|og$1IrlcS8@!mQRmuyZ2*}~vmkYzkevILKx+^rJ`Pp{xTXq;9T zg3V6a%47xhCflm^I6KM>nLgvo_sTo*%!I-N(Q-*o$74ipVYxbpO|xS!pD(|Hy*1T> z+?2tLpFI>>I+UIX{NGZ^Bf)^b3C|24v<#lvz6vG@lMf4WzIVa*>9YS)Rbe5B415u_$oNWGK{@sEgy|O8L;np@ z7%oH-k^zchw*U^HEl(qh&*`_)TPh(OX2rMgZ!fTq2H1am>RX8g9_U8|bzPKp;8YI< z<~)C9`+;fi!1VO=npaR8{P*vdGZ(qL!vh2J>v%zQ-gc zrq+r=MD&hnp{13PDf18FN_8{h5PJ?cb8yLC06Ub$=sZ&WQNVl3Q+wG)oSVS)f{{PY z^F}PfAH49Sh4mVi9DY7v?@Nskl~t(o5f{-ZyfB&~O()&8w@@|0KxGrjU++)+(O^qC ze#+ci`O~&p%|$Td=DNPSL^sonVap;DrOsTJ38yl}!!EvpGb+GA8CEl@?_gzq+T4Oi zwl4p9&yn?8YfqAbYnu=X&oy09tn3r|(?|hNzkUME#H3+kn{1m2Krs0y+7}L`C@%7%Et2Gc~zr8PsmUiq< z9^VvPtis16cIVFg@*U-N|Jv~O`x8vdUI=UaBOkwvx2#E4+YCqs6xo zz)d#8TN)i59k5{^=5COHgch`wkgv7MW$o$k$cSr$lwnOITMZZH`Z}ty)Lj9Rc-E*P zN3fQ%73y}7pW?oQKS_r*1@ur}5^Fi`*;7gTtcSIz)Kxq7KkD{myre(bsKR!25TjU{ zTNo*}eyb!349)b5OO2)s&|LM2oatE%LUy^3fYK0-l7;F+Aod<=+Kb-*35(^WQ}FwK z{K5vBZJ}W|DYi+s{r2hYM?ov%&WThH->%v``(w$qENuMj%#0aV*YJk|mp5t`%5P9> zZ(eX=SfJAtV1=Sy+~hVy$zEMNAD|4m_%gH_K+=0bjt;Vg;rl4NzF6(0#*$8hDt${g zLstV8kBYv%UOZ+9V?hxoN743`@;Ib24Btd~&`?Dyj9-kRErn{S71ea2$9_3ta>=7T zw~0_!Y0&_4Waj<+xGJMyGB#+={{FZN+Bmm;0_eu07U(2y zpYGN;^1b2ri`!BsXV{ewLE)!D>o3h(DGeAxOcAM)>y>u#)@qr`=j`)(K4Vo6WW*vN zeDZqXIy5{yFyMlkDYLt?hYAEV6w^#THs$SjEE;@FfV-tz9DGuz^5~JAs%q5Ol;l-- zR`sO*TxAH`owa9TA>oG$4n5+ZxG5{QN&cRoL{^V>-Q-%;<{Tf8k!kf|%lyRJ>Le!R zq<@(8R=?9T7qz(`hF_#PmdhJ9hT3<82o(t^r5`Azw^u{2;bJACpfF#WISLc!ejzJh zC*lW?7Rh`v>>+xVCdWS+ZtWZ!Rqpp{|mN~ymy_fOG|U})Sd5ij2F}Nnp*7>NfPz4s?_zC+A@g}OVWc-|9{R0Fr(}&FMN_7W$vvFqxsvQUZT7mdxG77vS9eJ1*ZGmIekUK7kvzevjB!dm7_mP5)3s z5gKQJB{t)*WEXDyN<7DzH!+hZxkjH1sk!#jkUF=hNp~oh8ILLb;orFv75T(ebesd& zwkWoR_;fsFWC`+98~7)KY!UKzH?cX&?(Hki4z>2?qQQ2Au2{6I8Ua$7__^ zauZ!AiMBmJjG}6w$uQ(bue% zwN_XO^NUoTvC`N$*0B+c!&(_)gf_WpctjwsgT|3{->&8AImH(=Hm?c)Ss~zlZVB#o zq$}BcAITD#9(pzGkWBe#VU9-pSFM=FK`0_mU*vcZi$8~6i4*Y44z1yExMeH4NgEn{ z!-#Vi=R8w*mn#>>2W9_;YKzb?RJF!RdD#fo#%iQ(+e>@MNoMP|UEXdlrMd89u-g6?sV=*FTjx`)8A?1@gqNGf2u6t9pMKXe z$^;!yMNkbpl5U|pPPzX$e17Z7(60J9|L%^qT4L~id@mcblFHliHz|J~5cv=LYX>j6 z2%OgIqf!k`&0(+SAsP`{w{PE;vMJBQvcHL zssE+dV_p|^Y$Gy7*~o}|Yt9~PBDsW=d5Jz8OJYcSZ(3w5f2Wl>v<-Es3N>fLbw|;X zMBA_~9~W6va%w=+UJz!YnJe^7_Tz*S(_gp$Ac)j3^m?i#VsWS{UvZ~XN=Ts#1R+2H2q_wP0oSUjAZaxrw0a-wpX^M59Oxj%RhN~i0{%E{sSh{_2+;X5~7 zl>av05Hl`A74|Y~c0DgNU?fX9Y;R&L=iwDXGpzkJN>GeBq10v#mVKgAQ^Ek%GtVSO zYfIhY`c&*=nDIM9KZybBqy7Nxshp?iHcf~5*NzC*Q~cv==QZP|icBamUYKOUQ9%P=B*u>>)3O3#c7^N#9f)oOAZYA3pEdc#8wI_2$fRW} zw!0>IUbSU=qvNe$EdIg}5veWGjZ5Lq*V4MvGycEe6n@wa@jW108%D_nJkhMGDpG** zv}-Q587nD%K2OA~7;GJ`(6Bz!Sld5EKqrxRL3w#J2+%e&T`~%jjy)1$|I37xNQ~v{ z?`!@T&Qdjb!F`zc5g)geYJ5NX()HmDIp3e%%M?$FCpCZ)@oZ~qG`Y6yYk8_n*5!ID zw}Px(Mj5@$og1=bTYQSN(?zzTX=hwsV@YBok|1j9u`jT)2*OhG09Ed7`J%yf{#&&; z2wVuWv!KN5_2>H-a1r`~HziP6vFwGgDmGoIotvoRk&TU3m_ItoN6BKS!`nq;1m8-w zXD@vK6V8U;s}QKCkfl0t;a@4KIG0N+Jnydqdsw^v%dcxGCJya&8Uc+lb1CiZx#EKL z1Wb58-8kMVLC@1BssF+k(K{+oj?^TY)O;CxpN225q@;5wN2MGjHl^Po#2XT}Luyla zQc{xs&D^on?L*PQH<=Nw4qE`?`L`lV39&|S6+w^x$(yg&G*CooV2JxOyg`5b>n)uZ zmSlSFeJ+vMb**>^kz5z`d*CuTj7-VwT_7HcZ2Sr{ZVExS!7sFH2+JV0NxeozaBFW# zMrVe#w!P2LJ3R;q8Wd;NIHH6R?L%eSWN>9VZaQ}cTvWs~IgB`Xy;Wva(qGHh`N=sR zl_cFmvkM%A_;(wA?>)C7j(qKz!`&uL37@qmq$~WFD!t1tZ@T7q=>jjvId4@=rtpXw z5r5SczplQ-zG`oU?uT?F-k|Cp*Ik-_MX+Ux&3@jLY2gGE1FabiD=o-%|3b}%CofLTKx(JsH4>BWN!iQ{3uJv z9%Y{OC_b4ggDbqwdP<6G_Uc~AmMcwuwKq!G(JJ+`1Nf$#X}93#IhGMKH0W>qll!cX zrg8iHy?Wt5Rnlr{y>>Ex)i-ctl;;;RQM02?O4DmlKs9TGknp$K>l1L8&S!iRf2q#3 z-ecc+*xr$duQh{jrPO0##=B~PHl>w&B6FsE*ZAD7G;^zRVnHELEL5#Dj%B_}B=A=Z z1C%2T`<|{j8kz!?1>zu(iPGBLu#OiIZOZ@uIr4RYcbHT~0^L_UG*F!9*M2RFvZ&`i zi*}K20BECB&8B_)IL<+ulAgZ9Z&@@7*i;h6=_x5io+hM5UMJg8RaJtTI^OA8-oL)6 zik?h6yRP{Itc;Ysy1M#95Jp|rl0nAz-qQ)=F7(d}{>C5~STU%NqT7kRu90hFKR>As zPbWtW8-iA+<&qv*i)&rafurO=Oo+}HYAkTyxnXa=n8`*N^@b>@qG z*_inPOxpAi?i{wDA^U-G>MHvKP4sy@%tEl9@kNEOZeWPAX-(BhM(zjO7w;Lc>QKrV|zevy{UJBCcZt<{u9qKw=Cst)m+*5Hv3B)S$(LTG@>kO9dqW+Bu2bGoB1(W~E zBTP7A;DjkSEjZsOJ}<2mzRzP~ViKcOsQnzY{)@-Hb#%Vvrm-VD5gh@cqG5kxgO#)?q#l_e+-6D zsSRe^T85a%`Bom_{&*z&+>R3$hc%w0Dle^&6DpGR5YfI1iHxEC6kbR^EeTL(%Fsif z-^GDCmfK5BOd{EM?ke;jqHRsZkRO|(!^Lmt{7xE^9d3qwUVhOHyob@MMgxsD!QR_r zaJoZ3pY2!#LM~fNX^*pZb!6tSQ^!WiVY^qiYOTnx(cuAlDU``oiRr0<9@f$7#B9--Htz_Nz@yWoMq|MUbgtZc{aGriOZDp^OFMXF1*~z ztANC4Eq{Yk98{HD^9lTy&A^1SNUsvZX0*tvnTLl5KO`iiIAb0FZjtR0J}Ol2ddb59 z`MlE7Fb1q*Gpl;uv$HdlYT0sIz~+!bMSTCj-GO8utX(wjv>bR|04S*IT4MO&QXDm8 zo`dtx=NOU`)r3Zu#O=6rAbg!pEN?ZIL~-^(#|vC1NEBbV$@1D_eqrv}Iju>w4tX>D z(@*CovGIYe#_wYsukO99&QOLQ`I#kt*mFq4gaR4_f!GPHo7Nv`L_CQ9nFNG;Hb3!uAPu->?#F*0IBJEk&98 zxlb1^)iB~aaVgBVe}6u(3tpFDXWLq__q)OsOJHo>-$1R2*QUuZXW&S>m`Nne7 zJVLcz1gkUb!$RU$Uj@@OE zmgU*m+~(icQ_Dka(CZ4*8NXK-sPjE_NEysQ@k+rXGzRF zIdQvprJiYGs2_Ae{`!GYWz$7M+J7xnWUdo}3F4jgR}j~JeB`GTFn_$^>efgL=#(}T zIAGf;K6@5F7HiuTYybV8lYEw{g1M8It2`Phg!B4grOF~p>A8t!&Y{FXCCorq%Y|u8oXba z^zODr-4hrIO<4z4u1dT8%?0y^S#cEK#ye*wx2d$C z6KmOFIDcV*YH~e)0&*?XF`wU_FEEN>h>H&}-c%Hti=K;n*tZeE(x|y}ze}>gPMkd2 z3BaN-wDeCup|wFoIgc$ZiT5kGSvT4FVut*}*R`24p-4odeDxT?AW~=jwrhbz_~yIo zJU1|~0GDMm6)U`m{ipE#KE%5|#9s3j>Q!csk$)*mSaw;SUTtvdNXPPSguls?#e zf8-DgSCna-ogOsB)z+iaw|$2k#_CZ8ZDOiOX}kQnSnr^iMzPYrA?5LQIDf~2$k@MP z?ms!h+#t|2J1?}E*L3(HAjtt^`!~FS`OM7w3NnA8_@3a*OeRt?vge&|Z$l91&jDr| zGLX{ABW!Pub&hmY*(o7FeR!g!HDY!3VR^D9K0ZDOc&MK?wJJcSf>e%x^Y>!5$h|7A(> zjts6I@`MH3<3@izS6#?zlpT%k(H1j%X)qPr_`AC_9Vi@)M-9sTTwUKnCQdKz$j5$q zy;t92hcZw8Jq_}TaW|0|%)GHIg$&(EPhWhwJbLs2g?iQj(_VaNo!?o^Ck*tz%X^Ki zjv60A8_KrlM{Q7lTSae!xy0_E@a5|HF90Q2*;GZGIKw4PP#=QxZRNO@`mxN4>E|6W z#DoBfO2p3bOYQL2#EZKlKOY&gIoI0k0u&eAbwelX&xS?7(9t#Z_g1uz=WkC6Mx8d# z4bN)oUbTn=^YV;yUg+bZ#tggk>#d%Ito_}w$o=P}L84-}*0?UgvitPg-lUIT2SrpD z#gt;+^0+lc_j&E<*hQj>}yv zSV{A-{>zsytF$+Z^YhoLinKH4KP*qpu5iS1fp4~6pToE5iJ(h>Bs&Ir5M`z)(KKR# zDJe9n=i)x6e1He^+x@Wusor}ULJM@$f6u>QAVPy5Kv-(K{`Y2D#+(a#RR`G0_LrsR z3ntK?cQ4QiPz`F5Kl6}UDXv-xzERt8d7+^CPC=(q4X=cqjmi9LNI`C)D85~w~ z&oSW3SaPQnyGE{VJ?aVL?nQK0u%cL6^61wXQcWm%JbNu~zvFAZb~UNtM*DJ!s7`Q<&!HYJ zwMnGN#Q(@a$3``b38$EGWK}%;li3DW67hN*O#<7);eU@dZsQJBIdkeIW!lqE`=SI zb%1Ta?RC8Q2HY^MhbV~9V}5ZeEi z6D6{(Du0E#%3IIhqU;>%Jg#j=^D zo%P0+9AA57!c;(~H3Q?;>c*zF`-5i&&F9A*`LNyc8N}ioYMAzgiSUV_>13pgc?&?> z^Jqw=#qGfH?5{5UJ|$tkBx|^PqR26*0`NntQk69R4W@*C-r6P~qn;bzuFl8s*rA%w zUR`=dH}au=Y>$Pp!)Rtu=i_*gB8QqDq#G+i&ZP<`>;GshYxsF#ZZv=flY9o_(wxZj z$=)>WT%pg*I)axh68o_`D2-H9gVYh!o|b04 zca9oPo*q$fga$7rl;AJb>hoKQ*2L=&3koAUmUf+1{+dBmcvc#GRN#!^Gy1l^li8g7Q| za=fC3qpa57nADSiko(!XR@fGEL+aGo1#@?j1u;lEzW+)Zb|Xdoaj$x3pzqDqdS~_N zNouLedPzwipE=gN?|go#+XDDvlom%no9LmO5}|G7>J8Drt(-G!JxgxdEtQVaLPS5< z*O8}TQC3Db?eG6KviS5+m?mL{4l=!QGQGJ6?$WO|P(S>q8hhuyM+2@=~tn_J6^WZay??5d9wdWKMs0Wd3j`a3i~7UbLYiWuk~{6jG`Cu z|KEqCYu^lK(Af37wRRqtm>34qk>|&o6S_?v{Jp)sPc$?F`lT*#fvN!?63>p@ad9lw zja6H}#?T$Y{6VX#9KcK;r%C8lUZ`Za&LdD-`)`5>r1F$a0MuOolpmUA?P{kS`-H|2 z=Fj|wWSpG^O6pgr(ntJ%4GlT`QWfFY4holh2%h;J`oBeNrCXph)&`oh9f{LQMZ(lu zhhA!|)0l>06qL^50~WAY_w)Y5OBJ{>0VLv&nR1hNS#yWN;br`ayd5>40417)gf08Z zti%1c7$-IhUVAD&pn*UUX`|`>iX2Ap0hDF7Pv;aji(PbP@${j(HO&Mw1Loap*U1on z6rZXE!X#Qoe3FS|IJy9g;HJi55*{MbNS_#O$YZ)wD|1F}+c~b?+`jt?jqfxcnjZbR zug^8D8!GLq`!@f^@XgjkwRO>ZpTG~V=4Q|V`%aAt_6S<9TTqN(p3fD%ajuP^pJ>(f#&YNBjgqcZ$nDv=B!^He+uMy_NB^L$H-`= zoRrXc)93A3?EH_~iuOH=H{UCtGeT485%-C#bcR{8bC#H5^}-&SC0!UV4? z&zKRXb?claZ#v`kOu-DI1|88oS50&(aMY~(d@HQKM!Va1 zr{Z0`$FUBx3nftqEjmfxdfyAprzoOI>5}asaVInyVCg1S;2=XN;Kn?DV!K zLjZqf5!|vZEiGlNtvQixe^6MS2h7X|FPJPy?i>M%pm5XiqzyX{&vC;Kpr$Z5JRDr_ zyvlUv&YjP0>S+>hfN~3Yy3hWb{^d{t`e*~Y`Uj&Q-?00zci+gpjk`Vn&&Oi_+Rg|S zb-7P}wVSL}UT4R?i`Gs_KkoFXX03Cnx1IP}R5Hv7-J6;2z42((-O3-3L*!r#cbka0 zcwA8I6yW7f*N<3jRRY@`Rxfqc$*vv+NgtJ~JT zB(uM-ucWd6mFtArCm@}(J@rOgLE|eRhdOiuK!Wv=-|l8sj8r?&P~O|^ATR?0=4HAP z^ny0l*6rZs@!O1Yy-!Fu+Z30Qq656WAaL4+KT=qb1?!5LAoPEQLr%#1Otr^yw1qdQ zcCOT=&crj3np`JP_i57;F?7Hz`s?0lr!7-xV|$4%5* zSl`3%KVtWO^M=@7yGLA@2&-K6+nDP`VY!{ZP}-Hb$ab0pB+z*hK=@YqxL2gm;HI1W zq?LzlcaR(RrhtLH2%3JeoW^;1*6~8Z!BHxXI~S%KZEm_;iRiWP!K`mMgng01!vFxxP0n&&WILv4qzIn9fNxo|mVNmw>63&^()L-*THD2#p{i z!hnN5f6@X7Zi}JRb_mIn=^&6Nz5o@;?(S|li*jB;LHh@8gEA!iVssQ^cnADE9I#5P z94W%t6;gQ4*vu(GXX2kMh}%OvK*H>^I1QH-C4{SwZi@29_d};`9P3xntqv^|O;*&; z>N!?9O(Bx_r6Wyu1>Q@~b~2#D`yA#it*}4KXFLiD<9qH~i5lZmL*kYjJoR%e*Eg3| zPrblk&aEJGEkg*AF|yu8($S=qny}PNPk{XDcyZ5kJ=W#2eADjtu>DEvi#}P?>jcDE z%>Se6t>dEHy7%FmR0$DLkTyt3r5i*AL_&~m0qO1@L_q~X3F(rS?j8nE5T%iZ8KiUQ zhM9Md=Q-#5d*`3S#{+ZUd+oi}UU98!;m@J>nu~rB`HK>aoxfS#UM+t1hjesOqGICR zg#)eU=6yA;DKad|<4()H{3H;&XFEj*x}8hLg46LfPcYuh+iR-nde5&A;<-E~NMhW1 zb*`C?WpVO&TYh z_jn@H?o^kVr6T|r$B)el(5rj2oE5b-puo(D-UJLG-y&!Qu9d3c&N>88-~X1dnam(3 zEgzL_*~441-?cYRcC;OI?dH(#QK@ZF17u_Lf{vP?u<5%^4V8!$`RKfqdqiX^XUW>C!E^TO@fG)m z_R@;>{T(P=^)`6tozg=X%%MLh;cO>NWa!=l7IN{)(+7nnZ{Ke5&0K~WZ(`4f4TN4+ zUx%d%b2$e1-O0WD>n|{!yB5D-ia$-8*km2EP6QeGX7Uz8Sn-b^;)C+Fhq<|+&MTZC zcqM>+XZd*k`?`yA>mU){LnSs!!xEt@6k5^H?mby)EZN~Dx_h>Ajup5)e( zHuV3ARO+utDM2?XF%0$qVcVS~L|XZ>XRw;$Hpyj>&iDlM0QdQFBfH&8&V=14s^!Ab z)?@P19qP7$t-$?6=&8SKfi2Kbto*P76n0it^#+ehbcuH$QTgk4JqGj2w8A0sD5T87@}pN$;VuX_@9z1w$^fzhuA5ko0bW%RC%-|pP$ zA`7_*MZcyOX^MDm*-q9#%xOFz{}mMCKOZ*r)oRb|7Msj`X|s>`vG!^u%kSp+iyaiK z_7dG*?7b@qn3fTlc#QisujWQt4{Z-zfSsP0-9S$AW?2klevj5!qqQ^ny*?La_dIaQ z4|8+l!gW;(9Z2{t8N`(j+4K9PbASE76J}>YVFmJ1v>1R7{^#?h3}ksIpOGa>`3aMd zkno##ko_Jll&sGS$G?10LXiso;FCPx1y5e$nxJeI z6Qt_R(bf6Q@FnO@=>;;gYkS!T5#rBX!gEOwo{6myPy#M64jtAAxYr)(y-WoO6M8eN z3XgC9u#zyqG7T4Uq0_~0WclX!n5_JGX*x6s+|G;!!s0HCkO9W!Urd)%q~*b!a@I2Q zp*mmB*Ixk>AjGSLf#2!h$b19Qlw6JfbJvBI_)?e<=~uODwKEihr`FNj2P)HeI0*L&uDGP4?f}es~LklX}GQaB1Kh0NMJ3 zZrtp6MMNrSv-_T_1Oa$0KE}uADfvCT#>Aldugp0h-{(qK&r)Kszk&#C&S7zCcKz{@ zD9gSeLQ$1=+wa*?>e`U->w!#hC$lKsVu(y))@&%pA;;{&TBgd;NpVmW3Qs){sPGA93ez?y<&B<{+Udl<`R0Ghk2}RAnr80WASfVG zHa2FGKHHMFpQ@w8VN8KU`+u`+vZNjzc^iTOBXxjZLLHRSh7{j%#2P-i3n}bgqWEW1 zu1R9ru+_1#i`$W?4>BEXZU`U|;8Hp06R*k{5^qavI!UVu6aQJu-z_n1(7$VND z9Q-p?=ED60p5dlKgU+Q{>i{O{DfNjJVLaaXOPwFba!=6rIInkpBDslc@hP)@u2+4h z{_qxg^-&o%G-**;%l{-ud zuOpl30dbYAQR*qe%GLEgh@JVJXJkR*(zNaMB^=~(c8;Lvh1^5Ru0I-AAnL56*BAb= zT00M-K>U#=D{cM$1Rh=46d@N5@fRvSA{U>0F^cs*2aR68H3;!(W2YC5!#%u6ZtAQ5s^3_2Yx*e8f z5O)|SpmE%QS*GM>-FO2~=3V#^P1Hx*O2%Z;><>wb}cO1wmB4J_W9rB0YVuBKqHnxpI#vJUk_6|zK33m19YJma11 zxt*rFcL%?F)Au^NsA}~_&{M5_;VFJEDe3cRZ{4T2XEc~)FaK7SM}6Ok^DIg}tk2!R zY|P$DxCf8Qbw9jW zijg?fiuj{)c?z>fF%j>l;R$9G9FRSXG~l(Xf3>O90e7Y8DuTs3`RhYv_VpA0mtsMR z)Uy#^cpWs$9*u6N+jSm1@CYIAED;{v1zN3DU)1SJ@fa*1)Ul{p!dp z#x0^XeDZ$|g75z@zmor9e;+(ng~p=s4fln&P$tkmo^}Zp87Mskw`#_H;8O?1dD{8c z9t58xR-dy9(hi*_N$BH=UDcJ*OPcZiu`~$Da9* z;*Dh}9R>>dc#{oRB#^y}G^+d;3xHFm#SIOXOMN5==;lRyw3yS)r(a-sEy#_aH^M~+ z92Ag*B{A$#Ow*qE-V2LYh^KQUyp$7x=nB0_;|!uwpd z#7bC40$_-k#nn6Z`2jAr?XLmD{W{*j7Y)ZeVM`|X4+gTSdM1!KHQj#JtRzSv)d2~> z@z^lmQ8(v5v>F6m!?-HgP9kBuam7~r0OEz8+e|ohBDFQ6WV#sW(D@io0Jx~F)T?Id zgkx(z<;131Zw*8<%np1@Bj&su9X7-i3+lt_8>2ZY3zh;+VM7fWm&1F4zE5|&xkc(H z((0D4`XR{B`0Xt*I<*S9%&bl;3_pL90?qiE?#9G(VhRIS)FE(dPS91WV#jOV1(4xn z_E~d-+T+`7OI|wvFNzQeN}{)WQJ4dfrn8-23BWQ<#G~mYe2ROv(6T3%@({eNhUa z&u&RGueRf|V&PvD-k4BUBxqP5==8K5Wg}v_?5UffMr8V)iT9$e(6Y4TL=Z4{U58ClefW77;>vU(GL7Mwc~cnv@kZy+(*L;>{@XN9 z-zx%ma~+68?g6SdNx+IyHy^G1Kq~vAxbGeZQ{a&qE;HyXS|xT-<>ABm|G>}qSBb&* z7jr=cK4|6qa(ritAB>mC8n2F>1UGozC&r6!DGAt`Ov!ifyLLr@K@t4j8UIsXXf!pz zDA{f{cn=S;Ep>}tvuK;zQ0p3W@NkI)K}GhxPTjCniP_d#3-2h|ulF&^QAtw!N?fdD z9wmVB{iJ{lvZSE(Xxdz%gjYJZCJcy7-{8$eIm%GUyJ-$b{I{;Rie7R_uRbaIMYEW7 zMl#j`603VJzFlkrQ`A1*HYL{M*+8{0*P;R?K;|qY-XxILvr%f1iQx9_!6@Zc={M~A z|3KwGvAxog`^nC87XrYQd%4m?+51{Gj`3-T@gRIhqf6O`L!O4PMqeQ!ql$rd41c`y z!{q*~hw=qiV#kh8c9}>px-Sv{R+j35S3D|Ve$_u!IXT0GLGr@8PWl?#LAbs?A%M6w zT_I>--xZasBGE<&{NQFgMoD~;hSp=nwu5hULuE^cU-b*my6E8N?S%htPs43clYYc4 zcjcziRTiZOE-v><;3u|c`=vqO0kp~m@Nl)-M{rsND@n)ScJA45?(7CWz_7~%5PURqd2({xjL!0SqU>XmqH19-&F@l z+#$(;PFV=nA>2B=0w9)V#xyC&MlRwTT){LJ!iy`Sg^xj)XS(ZsZWB74R8{)9_Q}uS z273$M5=kDltO51kZ((jU+-%wq`k^P0DP_{rv}+fguEUZ+$bwEnY})>3%C6CZe%!aL zN>^WNvYS>D1|M!rhT+P86p~wzW8EL(Dfc0jWmHShTZOOW$vvTJY7%ESXy8zKASi+-P+L|=Q?nV6rGEqt9s-dXq~)%g&T zy`7|PF&2)Zr+HCj7Qb2}@lJU=;FQl8a#g@fM-~U5eyeIf7Kf(>3ZGc9)wX1wB)l5g zBZaWXP11F%YrUg+bJ=Vgg*jFDWlGnar^k>9K7UM^DkFUdj?eCrLce4Jsh`cmH)&t# z;)$|0PNxG0i;s6YoTg=xtFgf1|JN+|S6VTkPIGc{;`s+vbAbx9q?Ma@Zh^T`e*jHp z+qZXAF28tcO#wj?rQUUKphn*3`=j@qkYG}p4#5`lSscqHPR>A8Nl>cUX)l;LBl^UC z^gq3!enngIn~Dok$el;a?i?c!yYf;1e+A`oXmGL4Dvw&9QN&CdVKa~AhU3(eRkir9 zljBziG~D88WLCZ0f_EbYFGZ3}a1`6L#bxz%mDHsR?nFa4Q$-JB#$0+HpT8FF|FfqX z5)Tc+;~?RB!W4MT%SLl$HzG|**MDiHZvOk`q)|ExAX0?u11^9=71{_=l8S!z5Gt*Y zA|NrPi}_ab%mi5)iD3p_q_d{ z3}DW`jaS>zpqmekn*eCw3Sp+^mAVZSv;`<{{{SeXyoSbA9Oo-85>B{pNisV(C-2F8 z#>vZzOFfhUK3y>MjSA6sctJJ~;Wl}i0$@CVu8M9bPmKbd@$N0hD#urd`~Lrs>DS!$ z63FiAvVS~f2q8WU2S{>KfO2^Djiit2jxOsy72DbNEalNsUAQD_tlI0erBVS}NRIPb zes~peYU_ zY6zYD=`A}i-?wFH8}X>OZK|=V&@U1M6Gs8W5J55kqNJ4D5NwF`586wFiv){bgi-!a z?>>P{!F$p1@$m$iAZf??1?nk4(>(?_sAc758XCl#00E;nps>5b%p3)#BtRfTzzgUu z8OUhwvsfHnfNX7T0gH|+w?PeAdcXlKARxVf@B&s!{I6+y%0`7_%*ACU-@TKh1qS}N z`M-e^Nuu*b$j;@e1OXzO2zRyyBYHQ(&jn)mMLDTND~z-zr7G_enCNb--R+0UIOU9F ze4i+K>2MnF@?|_R+F$s%LkDT^=*|8v*HaL1uJ~<4c{HZ_UEZ#9oJ{V@*4gl*x}CV; zF+JmO(J?dXwyfxUP*z}jhB&Q_cqFHKxA3LL42Z_~pMJr690G-LZM6!6JJ9dTJy8@Y za2wy$Rc)`u*_?9(U8+6x{QaA}U;ma=DWA>H@FiU<2lS~hK!`sFD1H%uQ27<06^Uv! zQEMFs=vr?5s*B;&Jopd*6`6ui{f3Am0|_bVGhN-c5fNlY9S*gVKvgf}+Ck}s?GYf{ ze`aVnB`#dh-aUwX)#8AKZ?%zb19tQmTQjW<5ui!uMGVMi5dWL$dJ)BR9k!q|OQL+6 zOZgKquokZ_qDPyDs6kv)yeJ$O7$j35)3K-AnIOHw&+Sbm`lZ4}tn_+yX(5aNLG5wA z%n2_%MQNJd9lqL#N8VXwqkOsamK{;L+6eZ7?kS1-G1W{oEo`^*PoRn7dw~~!9OkxG z-(PKN@z1IW$e#h^xAymDhfp6BO5M>>FAVmWu;mF4e~Vl&-XEdcz%#Ai3?hz!U;jcx znQ%m7+8;YosJ&jGG0gHW<{e1#8H*W|a61X~$^%8b2Xd;CVBVcK;Q0ha&?TXZ>zq$X zAz-oE|IxcwBWr-I1}8m0r+-sKq;@|#HT46?zXEJ!t?|QWuZL|PX=-Y&<$V20Vrgl~ z!Nc=NPmdN?W&oTSribWhXYo{~&Vl>AHIiC*j`irG%HB4d$Gkn)S?J3E!hK1Xp9vdH zME`;yvfnx9Lq*?})`7z6zcnYCdF!(BOBQK^2+w=t%VNgG$w?a|?Z)pYUP$ruMe?C< z7V)j;V#A(2ce!@;HSi5o!%uVKN1!rdt@osP1o4s-&(YA`_rbYTGN>9S&a$94C(=z_ zHj`h!eZ6ap_~}ov2+#=ke;Q)gerdNxW-HtYny9&lkK>%%WgukW%JF4m>i% zi~AXHv8{!rQmNN|z4UK?A90X>5+|ULCva8^{4#o23txhkqzEl2oV@lM&O5b)lCKu` zG5&XMAF<*Zya0G~E;Ed&4bZ5*>16UF<7+v)U!+~wd6U0ijBIM#6A}epBmDfpK&5lM zJgR1HyCx;Ce+M+9Z-HKunOCH|{qFw2b~uRrTkQHGyZmf}6LjF{KNkaGYL)3rNc6=X z13~saUT+hr?!JG%0@Y`X-!Hp&Ru7MBh-U+;~_*^SyB)U1i;5|Q>DcW*VIq%tJaEG+<2&%jU7@}nh2 z5?T;7As!C!;@&hp>1xY|Ji(jssIRG2Nt2{C@!uvIDK+Wa;-jQoQN>kj|2me9s=BV?V24ow;WW^vO>Gb^lZAQf6u?%+Fkfx!$s=Ol(Oy!VZ zKj{3dw=`F6r)GW>KXI{rH1;tleYf~M9}${c^r7F{Uc3(~sxMR%@k|G@&$HES0)qeO z_%#(E7h$jD6E*-?KDPw#zq|9x%@-ibc>-9tQo}kus2A~rgzj`jF9d{Bb(Wh;_^lTS zN)Rf-WMiN=S9pW3((&4567gDc(pYB_UaZQd;dn#+gfpkVBDR?Dr>dg-#ajv7EEX56 zT&`Al#|gS&)fpz=S*)cbei9tqJe2gc?@QT~NVm76P2COLoc$iYs}r=Znu3gOBv=uCf{00keEWN_~3lTmjX4jfE7%pVE3& zqS6jW7ns4B+sC|lT`-W!FNa8^O+bi8%yt>8IUp?D(Oae0C4g}}?es5&w%$G_f%wF& zk2)0!oy^Kh83Rb^WKh--dl*$hE+&yZI{|!zQR5{@=WdrdhC^(gw#y-&buBQ>-ms

=Wf6o3P4JnZH71v^xymtXGMTd@^7F7A`u$} z>i&Uqdj`Qvm`ymCJ$-`=B+JUm?0cmK$=$}4dx@&R4Qtvk!6vgCIk0nxf$g9fnPFiT z=%c%-zNv``w-%ULlcZkC?MIXvs0l7w7n)_1a?$blHL4$J{Sdzz62M~)mJYZ6g>o}BWWD{+sk-#`i` z)L#c-bSA8X)$KSUAMk=b7bbCiY%n=xaES9eoNaJHW(~biVE&Hjfc3x2pOu%hbQ`}0 z=VNSg-HeRv1AAJD?_K7(CIk0gE0TG8&VQ{zI|4e{nG}$fT7+RB`84QdJBEHk+eXcc zXp4LmehsVWS5VwbU;}~TUIKP{hGExU^&IpWd<}ZQ*dpDGOiZQYYpx@EOU6e{j{zcQ zwcyFhr{gIfdo=?XmpDvOVeT*-s-)y_$Sj9lb#prWKFKCi4jhmm{V&Oo{A|Fw6Nq3) z$Nl-pZ?sil5+r25=0#@mQ8&!Th!XB+|-MBo}?c0kVodxOK!dgTBqf`h#0U~eq>|D_U zMk}V-L>F`wGk^=RDh~sJ0zeOcH>jZ)fEq)?{1Rwt^7vL^U0#Q*vKfbi^aIyWps*xR z3(QWV?LGswlK}Rc{obY39ix&k+y&`c4(zgUrhS;;r|mdHhJ~OME=})4pXIk4@MJG6 z6Zp0SBT+H}l02p;77IEQ{^+J%6Xr>*4gK9h-Hg}1B;D9_8YkE64V6eUEFlKQhR=2L$H(+51S z0uWiz4l&kr6}zik2v5k_V4h_Qy%$7G4Yyw6Vr#fVOvv{dxAxalqQmoQ(mH~?-)ELF z>W###Z9b6pD`36%vx~8GPg0180BuIFyKTRD2G8RHUK(ORpqSr4I*Y*G71oGw;hedc z%cbvP`Ur=-cDm=-okNN$V40rbVNp>XLo-cs4k*}^FnCw^yX?iu+4&kAk%$l8&3##5 zGk&P8(}fZND}R-$wS%ZE3OLKHhFHBO6vdWEkwZEGho(7*hRg_epf} zs@p2hj`svh0?%d+urM;kh9j~w6t&(e8dM*=Qc{~pje>xO;z2Aoavpd~IuhlN&n1uI z2m7(Pn`_3)wXC$XAt}N`D2#UMxBTL;A? zgSjS*;#bo}V$%I?HL49#a$w0R z0hl*A3QN?_LTkE8TwHvUy~7N=H#9AeW1K+PmV}~o;eppv6uA@&FqaIGrt51#2dK2B zbp!lG>IC$0(UB#vU8>?BykXetcquXf(g6a@aLVyTi*614cj#df1{i{d<}2zNIp2xC zz?5H?6epet|6slebXPQhD0mYm2i>Hnp zR61=ym_zhZ(*AgQ2Y~x(6d*s|l-~?He0ytL2dWt`_iSU4dQVVwrGR6s>cz29Rp>&m zqmlf4{`c@9g{{}M@LG(rjrKY@DxwxU6v`~}`Q}RRCIsNdB+Zcni_OvILP^Z%d{ap; z?ffVbH3s3HEnTv|akM`n`~q}i!s6SvU#Qf!ZK^W>Y2y2+H~2Rg7V&Xp{R(IXz^xg& z)BJI^No@ytU>ISo>dhYDLF|0;?*Mr4zv3#Mz@GrbhWD=1gq!_=;SP#`I<{cp6f`Dc zwjYiWoe6d4s8jq43rphaAd!iA`3x4_0SO6m-WA=!-Y{B>$UywrR(u#6H9Hj_a(eEg z&cU0yQVA1E{xkbU&d@3a*kr#>(}q;CDghPpu_kc}PPinBXV|{2Ls8L3x0#0UIEX$^ z%F$^qTa7FJ6mQKXK>dvf{hF3qXuQlHAK%WA_4fE1%v|BCYY{pXzWTdoQ~X{Ub}@6~ zEIlfaBo)LJ{w9sB(0}rJHynf3wy7z8_Ez(TlpHwVYlv*Rhqvm?oB&$s&OQI6p2q#Y z08)eS9~4(A9v+2FoP(#3MBzTkSMBmBW&>*m$29(E$LmU0*yp(EJ;Z>A@I7|#lWG`< z$oX=#P@g1LNY)7sP0FzB<{xCXZN<)Ou*V4)VC0I#_zT@ zrtmdIatE%BzInVw8vd(NPO*LlqdRjSJOHLdLIeYw=vB-^<7{D%;q>g($L%4XrE2Y& zumDOg^02M6UrmA+V3GPQz1J%`e5XgYfM{Ty^kiB-zUK&PKwh=b_NHdqqGe1T^{W+}!Zha>kkp3k&j!^O|` zn-V&TxreB>?2TRDczp&9&(}f(XUG$$KjR~s4+6{Dnja^s(v;Y>q{fLsBC-si6?rbD(de(*|`DU zVica+`pJiZir%j?GsdljT7B=TUS#MnWLxZozV2mJh+Ln%=cBX$fKqBPt`{awhF$i2 zq_gG#+71F&96;mJ`;&)vw_$MiG z{5VJ-!g|{*&2p+Y0JgX(ANToU>qc&x9M4-D5Cygmc2_D7PAcr!u@aq!G0zU)@0aBT z?DmVTUljx*FsHOlc>RUaBf+iH3Lf1923`5E?$V4<>D!;IucNIUCm*+*`an0s{}2iM z|Nr`vfpCFfg?nF*#g4t$$l5Vf)V5_IYRlft_v48V@!=V2gpSZ~Gc)g)=ZFt^X{)ei zXb8lg(1`1s{b$B#F(s>$RL?buQz+9639OyChnC&Ci418dLBEmug_H!|>B00F%%Ve~ zaBNV)8!6(-g0vJ9v1kzX;^Z3>Q6{3W(Fxt>(Ra1!LxNI+Z51>>aYH)VvkUbN4Xuqm z<6wCSDP^WY#B@0&Wt;QUN$8(!F?NDAjw%=zAanA}+yb;}`!5lc1+%uD9O91e_b!ya z%w(aDgTJF3njxY^(Sd~sOH0ccueJ!qsqxXDXjQ3l1-D~3CgiQk&&E97e>7*ES;7Q9 zHX{nSs$#s->at@L+1_ub%vwu)Ck2F?!E+fXAcd?d$Z~)vsht=!rl*`}UgxP(a~D-! zpPBrg=eFVXjql#Yv1CoHjwc79e;b@mG;g2A;mAozn#>OT4Pct07e87@Du6%U|7HTo z^hYQjG2Em`G-LHTghBbrptuVr$36L?$t81~Mq2vY(NYWzT)h1S!Y49DFezcF>x;uT zuRFH@7o4ie0`z(?a(v*s@E$Rcb@NWyyIvVkoUb6W?7G!6$bt|q-WS^kAK8jRn9r07Q77p za?a#_BoqnfoTm~0aRHDl0knf*pvl+_xVz4dLmK@n%Bd?XXrL@FcIimMUW5X9Wh&loKCxRSnh~NfT>S|;#l8Wn@GBgfA z5k}$u&8>7FYeb#(I^zLE{!?VGE3RiSk*Ev~B#I5@aJ**~xNWl3)lK0=MOx5U0D(!a z?Ij!qKzng}j=@r|1_zI|PD820CbFIbW7XIm#EBR|{jG_QY{E5jF>IvDWmKA`M`rz6 z-0Hor4L77np&}361s%~7vG{doeD+}jhKs)mPBf_}z5eT)*B6L0|V0+FjbR4 zQ4v6Rw*d>tMA2*;Mj=H2%##*%TByyX$U3}2A(0HZBreaXJ<5Ykg~)tfX#A-fpjrH^ zncCa2b*arT2TNx%5 z$u%cXgIMbz=AZ`5c_;TX4jCt|r`Xy`7RBC$qM{;e(vCvk!wE|!>WG&XQVqt8=KF3Z zreQikY(aRcq2yVz+M9!3^|o=6KxX5^0%G-uC*TqO_BdD}ktRYr7T;v{@@Me07;t=) zeh*9f%ucg|*z$YF?ronFQNUn}O!ra>Ja=JUsu}2mpfdxEsHpj!88m4art$V*Kdf}1}fd|e1v0vN;hItMCD%c;eyXhcBPq3eauBWp^_BFGo; z|6mna1$ZyFR-$h-r&F-4=Mp&CiPEzv=saPqr6Q4s^cCtoAmv@T_-FHAcN#Rl&f<~5 zs7o|Z*kiz}6$)7Oe$ST88ID5;K|z#DtAoPwIHf5#8~m1n=V? z3Nu!4(qnrVdpN#WTPgD)v=OW9z)W8%a%)X6I73bMzb3q<;Zh=n?jG!&ZUitjtk2WZ z>s*9+9CFoBj*p{epVkkCLx-I7_-s^Rw4N4z0tKgs7;h0I4Jsn)49r4^xsgJ|2gG*D zXEdu`Tvq}PE(W+)QHlMQW*8lo-A=XYYKnu@5iAMf(+hMCtabg&5N`CLGQn1QL9tud z`5~v^GqO;vd=ybf#57OzY&as9MZpZrV`JMws@r7c?-6G<-U_%{r9(?D<;W+daxOFU z+BHM37+*ac83OiJ5kF?k-(J+z^jig*fK-TVt&%~Z-#P#<1gY7POw=HPl|D7V#gP&w z1o$XG3E-o9Ad>yjV6-^0&l?z{RuzMq?LY46fuc5ex(4UIZ+-K}Az(h%O^D=7rF&)K z*pxqMwqT4WA%LyHAYmAwfI>Z}X6~i?%VbtR-m@95(x7yqn;@Huu-jl&FYcncNY5e{ z6v0&-0Rj5eN`r4wR}Rj<0#G6n9Z_5$w3#Z&)gZlw29$5JLdjWVuS`sBvav(XI!V}z zcF%9rFm9O8P?FNq)0+|{j66UzIxfTYY{@|OA1w_Ho-L>0g(9__Tc1T_)RLGo!Sl_C zXEPa&VVJg~+Qlzl7RM(i>i0;DTLPB-N_bOl@Z6(o##ACVc6u$0LuTaC(I)Suw}^P^BvuJ{pA7aZKbQIZ1C%&4y!tWeRqzfV z+=yYxr{s`jCPRv+&uOoHc!zJDT=vS^9JsFx&n zAk^E(=jKTZ(lBFIy2FQd{knD4kYLz1YaGi|MAwu}7l^=gU7oon!6N%h`*rh5)=is& zL5;vpWO@0RQuaVip#PfgbDfWU2?QY5;K)Py_7|hm;ry>mIwhNzg6-*8jsCG}tI1 z#u0bpMrNIDKOz4eV&F75Ukm3w>M6I)>Gx5Lq-VAIA@6m!dJLW}}z-1@_QJ zOfYNFKh@`tPfj)#B&dX=>Wb?@o1;CV*W{)0;bF-42jC!44@RT+BDCQP;e8!op|r~9 zV;uyB!i59OVDAwFDy7I&vLzMuE+5Asu@P30O-uJ7{r`$OpK4}@{k76n97FwFH4jYl zkAc8_IU^(E>p$KXVp8ua8twC)Q2nDw@B@Sx{G@1vQ((_LB(}Fh_XH2z4R8u{T0dAJ z^)CX0`2gQ{mvGQWu3%UgXAArEtLX0I_MDCW1XUl|TuFHVsc}#BPZVCn#mM@za#%o4 zveNY*=SJajg37O|7#O`RPG;f2%kVYIpWgbOJsZt%{~y46Xc`;tw18*l29aM?F%c=e ze5rC@5;R5Cp}SsK60dgWC?@O?B(V~%LmDbIg(#=G?!yK8*(n96M{me(q``lz#)G5l zMb3W%!{85-lHM5LzrsvXqX2R=;A^p7{^Ya`f)0JpIERIK$o38%j88=X&g@jMxz@Z{(cVP+u{=*!OF8VM} zTwuB=6~epc=zHxOx1%G0Y%ccKOd#eW+goiNwW@-|L9d8Hso9{Qe(Esnx~dXz8R{yI zi(zmSlh^(;4qY174CzXUV|oP*P5kbgmhd!*VR(2XA*ZGbumoPIN_k z1f;Nf9j>$l8?#IQ7h$I4)wmEAv6mNLwUXZ-CdAmkn9z}cFUao@-fDN5iK1(KTxZ}C zAMy>=#?sNJZP2_huqCmJ7+;-A6ryw4*aWJS8;19I|8wfXt5zrls7rG}2L=*rj4iCw zb_`z*1#5!?tE`2efVdqzoi0!2Z^EbGA5<9F1&v|%}(pg4x zdxD#pMor<$i4*W2q^?T_oW_1$(yu7%jQl+>*pBYJ){|Y;^S9o4lmZO+`f;>`vDE zx?X6(!FPl9>qz7xKd70T!ecyrmhq!tE4UJ#t%VUWx1nK+Wt*#?-TUtpUfCz;a3@|n zogIL4Eb&#Zn=9ko?ZV=7a8xH0~ zu@T9iFzifVIV85iUVbyqt@D9#V5-+(2)3P{U+uz!zTHq8PifDYJTBFr%j%W5p~RBbDWxCUA6S9J;kF$TT{LOTR@ zH%L!{HTrjZ=z91M@%mWDyn~ZWC@um+4GbG_V$(6N>9hOv>60B0PHHC#x zEUKOLe{A9Qa>6gLPpRi_$!yYF2e7r9xf>lE6ccwZsOQS07vchi2nS6 zK7B(&_uggxgL&Hz+%jRT$@miLpW+FgY7$k#Ids1e(>sn?AcSqDiQ-7l2v= zg^###;hXkCI~}|2_V=cimMG)9z^*k3N$mzVp*;}~lN)x@Ulu?PB(Vjf3sPPi<|ji% z10E%Ri!+ECf2FLXio{?nJIz5J^2Lh_8K14N?qU^=exVox^FiT{IXE%9Hr>>K15&-^ zaWD;{peg-Pv{nuqX<+xD0{LEhEm`9NrG*&BbWb($wy_v?_we{Vba-Tmk*EUBF3c2I zCjl4A79UH&(4PaNDL8LkF;!e7zX0(fJj3{zuN!c%1gJs*B6 z!7M4Vr;h>gWyP=|PX5uZoscHw7>y33bpzapQ;5dN)30s%0jmv+@-+&8N$p2TYX2o^ zzXl3TjD0TQgA9wUktf*ypY>x_sMpj>pQia=E~wmj^ob~rs7h$EjB~8$G*lkHb_6Q7 zRR#tUKccL0U|$mFrjAp7qS_%$+vJ-0SjazO7(0-__=o?PVn@s0&gu6D&}QyZa#jTr z31NrgcgS3oNi8iQ4#WtSveEtvuzQ(UEr9U`(H7d<4fjr0p7~{tEmazYz1LW`Ze5S{ z;S&N)0KdtQ&Ay&r*2<5ja+!k{P|?T=ZZOz{+icI7|O9^79yS36kNa{FbMAF zLS6jV&0i6NY)$sq%#4gGfR~sgNB>Ot*@$Zc6cw$#X=_?KFt;=$PtaDv?Q8A5aA~#& zZX~>|diFkbSUV7_zpZhDBjEqy_ex>0*9NFrOV@hi57J6^U4_-i1#}NF3dzuMrQr}4 zvgQx;!Ca9T8vrQDzyeN)RW1X{CWgbfuOj9@OHj&o6`B46RACjUs z@JKMn(+?rpdq{@mU*wyy22)f9%t899b83!5M484mZiR)M*sM{7Y~j!}WJLQ1ma1>i z3$*SY|DdnDcnLYJF(Hxo?K9S3BE23-kKcPamy*FStE5l7iOIq);XnA`g#3rB$?s_r zNHRXQk`SI7Vf8?am-k~vi!ikCU+7TTgT1p7A2Kvz5vx99LLbe1(Ax{_>LMXI!_a{Z zs7g3752#Uswzy;_ZU2Q8eY`x|y91`Tl!SePwM2o>=rPS2IwjYK?I_z@UpS%Y!WQKN zg$2UhMq8l4#OJ(zQb*tzw8M3tYw&oh(MH|C(>E}11=p9M#+}`|cMJym#2*Sy122$n)SfMC zeuwf377Ludp1Uyoym+$bIR`U=HK-Aa$h8F4#wZ0J5PLT^a&c*eVl1!ZyTwWmqs{}j zd{zfRnT1iZ`VIM9eD+kN#o{x+xP&VJ`Om=FgukU%8&$Mm!cA~s!N%Aq6+jvwueHWWrAC-7Im6+BI#N(dXp)#=>4&~XRZJN4 zc!dpJ*LmR;gtSI>l4F(;gg7v0an%#>B-y796f-ZDZ)U++gF0al7AmSV@cW6SYdJZehE zQ6u1IyU_<+W+6@yK=X%Xwidl}0yGVxfX>9yU0jOb$(87;Sq}@fROWn~fPL^PEl&AnUUvv&afL_M4LpQhw8ZMF7dh+#!-%p0~d9c~<2ikgW}evq56bH4_{|?4r+mi_!+x zbVdJmUjq6B^^|n{iUu#8mS+b3+o_P9z40lP=fXy)L5meDR~Bt0o-bV2wbZxW6K?}4+$VwWC;NCcmykm*N_$MMxuW|=QBQgD1+jhiTzCPytfnA zn@l9!G>^xRAGZ<5Cr^m2>nBi5Uv$Ly?G|8H7YG_EEm#u7ETh3Zne*nxxBQXISx{jE^+S}_=J_B^)&(G zJt3Ls7^&`8m^gVq6kon1rHo?WfteD}E&fF%6nuGRdX%upNP*;DWOuKv*gN3aH@ykW zCa8wqK++esbpX}xE#RmOOM5YiG3hJc%@xs)r_|T7%XNUE!k*~EB;UIfrL}m@5&Opo z0Qo;!c4M{HYd~K7C5IxfUVVc*qB8Z2iRLvDG^^i@yKwMhX_`%$ylYkV2XN5TnXPz- zWQ<@~N$8%h5r@1>2j;Rc;X46?(AZw-&&!W|x@}Aj54?EZE!^~+NhL1NYZZ%XxS5?= zo*0A0X13>Mu^iexPI>$VpZWN1op|9CMX#Q3d)0px-R>vW@zw`!-G!OTsspODtne&$ z{4;$ein_LmGeLfUrm}nTXP{&LqmHtc504r@4qKjZ$`3^7(H%Ui|J2oT9vh}(?V|SW zDFGWX4s_{uvw&UYV+UJ-{KN;2Zd>@eX7Azdsx{jz9Jb&_=B7ToZ(bU85%$e}Z&d!t zZC~z$-)St+U6ZmrH0*){NuGK|Lkc}tcf=z8b#yMB|E|0|seGTcRyZpuwkdh<(~rLq zETu{oCK}_=zr_y&1u`l`jN-<_^;qg~#fj?oixY_Dxe+tZ;GPahVE; zqPc;6$bp91rfY(C5`d{?;inyWBv3M#c{>&cgYm;ISY5JyaoLogxpJ9aFzMlY1vL9N z(FN@)SzeltL;eiR8WzT?8H|x)TIX-)iXk5A;N%`&>1R>2Z@g1GcHi_uT*E#CRmV>o z8yg$r05N8=43rGqDSP+Z*>0|u!t5%BGpn7GhuA5A*rwa%Klz#~Aae;@d*k+wmPevQSG-}M1# zYSFMS)~&|j$C?b6dw%imct7)h?0p4WR@)lwXP<3%pojrVh$tv12v~@8gMfsJAl;oi z6a)n&rIBusZd6J@WD9xoP%{Av6;~npK7v;Yc zT3@9{PFcy|cQfruZIPNH;5`%k-f_sxQ{!zB8;U_hM#pF*d!);aEtx%9E5!Pk{wU?; zu=vVTlqZwP`NMhMG^fRRhB8E*m7>t&7@5I_{74AZdW)P8wS|5Ks)3!y%-H=_Y z`0_TRNyKL|aqFVlzy9U|V2CZ)fWjsfw3hS;?j>B^+_H0r0KvBKquiJ$xQ zhX%6Z$~Aj#KDlZ2>Au`az|F}PddNg2(0wA4)a1_HAKUZX`Jgb^$uHXV5%2KlPIuU5 z2hQx@CIqO=Ow7#j4U44L@cWRVqw-zBESS1uP*Slo>5KA{|Nh$r zSx%@{S% ztWf>r@D)$fT3)Vwhz(4tm}2M!4;WvqLnIe0T+q=##D;tNVnW5|EVGd^MIwu$x^v;U zpYM;2@Px7fFQ%oLq#-}_?q^|Rllc5DIPk(~>5j@xTy0Md*iXD?GLKH_Tm8{db*fn_ zw5MSFod|qFQBP*0st6Q!)4j8b5vleBTXqOJj0bkoR~#@E%`7Sg-JKqATKp8BoaNHg zht(hH<2nv;EEQn#`;qU%mc@aOXnC@f9v%aiMO4+g*QY1Mc39{g?{u361{4a#6$Rv- zjBa`OB_RrLuo6&WJk^-Qos|IIvTZ}_iyfCVQVOTy(-zwgudqTO%4FY&y%RU;o(9V) z@!i1`#_z0>C8re_;|Xme0it=yuJ8PpZs^2Es3Z7FFc;Sa{xTLpx4?+!AG4^{-L-31 zB?@f*^Idz2uQUC+RK=1a%Jiw=*pw|G3?ZN$GA*5$iDnlwFlUL=QPp&wwRP~`cB4|i z={Mw|O!89mhx@A&1%e&|}Cf;~Naykii7=u?_eA@=|E*ZlE=O zGhwnFknk}i2jW=r+@WKw5US*}9?t#Zx#46^SPQKa?3}7@rK+0UsDSYAo{Qt2etv!% z_ntar-SzOeCtK0X?ZDO!oEr99um9+o>s(s2=;YPc2l}r%)}U-it>TMm5g#A<^8Tp% zxg+O?GU`3S;*b6iGTmlcJ0xjmtFy8rOV;ww9@yBPM;!02;~3<(cbj5;D-q;*(k*-y zWXhzQA4kd8i|i5kDXzfnPT3Yo=O;hNcoL=2*;ZPgh=?Gt4dCQqrK56N9 zq$Ujf(2Ys3ODTYarv`?pR3czf8(PXN+01hys>q$1iO@l((^A0Bdc=ITFXs4`3*RoX z10rS~P(-ut*qfss^hk{p8z^jQtN;pxZ26<(i~LX>{_r)7N=c2W-a>IYAulDh&4X|D zp77mun`mUK-wzg`0wRD$Ji^{!+r;6dK9Kio@JPp3ifQyX!-tb91+p)956Mm zIGh)b93fYMX2C&+p9{GXgz&*SI}8PATEK!Xh$v$0hI8N`Bak-nWNaDC zAc12*U{Of9<$KSW=9@M1VW-qW&#ZD2b7IR3a76D@2pp~L}jt- z{vK5q#K7g?ugfgn^rTl#uGqE>!Zhzu-vO*5hK>z-?Akr>(@@!az*>RL=6Hb4enQII z&#$pzc<>1#q;iB=yFGZPntY3)E_?#GGA-Z)S44=hcwx{Sxdx1woGS#*H00^=l13zh z$;pU7NP9MOgI?L$#+y4(HF_AjFsOws1YG7ef^>+lesghY!l4ZZeuA3F03#a5kR>y+ zv3VeoEJuoe8`c#wzQ$$-(`$9^a7kPA`Y4odU@O?__`O<9nzWqhFyh!bY=0g29LBDWc&yrdE-c!DMVA)` zhl$q^gDlHJ7bjvM7%%j=p%eII&Zh_ayRuph64C}Oi^hY$B29+)`15Ob-bCWx9@>22 z+e@o~r0guk&t$DZeZq%2&>W43Zo`&E{+rSSQz+ca4^Ieg$Bm8qIZuF2x*rlUF4&>h za37eXz$Gjq(hVKIN6^a>#9|7!f)J?HhT&Ak<276(Z<8Y<)6&=hSndq98x!)mi=FtA zT-LRxY_g!HiUC5Js z;|>IvM!V^j&Y75+Mqnep$1Y)HVtR;kC5Zj!?dx0qCDidCd7I!ejhMY{RIyZPvuM?S z>gAPQ-x@E3O1mowdx>ujZh4noyf75-%e~`4<_(JEt9#XVbi zCnT?4?dj>cio7@iB7p!;s>xQtj=2WIj@u=B@C2GYpb>Wfs3bL+4IvC-WvT9I8{2ST z2&FhCT|HhB1n7*M@F%+q_fJEtAmG+g829DF48)w+8*KDaViACp0HB;tN1u}wZtV_^ zSMrpW%zHRusMOv(VEXnnQ(=Y6%vfP3;wYjx`4pn^WO0yZ3INSL%Eo3`eVP{r8a6S( zLKJs93LAYDphv<&vn)jF&l%+Q`s%36@nOms>(J-8en6f$oea2s2W z$tNW-@zL=Rt0N&+T@T+>SG%F=BnaLWkqvqZ{x!TDXc~18Dlw>p){`gQu`;YfVmRB)V<)ol@xjT(P#YVCHz$f1 zmNv>4rleS8a`u>4a|MMWXALteO;eT_ z8L5#U5uxSPYLL$wWzUV=&>}B+zd_Dn)}!*#X&*j_>R=J7`)?qD_naEZ!jxOR4-#aA~n5o_c$^(Fws6u#dH3?DHvqURw)x@L!p$haYlKv|8(sAoRq=gj7v5`q2w{Vs9L;JnVeH zb96*QSw#OGC1|)et@>ob)6TaWU&iGkPO-R`m1V|y)>>sAnUyE8Q%C1;aJ_(f9uxA^ z$PQg$1tf~8HXQmo!u;QE$ zI}eW#N?2KMGd$h*IXQ2p4UoPGo>?W(3Ei%N_IShu9KFr2hVurJmE4Xh6MvXH)8)ot zaR6%uB+z>BMFsnUoPOi)TljKh=FrjK?X4*-?uXpz7|wLfjA3!oU5U^Y=h~}jE!(7y z&S|av=xBw&GoDw(Q2zveMGP^s8q3_w2s+wBURabms+s@=5Ikrd*)VMhbThMvjmO3? zE9TuxMW3Z{$3=;9k6M@Oi%=KMm!IYc)S|pAg<|4US32bARjl7au;`7U<^=rd7v3(gklt+hYU8LMwL#Yr1a$QZVNs4bo z+`c_GjV=juC|>y9tvu#9Q$iOG+L-_5JAuQ+ON-|K zQ`E_;0Y$}F0d{euV;R)%KG6G}84q1L09Ptz+YU`@7w3aEj02kYo7+jK} z?taTrD{5QVmj!c$@l@)F7?P{f>}Mw)hR*jK&)hBI;NWm!s_D*q+z@lMxIcT8{GG}_ zkaHXYXp^P<8D2p`=FEo&1b{eMJU^Dv*b4KHbbU`9XMI&dN)ZkJLZ5^TGeH)pIy|p0 zt)tyZVi0_1D6_E~shgti3yt3qU08j4wXPc>?z^gH-Yw^Qo}jj9LNaat&3E$=(+4r0 zJlXN7Hq^4iT9L}f0~7iTxw;uZ<@)DOE+JGhMqW{l*}lPjk`_G2L+wm1z`HZGcQ^RL zrI(`}mku6POvJu(rktw_#0Pg6t>~ztB;W$B$l}V7kn0pCZcsY1R!hYZEit1;K`R^*oa3hj-l1M^~AE zR!c_l4V&3_E(}|CBj2yS?y0Gd(v#vmU=KIcO0>AWlYrK^YK7W!Zsr+GRZ2mqH|2`{ zjtWJsV7UQv{c43`LAb(t`7b0wB>5Q1b}>osc$28jZeYU8%RXbkuVR92P`LxX1W-`9yYtN6pr?kgMdo* z^4gd|{^>;hr+GKDDrs{65iAX&Dl%vfy#9(q2lg4kwpIZ2pd|+0jByF${ff)ixsh18 zV5&t|n|5Ot+8{lMFVLU7TSso%uy9h|rx%gxZW87k<;u2DI||W6&VzQ}USZu3@Pz=& zR(gCqn4}&!mQ4o!WI-B0;)-^O-GuPe@Ft=t?SvE*5>F#%%g9`X0Gs(8Fu7QKr41t5 z=z6_@EphT$a$bKt^HTPaBZz2rehINPKDTWiL+ZM2tn4n}kv z5}9iUj9#wr-y9>1{J%5q(q*!R8gHID+wYpW(Thv z%K0RxBv}&4DWgjsy6}E!5}C|J@m@ajz%Q-R$Tq!O;kLijuHN?46`S$cKu5_! zJ`knS$6OtI0dZ9JzncFwpb@CsGd_D85=?2Q%)u49p$0CCoFTEnYwL^xYS@kt*FFz! zi%h~K=0z|q&Ndd8V-w=9lDzPP8U>591DSl^E|dHQS*?VwAg?qT3IOQSLy*q?3?D)% z61WBd2=w2aAdHP@0b&(@a^Y0VqYgGi{>Yu!!t7_E091dB^-a5y?h_C1b5LWqrES&I0)Yk%j=wa11_3AS(R#d(s-vlnV% z$h!b4JtWv|rjkS!38}lWLsHUiqCf@g^N2p}@x^ieC645rE?4Gi1|c%k@gXvhn8WcC zvHcyEh!xMWpWEw?U}gspBZ)T0rG?CvV_pcl2~0!M8tuUETt~XX-A=j^bYIbc0L^{# zGBU&fkaO(Q3mwej3bShElmY|mv zY6=IP513r9Su1k|GBI?-AKwPCZnVbGfg^$h-3$*l)6zi1%@xE8tuwwYCQY}T1wavJ zr@4YjMX2-AcOV~B>B@CbXau|zO#{Hu7RZUAGC(RQS9qAv*%$7r1hTN#LX zp}vYw$&v-=CO?ETIzB|3IzB$$ZCO00LL#{c4mufLU_FoEASzH-xG`W(EG3Tfc4CvR zZSSsUsMq&ZtE{PcjJTht1Nme|uw}v>iE~pVZS$^Ln5p1T?!Dd=0zC3ulvXdjP?r|} zoFdJUaOR`e9=Qfk*r7;yAesd;Tg)=97f$x2NjRLvXWh$*mVNn zljtvFdgZHE0YgU=oh^c-LfG(TJq#2=e?n5qkwrD{{ z{5(Sko=(N!qDQ+Fc8eJ%^1Zt-{x)a)9nT%qA4Y+zlPHbo(B!v?iXwr1L~waB^JV#g zaST}}eZ9R)wPS*J0|GE2S@dZPZH7Mc$maHR@(zh#AsF6;i9fFxfA-gkj@qGL>PI^x z&fOPjg}|*F@I~yX?ggIV(j5|yvO8>80Bb1>tTLNV2cxSL-hDrs=`5giaFiSjrG;W0 zgwhv)xsqt8p~|=u?TuDwVyoxo&^l(12+J6?j%eAb;>CgDI=m zb|CXlp5#U%LxURFV`RLC4DeD&WSrEfSdR^wLn|EHx{EuX*5u9M(f)*#auVPYVnx!0 zX+tsaW4Zz2x{!JknwR#FH$c!&R&%Y_cu}fCnf*?gGqEeLZF*B?yrkB#?gFd)`EYI6X!FD|Bj`xknK?lzK_< zDY885#+EZK-=|ed&f*rBF$2eUv>ckE0Ma>$$t4kF%YY%?tQ}^76V>+$2*D5xQ`_UP zT>kirY?vqS?M?&@%*eVsW{$(hRJ-y5D9j-L%CibyWhN*vG1`bJ%iy<(7xF-G&W*{j z{!f41OJX2`B^98mIU2*iz?3kXMDc%$F>U-aueK1p#TWozLzVg(U<{9uDwM%Su=82n zR8>{I3D-zK4&8TBik zX8^B*7UkTVNLUPFvM^2yjtzl5uyI!}ac(AeWMdg-XSA__Nc2Jwy9)4fNI>jH&Jm*4 z!W-ybwgXzfe3TJ+h9l!13ND3W$)1=H8y#X?(4%^g#7*=<(nOxO`cYf!B0eQ;< z*OC^sw1SMU1tEz8Gx00yT>jBcYdB4Ctyu_=k<;TT5>!3Hjo=!PF9>;d~k;vLVhzu&&F=u3*j<9D&rwRo2K(l?aYlE==^phV!Rwm9ZTHb4wh zUW<9n*~U_2lj${+nB?t(BB%h71KztU^ApL}M0mcaDnM9m9X% zZ45!|we$!+oer>K*^0?2sO$o5ka!=~T62<(Jm!tr4ZKxKkaib=C`hSC|Kf?PWE^*6 ztV@}M<7_>NdguEj99;=yJ*V7)8y22507AbE%>w@+ zz+SM8D(|h{Ri1)E;u?|3?t;OKd;jaN=_)YA zcR(c|xT}lH4a5PY;NU?5G~f^W;MPRrSi`w7i)|~Z{>Vu1o)zbv{GgJouVr~*3h2RZ zFkF(-+CXTi-?~XI7l*ow#D-XR{p>b{^yQfn;xZbM;i;)cBB4PpF360^fQW1-OG|PC zSmJG@GW)ne5y=u!WjSEkW{goN#pi(VS>_7SI8A_ZsZEadX`p{rke}_wn#+iS&FDPm zLy#hJOC$v$?33|mE7YOK$e0v?VhU3xV zZ%;2ouJ9h_od8gzAVhM#bG_a&;lL67H`_ZC6m_(*c=0Sbgrq!(89Jo^bGBoQg!RGP@%s)tF?maB4k9s6I zIi$e1{BS7!&U}sV2*;EfP-n>C5`z0<#gyOOg*>hsaHea(Wyvgy_rQOe5V5f@zBVp% z-E|tuCswExWuHK#b&F7s06*+U#Xw3)iH2nUl9F5T#P9Kwhf5ISgrk^Az&oiQL-HF@aP6Q;zct=e+oNm1B! zHyryisJ(STEy07tQ^=9C+T2LpfRxn$EO=nEUPW|A7GW9RL_Vr;w~lQvmK-Agr{(}^ zNsvT>VdBxNL0{NIUiQtK2gsJe8bWsQ4)J2x<=Y6j{A-iN4uWtum~t$Y{ScXh^*+F&ur_ClmU0(gQCWWsCel#C zjty?E=t#=$Q0jdtvNTG!w9Rp0K&^h~w!vn;`EMm8!Ylwu{2+mLDX!1x|Yq&#Ct(fm?rl?Y8?>R z+A8FE6(APcPPrg8y^~bQacC+Cl!>~r2VrDQK_gOhq^gk^HEe_Inn^Hi+|i&HdHM*Y z$@Ds9Ermj{s6v6f3k%_jxy5=yH%O_(_uWTw!~qNN=UI*7;%S=4tx&CsdN1=gjseWakz^#&-0*Ae~U`DtusCmE(Mc zV<}*OoOX5`Oji`6FNkehL6NLScfnSW0_H8M-v*uMAocDu0;?&uy8((Vf9=aakWLOO zc=mdMcL~R<)WcyS;>@)*_<5>6+^8$;o`9laGiP;>O@G`d>Hv|anJE+e-vlQCGwocIeEn!3Ha@bi}q3&ghqQZUHB zOI#;;Q8p`AQo_oyP%I?!X%*%{?C3_Y6Ij{eGlFX=w(f1B>z1z$E=)fBD{19vy}5*? zC<6#kw|5)4bXFn!N~;P#8r>?3DU|#if>^bRE1RP!E#OrqO$dB7p{76C>7*Rvh1tf(eR@8n3ek0}M0I@uPp;~V`!utv>uAwxQ zEdUYh&>SNTu|#)Cyc}zJw5dko>px z=Ye}=g{=NI9EOCcEQRvH8&y^3|F+Tk&_&rXHcI5feNN;yuovGD z@fB>^*1;Qurvk#i>Q2zv&$Hu)PA+6;0&6Ev50Dp zQ|bHTPRTElJ0-s-ytu~c4Ew56%NM%n+YIG~LDb{W85W+DOwwkOq2uU#;}dZ`-e&CU z9WlWcEscvI@YEnWxWUnD9wNK{HQ{9dLvQ~~Cg$*?%f=tOpYr#)Qv8aO;f_ooXq`%s*iV-s^x{s&3}9;(sM!m|3AN$4*hk; z{{8JVm(}Y3{>$&HKA64r1F>) zt~f+{(~xp~UE_XA-K)v9PG&}beak{0JgFv~rExsE#vvLC`z72$q!1Q?G+(LB*&-9` z0v=d%@v6q}eyTQ1h`r}Bi~TS_5J?w17ApVfe_iz7pQGN`0BAL7ir)|yTpPaP&<+!F z^Z)VnZOi{Zs{gSdl>cvq{>ut2AJxBC$*En$lb+({v82wwP z|K9UcJ3)8=JeyB7JxCd>qNk8>@y8d>3549pcacz+k!=42cz6DrSqV{I0Kpne0pbWk zcU^mArMhL0&8k6dRI|dtmRgU)2Ha0rSeUe9`ELd{=Gjl)C#;18HVER-3>(mduFdEY z_^&A=T$m7J5#ny!h9Od}q?`lWa7{?);lAHiH1+=MoTTMdRS!bX$^}JWP41oWR6__i z?Fq`j2ciwM>+X8v{2?fdE?Md1{qsMKm&LM>v;b-t*F5R{HzQs=bQd2EiTyM}@5}(; z1p_ku}Bkl#AF#@h$;}6-{)|%$D6spdkPI#J}%DX9)Cuhl)L)o7&HVJle8#}X=wHP@I zBP;7;uszQR{EHG-S!4G1u13^ufnHoOpS!pY8D8t@xPs!8=#B6VEFTHs+7odbomNx& zj{W>njtF_8DuUc}1WS1R%2iy9=NNdsB+13GYGus^v;Vp$y_nRBi#k7_A!U-ik_13G z8mvi8gzyv#(%(;#H@$38Y<03@k%|3Z{|v}QauqvDS>jjd@nL5P2UN~is8{h{lsciG z9AN75$;{{D=jX>N`$gZwFI%W$iNSfr_2p_W1DgAJ3$w=ePpAS4!Ch;+A{PzQ+_`I) zzGWefXWHYR&gh{dM?C4{(&}yH(lv27H6r3e?jqMh7EU-5az6*5SFc{hb6}$wWIrNT zP*;E;c<@j%p|b*r_#eL?`JtH?cf9E-?)F2XY{=bsnytV5$Air~P7U*LSFzi7&zxoY zV}kO_>dU*HbV%*oAQtuTq>JK{t;XLU4jgfXOvmosid#3Nh7X?<-hTDz_KV)}w%3!|9HoeLa1?xgOKi+bC8B69yG0YYiNB`K)*W!Q4zOHl#W#( zcV%WGh%2~%`P5G^pa1xJ`35Be{eUyv7(EW@^gll>P%c_eBK5t80_kpDOtALG>|8IN zv`|!g1ONd^nV5{3H-hOi0dvXzlm@$%`@c7tw=P;cp2Anl59UGZUo4oL`U~xfi{HIM zLsL+Xs=7_sCp70xB5~yu*o%R(J!&6Bz`}EG0jeI@Ixu5c8_N7v%M-cCh^}d{kvB*F`hju2lOiK zhHicIW3+MbpP!fqvs`gOksX6_^MkvGhLQj#jqKJ1KwJkfWyk_P!YN_ff1NE!19+SB zX1o;HwP21DIW)}|Q=sLXpBRLE4HTJ5bqY}=w&2C|DyewY!o0E;a7~iu=k4-C)&ZJf z{vV4k0#&^CXljxRw*`ZO1@ukoC9?Xay;Zv~ps3{bP;{Vyw3SuPmD(lb{<4yi>X`;3 zlvDs1C_(GLu;?oNrN*D5BKZrfQO^4RKB>KR0A&bAE!-A7ok-g^`K~`-@v@ZphYl}n-)Z|VYH6^ z*HH;;BN7A{bFCb2JB^9S07+YO$sGd}w@;`y5PY=vIclQZ1?wUxsYj!i7H?y<<#kbn zP`GsI*OGTQH%4p!+x%4pcSX-YNUl(Hdeub%KYxGibA3~&aavk!K`_g0^(~B=cXZWD zR2=1ikDh3N8b>CEpEw6^!kgRpKi(V*ykP)__)_x-m{b#}b*_1g)D{g4l8?5maxyuL z;m%mm^cw^3Bb-s^)^wgubzE{N3C#pLCQ>G`0yi4_=D&?DqXHV_G|zrGCIs66I?J1^Xbirur^9b``6qV(q4XTg6o_J1Cj-{>9#%?=q=EDzEX=_ zXGH%$*1`u=r4kzrjUIDHUkf@)Y%Ea;Bpdj4O>HeHwuT1PIZIJ;pbMk(XV|Y-YNsbB zsSpH6YS5|)=>2mXyWzmY|FIjoaeQXcM48xtm@ff^(CeNy)5AEWI*K?fH8c$L^i73= z6r)V&fG1?)@DtN1-dDm%8T{H;Tx^9pe_{g)3-OR9jhVows2l!|mER9r%zWZRhLVSi z%acIm_tjyLP&|XfoS?g5{rWS|VaT8U7bV#{BqSMNq+$|u!kU=u5!~Fv>z5yRx1Q1o z#hJ0`>FgWTkf;WPA6$o(aw@dW$-`&<=hut?#M5rsqcN>&FS z5OQMB=QDtAc#{@01#byVq?gy!j4lg++!*G(4tVozrsIR6*@=WnFim-)wm=7{9W^Dg zU(04;w$H+c#7rO;P?z{03%mh{?w=rJCpBQ=btJZpra8-=zkP4qHrULLm-ECKXGGbR(50C5{wy3DMZTiDc{^re~PhX}{>PP?# zY;nF?k5d=>9Km#O(bA%=en){K1RBda`~m|Lpf?!|-2u|Ijxm_@yVhJl=&uTyCt=j6 z7R--uK7z><1R*R#iEI5%t{q6_C_+~+$@+_8W&KJnCqTC-4F>Xd&S%g&>ItiOP!+A0 zaa1Mjpx%K2<*vm?gg-WmLY%N&CmKbTzC~}!0?qjunwM^m&mwMD+(fA;E9*nIW<1iv zI2-INqg_9pMIQl!2WGv`WS_A3*GP};V`94^d|u6rl}E8k{3(0#b!$b>w*mu^op$rB z{N@WZoix%HpY=?Q%Wg|?3isGQ?Ol+tP!JuxQ&N!KKj^#vkAyMI)5X=5JyG!5HKhVf z@-Zs>_IksExjb&lJW;X+U|f$3Y%om?b8}E(PXys{03BcNQC&ET7$j4_wc+Gk#30cc zLC>Ks3eDV(iv{gdH5lvx(V$Fd8fWS?OM^%1i-r@2{2?{P$9qp-hUINs_Tx30=_nBH zO1kml^{`g$v(phx-$u|T8jVs*Oj9A!s*NS{C>}E#JC*^E_h_F!10x#|Xpk3obs9B% znPXl;kWL>N<%jP_LrD~X`a3DRv2H=X{bOq`T5EEOe901t;Sy%jih6Cw#Fo$4ru^)9 zR1nLot+?xeP22n;T}rOCa0s7o>% zKnpgXU&X)y=&~k+xAoH(3>20GeFX!=OD3?znPH1RY01liy=jAPP$D&$po_M-IAm!3 z;PGd)=Hd+1gL9#kqX~_%0BB2!a$Zm?f>dAv{{VfnzR4upTg`O1LfuAQw|e-}?Gjn= z19@mNPQZ4oyls#AE;+v!?_c>RtbghAR+DKV+}kXVu`Mw0@Q~V(UM-P_wywzvSMOUl zT&XP0Tc<-n=lDR12a8+>Fp$>s3b=OIH~(0 z1nSq=Gs?k-1{p!^iFjR7vWt#x53A z9)pUfmU#`DtrJm=Z|yBW>fVoVfMes*G=_OVo74|8EX8b-l`^YzNB}{Kvc{p;h-wak zl>A}EpgM8(5javR#R!G~X?@Sokcw{uY;}<9KbylTy;t*kqqq=HMC1@%e%}7ZJiF_& zU#G%7+Al5$&2zUgrx<;>Vyf@f#@Q11YxD(ag2a{c|^Py`azv^Z2;K*CbH$>w} zD45@XNfGDS!IcHDH6CR4mbANWC??-*7tcMb-*ToMIsx)ma*4Hsf&PHbVD{j2RJ}3% z_XZlO9Oohe}Ziuf>S@CzIjs9m*1=_GHX7vVA->x|cdNW57k-(XadlwrJ7p6cvcpw=u)>V=_ zP;J3Zhyjw>oUue!IbU{KPV@Qm=Qb$8nxVp)0CyV?IHzX%8003wdZvPf6b`pblZ+H0 z6QznGJAz}QR~H!IyrH1_p(_Ogb`$fOWSV(`zi?x5f&z<%KiY9X77O(fQe7n z9!_;2GQ3ro@k;S1Y_T+;yCoxgkRmb8;)P8oI2*D!d(y#(!M{kiD@0t|M2(ZF=-G_nMFCd=X=h?Wp>D`p%$?aDFfG+`Q`j)z4F04;JUdIrq>p zQ}3O)pXEg}tuFin%(%D)jf}DQ6q@9Rj~-=cr$Fqq3@4C)4j?>zFg-caxwNGbsO830FVWtj zfObWZ4|K_2kmG?)!3Ys-QZkJzp4I`S4js;y@Z|Nyi<4|(&rV%}gra;Sq(N1&C|({O z657fsABajLTAT;ag_EB58U20KD_eN!k*x+!7n=2XLe++k;n*=H6&av|_8@s8UuBW1 z^~}If+LFAZD_`QQ%Yb^ZXtaPJL4Jg2b%D2WU@E=gIx06wYn@1ngACEyYHJh>(yreF z6ZZc*0A*}UKH&G6?@)~%3+vuvN!E%ji!aPH)6E>5&3ga!sdMaO&$Pe}zs5o)`^D6W zk^IOR*5u*!KmIi*V9zAPh+3H)&_8Mi--&aG1XpOme5u3B$ES(_oyFKA3sQ5B-i7iT z<{YD^zY3~lFrkoccXo8F?d()Tfj<@jUrbZe4Wh0pI`_%}3fvQ*+L5qk7Iuo7sjHCx z$Km$2wlh#@#k`v<*u?UU*rRfwhZy_UCcFh#ME%@z2p>hby1Qpt7b7^EgwiW|)YJ2h zA*Ka$MhYD`B6a;Kk5;}!kG(96q)4WrHe~jzb&?RVo&04i?N}#Rawn`(g)l( zwJuf1^LM~WmLG6`wy3Lt{VA^tKAg$z2H(Qt4vF`##zPKXxY_>W=JEd*bG;oD zU1^zi?Ob|&(A(6x_@s^OCeMTO7uV|_T|@P|dB%SESJm~p6xNxYI!vYNpOZy4{8n?E zE;&&2ST4M4*wH5CYVH*__7_qwL>g|hSRBp7)&LY`wzS;8b(5!^|Boh-ux>N~?>ni&m$GU_+Rx*a1kt}0lru&omJ-Muk?u|+>3 zs{b+KnaEic1}?6~iDhd(Lw)s!tUix<4OO3FHT!aEg|TlPsCjJqhYxpCu${}kIV z5keK7y2mMdrp;4#6aT~LVYTK*IEFXs#86ReYQE0sK@#0{mI|Tw3sH`puZnq=-?ft$ z(5QV47yyOCVm!Ue(m-ed0u84VLA{m+7??5O??jImuZx0;`~aHREN^q|s)y6sc)UTi z$W9R{QAk+}_&t;8aoRh~4|X9DJh|I16@PApIs~e56yItW&Z}a3_Go_73@x*##o?>k z@l!xj>=$~JVbH>SkNc-#hBXadmjgt&%>4q|(2%AY*Jm$X-%(d%9~n4DLhzbdk(v=d znhpjzUHV+>oLLT|Adz)Z*1t!F?#{_W3Pv7x|7-ZHO;dMOZF!~!CNr&}=1cGwKCmduf@OX&4?hozVuO!TdPp&)GQIOQ~O4`ZUppeHJXoDfk9NIz72{v$-h zokSihEv_RFxkeBFhcL_H-gY zXzDO4%+wChIu&3jGNDYJpo_iZwrQcc3!Rq=7`sWek(7L*679IM;S90otjK5p8Jxbk zil`+acJzSIh5n0>fPi?kmGvY4_NA{0=23vN<7hL5ZgT*{{@ZOXKw|q=AtHPWo`iGx zmdcJhs0hc-CvDLM1RH@ljyDoPekJJ=`ijJfX9?^1=L9-cMWufHLK!i%lJ|*U+fpQ0 z&M-HnvE{jb)W>M)d;8<;|LED%m8UAo@9dh;snI%HBolQ-O@t-XuWtK+)aFPB6@w8)%kcBES&){OT~bG(G7|kWL5cGy^z{=ruItFe z#Pq;iYmE}oTY(|acSy`vatofs1txePV$TKNx{Dml7q_jUevzMD^aZJ!pl zmXFr|P$O!sj`D(os>jg2U|Go~yMCkB%6{QtpN|UMtiyf*(|(@a zZi|o8yrO0hF4gYXkR}u9HmA}WarStFkk^%{7)uc<&FM`)3NtS^F9X53w->B)o;=w) z3D93uYht8R?bWMS^0m1}pMC>+9fjD~yDtcGk9!*kbP~NF^&Jr^@U^cX%H`R8Pb1io zmsdnv+s%?EaY>0{m&+z`CL$1JA&gZ{ggPw?&@9k1r5qfJsPgJA3o@T#X2! zZcpS_L0m5Y6~){tydX+BIjk$y*0>#8pdfbja#H@|jd5l4aMbPbxV~p$Tm{bF<^n+hNz~l+Dt??sdPXM=B-VYzO>`uZ#B~cX;;(9k2dPQmnYV7Po9#vleRVd|}L?IW6M0zp+!XcOgCQa5zTQ;}mr$MXB z6Ql0cCp+)Jg+G`^f4vH*I#1vt+iigdo=N0kp%kDVUvdzAX`j6L9xZPNpEW;khn+n_ z{EG@LbS%MK4l&?oEwXuPIrL z=SX8n=9!HYN3>FscZ(oQICF`uUMVRKIReBhgfqFA{SZZhM}7lJagG@d3pOB0aS!PU zK5%0R1ahE5PCc6SAC3%RB)l)1+DSly>&)aGj#2inaca%f{qp3SsnD+JOvaOqzYa014X%-8h-@0*D+#9j_g_+0DwqO zj^_svJT;b#12p^kq|8QDH3TY?9FL&{C_5L*Yuk|80dpWd-Q`hMs1c zrthyXuV2AG^Xtx*mP}qBNlk;IsURWw%feY>8`k^yD~EA3vdi7$92m?L?cMe4uCHRH zzcsflt4!{ir9eqf1$FsL&vQ$)Y^-zQEY#(!^Oo2S&~=S4gfbsoKbjKm6dy7+IVLG5 z!DX(0Akl5#ec@V9J6?J^kNqdLme140sBN^g`Zuy0Cpy*0BoKmkQf)xXh+Fj%MaVOW z>(;FC(NUA#47`h!{&usP42}Dhtr0XXbaJ8;f-G)>c40jwpgZ=U$I8PrZ5~RB!YU-c2 z?ScKa-m7{fKtE9_&msDEM)Mwf& zb|c2@{jGlwZ^!kgn^U|S3Yk>+=>1uXW9ykt(s}ywDoz;RQ|>DgsuOFcbr^i%rak-V z>s{LG*Qq`e2lUTbl=ZhH?AvTu@yR_V!0bZi#m-RPaP5R8F4}_ln8390_0(_+r$rON zE7bL|@$%*?WlL(S@3-SsQBnn}x!pGE`9F znwKAU5b!8C(Kog&?vR2oH>>`vpP6x}u1#L5LcmyRgr$&FE#M3DNl-S*K?3XMbsZ`10lwTVMo~cQSZ}1hG!ip1N+q~Vekkqs+w;d9 zpv9U?0#Iw~=INRe(PLgJ(^tw)f!TyCxgqb`}D^*)uSQ~rstz5h zJh0?6yfzttd17C_e90cHtsQ?sSPNL6D=?v%YqY+lrKMj{vnFjrv~B*f;BuAB0z5v@ z@%#JLA4!5ZZ>PM^o)zt3TpX zi`Ic_S=Qs41WE>#j{sV#S!SK=VtM`a$>08Ah2ANpUh&$Ce zYTu&VdRY2#dGhc|hEKh0lOZSCzbAU93M!3zn)SvG%;wt6do+qCDWq!lW&L(i$$$D; zBqb($jW%_0!_r)}-#U6BiD|uXU-Ok8;x3urpRvu2?;)N%zZviOAl@)AXH8F_hMs*Uj_9VC`xKXIrS^9@z~ zIBQbv7v56^9EbfC&P-;M81-ocT~RWPeX?76$&vwSS#a1HyWgWoB*Q80R}{=xIoO|^ zY+5|WdHsV_xog(~~#_>Uv#hS#pa z>6h|F)d5melGyH4fG&FDyzmMfiFCaEuem}J4m}EyFz%Uti;Qom=nE-5fH0FVi3Y2- z;ZJIDjNe@9c#OOLAXsC`%OdbHZk?Nff!(B4hPA=ejb{O{CF{PNtN9$XS18#6WMN_FN5^$BUC z&!p+;7heo>YrXY&^hSR_r~0LNswi*%$K#updIZ}!dwC}9rq?BPI9^(Fzjvh2$MfRM(rx^yLIS<+%y$%)+6meom>ZwAeRe)*9bmGL@{s1I8_fVK~zc;FYQ5>fe zNl^Fv3nEvjvP5BC=(!0yapHN1;A0bbU~m zJWJoF*zk(ck;o{C>-+pv+I{G?Q|D~NYUvUOiWH=VgYrC|7r$#|64E)?pYm=~g0^UF zbo?$!YT1vd{-Y9Xm<;BiCA6kiqS+|Jxcgc=LP9ASihNX{&IO8v{@yTB7(|&a0Y!yA zG{QDQQ7SRn9u*Zp1c#j0+`4k*iX6-*L8}w#E?E6}_{-vLG6H803L^QvhFK|X$tdvB^JcqTQ-JvsQF~?sV z91x(BxtoSYXL_8z4$$yIWaLY7~c^NbMoQfyQI{h%Gj#BHmjQFgBjs_Fk(x5pP}1oc8A%}o zx=9k^EPnrjJV`@a+2R?j(cXsOZ8wwEii@a9sA0VW$^?JhJV^{Z3lC3gvaPVdtJ}J+ z8b9Yq$Kd6xVB>1^|}00A7?DQ&>EwD?y+G|kYV{3Xi}BHp156%l)XJgQmi%C&neWe|=?i<$D?iVR_FuE5 z*?gqsS2=3FT&&KFyi}4?e1A*igSK{2#{&m{iyO?`;4GY}^zt2|FKK>A69^2BeNmfpxqTmqvG4Q43Mkp+x zY~26|EZ!gOQmIh~eWY-xekiN#00?AC$-&H78%R`~#SGj8U5Hye2dZUlW8<5l;tW<7 zSK@xLj7&e+!F>(D!f#JgzCmqAt8u{rbHM)(RbK%X)z-Z~>Qz4#Oh5qvi!P-b6hXQ> z6{Uvm4hs}ikdzjshLjkIAygCuq!~Izz@Y_(9{8^Ve!u(u&+}Zo_de=5XYYOXUh7@& z`z|{-?-c-wX8lbdI)J7^c58m@#Xxga00`*15#mf}1IQAU4RBEqJ{=x`me-)EttM;` zI)E27b>%R^sT3U?9E@*Ug8~~RHMRAc3sep5u{sce!uQb!TSae8K+V0=yKrQ?n+d{O zncw-BpAlt}Jf0~T^-MQ#W%Q^<(rW(vKhbg~H&a!N8`?UCriki;#LFYs4qIvLILd2i zPyD{$>fxHXbs%_cCD$@HnfL-f;}tf&{K%xSc&x{NZu&@eg#+c`4K4LGi^~;Qb+__3 zrQ@s1Y_XA+P;)ToKBfjmpBj@BDx&T~*OInx5tJ&T%vN=hf?m2wuqxg#{Amn&+8=$c z3N8Xk8hYWS!`qrRL@Sd{Jm=n5p~iId6nz&|N631BvM+>5m;tA;AJM!vBU{_F16jFyx!{WJ*TNkHt97kY{?N|?5`oeIFGyKBf%kQ{ zl;qD2G!rxmX~*d<=>XPh70weOLu+}tNCP{lKYn*?21zUtti+ogl|dMXC<1dv?m*u` zZz5hd)bG%f4(L#%1>qhRo+#Aqj-P`maA?taWhqx%R^T|G?SA=a0A^s~%)e2vns<3z z{=5`Vxjdd$@#TC(Ma{L1GjAUI&Aw3W=+X{e=`5$1m^@E~lQ1;dR2)9xUF29U>z%6+ z*zjj}>&V0A08!E`({8ijbMA%kQO=6*=( z4GrmadX$nxw4wUl1E-!zhdUh;5NaUxf`ekavH^^zVLssC*T$l?%`Ghra|?{hHK2Z{ z(Hw6cFfRziMHqIgxV6Fz2&P2*fMn4Rf5r_!<{_w+xeG%GuL6;LX_JZIBfzFz|p##REz;ikFRs03C-*0CZD5z`2I{6qM6IJD@WC zJ1itY;^Mh;@4ws{NTCH7HsoH_+qY8SU>^>lg~f96D+``DvO^f8cmcSkv`-dbXkavQ z51R}SKG>7Bb6LKm7dN=`>SAG&Nesd&3L*k5)jN^6zV0b=`!*E52Fz<3xqxzvgiho= z;H{+v#zG}ttzdCr45YLV2HYGRT~NooyX?<+kMCPIl*%3)cLbIWz8}bb(c$5D*LW4P z0p~(rH!$1e1`5ra|EcwKxM-uwh?g2Nz1wSxw~wx??NCz0^ZStGv3~bo&L>ryWERBC z`G^`z^c(bQq)@Er*3P!N>9)95MG0!SENxlc^B3gg`mpeTb|f)$8uu|)6Hh~mkH@pD0*`46wK-Pow zZ3V(?2cRu>!#z~MF$C}q51WgkuLCUq+-@K!BB(@kI)B2G;9%PB`(|bx5}S1j?Kdbt5E09;pnC+Ql`9id z##aZq>(Gs~Hsvx12)m(Ttou&f4t8Bpa6i${qgDRQnYXu90{Ldv-$H(_ulPB zV{2Yj_vuC+{n(xNG8ku&0WqjD2u31!cz6_m@06aI$qp+O40aI# zUI`@eXBUv(XcxKxGxMqfhfDK$yd1V|CcAO_HaUE=5H;x@u(0m5W%eiLj=Nbu;hYD)r}Dm)|>UGHR0B(xxTH}KK0j$^kF^6uhAL!{F- z6nzy`RZI0+q27)V*aU|?rJwL z%x&-@(gGj_i~|jfm%*-t01kU?2yGn*tVm|Pw7UASVz{>UeJ_TFH&>c5hbeSGvceC$mU6O~ zK77A;FdoVV?gR@TpBB{J!9o)81xLuyfAFW5gL80#=Dkg-9JOB#K0DLEoRX~qMH1N#P!=gA5qNR9BY~vtZN3NJPXocC$I%$FL`1&R zSuzjx=Uz^fFX*$7g|9OMj*F#D!Y~~zvap*wCIQ$Z>aCrt9|<@c_1I znAcv2AiUunFm$7N;B3K*!GpS`SLG{Mdvyy=T46-der(Ik;t$y5FI4j_6{mTfqVyY_ zKZ7BNYvkNK8)>GP884dUlW;O;4;lRPlEMqHbl-jH|HRb1^%HvLh+w<9_9wpNuEl=tCuhFAbgwk9!5wf z-|FhvuD*X#LtBKnLb>ZfNj$aa4CCB`0RzwL1q#7(S9f!u|9&@g^1&5;PK-MA!CG13zk+ZpcI*gSj5FFbAMJ@JQPF@^mcA-*65Ol&wEw^+>&cL+;M97ZH+k$%G}({%#yOVEK)pi|fYB?%3A z@bgtV*y6#&Oq2wC1D#us9*>~%UjPd}13n6{HSr7Tw4loa3ZOU40YbzHo(+H_-U_^x zmKGgnn|?ds<^&KG4#F`7k%M$g7El=w+EVFh8*@icKMuh{08Z2kJpX|M2MmDp94}yp zE_DGIlL%&ER*+~wq63=~((((mT@OlKu7ZpMY_(XJnWs)+fj}KSJr(mB3X=#E8`xp{ z^6+eDyYWSFUh6cCa|VHJ2X7kOa_BgGK*pNw(tjR3yA*O<=d{naTW4tH&S;$un_yw9 zQamOjb?M1j@6hn@aFJ!wXO9+jd8VgTmKy#&2Ktu53!<&0C+94$6{nCUH|vhH+?JK4 zX~Xk_Q$vHh9iTZu6ELD>@p#~|NZm9m)EnGHWHhnfn*w#kr8H{dg+CX=~A8?sULV_lI|rgFRYzOlMMY3EJv;;ej=$?&;WG6E9Pr-i*+C z|9&Q3bSGiOD}Z&PXoe@WOg5E~sIjnVAeJ4y<5`%ns#Gp>wLhq#r)jdgI--LIPnhFJ z?=(95eGt)MwWn9wJL)Lxz}nBfVjhG%5SNu@B@7aVt8faj?mM{eK(PIl;|@SIu%TZa zToboUhkY6mY(Zo&)L#!g=oOH`d`I)IYODb@cLoX`TF=iiIuF|hLdI!B=tze+hNsdU z*uhxyCMtx8zS#d159L2s(9?*BQ})9q58Z0=K%QXhxdRT6TG?6{+a74^PK0%EA)fl| z*>@n`5*;9_N^E>>6C?B=>j$g7s>_*Wv~C9%5w<)$5l7E9iR1?SUfKw#)s3DcLmiU3 zQ36;7)?vg133z~f=aAJ6#|X0HU|?Y(ANWl=q(BZ>XPaE>IO;=e>BV(gu z?s*tOo(AXpJ67m1jns%c#leo0&-~Jotf#j(B0E!A1M@K{I0!eg8K9js*qQ!@o)+qW zAuMTM6{H55XcsgTagla|oe%4?W)H1f?|_iw_06G)Ap~`URVo8J8g9(s^5x40m7ay* zlX4EAwqZ{fuQr^A11KNyA8y`(LmzrY*z}hf35vu)1>9-LNiu+bT zG@b<*K*ow17-RxS)J{l-dZ(~>l8_|Q^K`Bsf{^Hl2s5kXYi@J>+F+_5jQBzOrbyWp z_mTO$+yM4okufN3^d9=O!lwKE#3>H|)*SNy%tN?f2yB$<2JmPe1S!xV-m3yU0Lk+9 zi(i2UXVJdHtD>R@E_~0Fo;pix@2}lN4;(99b+Q~+sNgLsx{?zURnSB3OExveNKCq# z=dW!bi7z`+Tx^NyBDpnm@-wGU+&LhT9FlEdpsuYr)AGGBL_9!-SNGfWjMduq4-+K? z%~tCf^I`*6&Gbtz(YnT^UF_U5rm7ixU&$o~L@Wbj=w3oHcq^A@B~(%i+9x)~axb_- zCu>WG-(5}M`j-V6DHzgJLF(}y(UgRQwT>@9ry8)eK|&iO%Y;AO(A2~}g53dQ4Mosd zw?T623c(B#XCbf}g4ICG0ZH*qP{xBmB67%nn7j@!>@*NDO@pOp2W+gF0B24THW0-L z0I9@JhfX1`28m2AsX#77w8P*PeY9$+k-Z=2P{}s%UCAT&f|?RA6e1>)bAw*+^71mW z)~C#U;Q+`8$uU6MMsOX0h9YS|;!Wspg7_&H+)q?N(9_~94l5MM*9h0aQqKZ1TRbpn zI8Cd!E3gniB54Y!oq0GGBta{S5b5_^1|U5^m}~%b86pc}XM0%{%2#Yq9v|p=1`?%> z&Ea)RSp*XY5qt7PJRXf${@V+|XZ$IN<79B{*gO;J?b{D}gFg3~3Tk$;0k2Ka2>>Pq zji`I>4_`v59!I={Uj?G1H;}!j4fGW_;ub3E;Up=62v5-U$)meq>a3ttxx*I^%qKVC ziIM{gI^@c*0}7S@X-oMAMXCO#^*dK@%i-i6`$t`Ws9n5o6^=U!@!3sWt}5PsJ4k%4 zdrURKTQEP38HZO7FF2MNe9buA0{i-GarNCFYLBa9(5?}K+c;;-kp8Xa6nSfJVy5Jv zL?xFo?cIR)4u`yYbLZ_3qXzS{szy*!Cg~X&(;y{LS<@;oF$PqRYdXscgtp(EFV&&3 zpb>6^=W`4O5g$aV%HW>U1xLB-ukUA|z{q;}@=Zt%i}W}ECD)ab3Ivuv6df|43ZD(} z8`!QOa-bm+XW5I|u{M|~a~?c3LJkNObxwi+4h^ak{d`2dg0SdqXm35#?cJ%aB~GDGDySoYW@gZD zE#uU#LXUrg0OXzKvNy9@RKW)seR;$1)+;9`wm7$6XItML; zq6lZaN2$iBK1a-zWlMyog3nTyhAy==IK!J~+5yo98kIF5;5~VWVI$a3Xu!}6wZ&~f zZR7P^KX0p}v;p7_>rPu1D3&8gqzP51U+DExF#1N;FC0)H#4LbG|5jgb1G|7XoMw0k zz%SYeT|9|sbU_Nu|88F+f}*%qn3I;m^lNv+#J`UC$ZTq~?>30QA~yrd8aQif&QKmC ze&rks@hZm!m1Jkcf8Loqxw{i=s&CzP_L&re%urZdNX-uPy$=>_-mO2pinvEnPA2Q&1-%ZT#CE@6|Te2C(BlBYE`Zi|95-4h|FPh|R zM==gs=12g^L3KWHCE;9-GFoi0KlYmN#g3f-MM+6U;}Bj6ho(Cn43cuv0pX1lc_(U* zAL2fhGp$Y5Q84b%J%28CW!u9CJM-1tyx-V|ZJ~Z9->>epLB$gjT=7GL9*&s~-~H)8 zl`q47p94j;9`WS3I1KOtK}^@|EUi1)TkVGfs&eu~Kj4H)!coUyU#GhOAO00v=%W>X z<9<-5IKV_*5NNQQj#L_Z>O*kh2WuZ;)`72e#9TE58P?D+8?==6$0s^P}|55Ue^?7`b; z&#+&*b-iT2vTja97>HD0H9B~)ghiPlLCc&bA0hex?L(3q%3<#LdH3wHSwGcxPKf^< zo9`y@H6yw`c+J@gES#W9k<6+(Pmfa$w#EHH+JbQ~tSv2d06w?SZvlTu=_^!wDeghP zGj&;6*^e_29(BV<5jQn9vb(sv+zD1Q>EOH!v9+T9e8czeZHTl9h|?47`-6ijhxL({ zz?SD@Sd=L`V)*f6*MtmfrD2O3cS;o1YHS2K%@?v7y2ln- zrmS*Rw7MN_I`{|0REwWS0*bukKD(t`w#em}Mhhs%c0|5x?p-UeF|`?v5)o(Sr@d$E z_bVhUQ-=q=ghpmLY#w;%uTr(D8;jB>XCz`kT)cAcb8#4t}&@ZO@=v29W-}QI) zehx{B!2wm`xdwu%kEW>R8juqhDNv~SP7sm`@<@AIV4&<&UOuZ&&iP>AI*T!FI)QUs7llk*(dJ9InG!uVnhrLsRoUTLI}MF)^{CD#P9Y4uA^WaYNx^dp8NZ!pUpA z=^Va7bUYUvuzSV*DPK)#$%C?}m9R+vQ+eU8B)YEUZ>2A~NaV%3ghFr-bH zPGhM1=w!Xx>eGtuDD}a+^ou~S(vaS_|Hi1D7SQA(UEE@9Oan+*02qJ$eDz`sVohkf z!qJ0-_~5SccfmU)_`#bZb`yYcS>lic9ndlAcwvAl5wSA>pZfWTd=tP~9T4M^H-pU} zTrAGr)r@nypNZu@F-BWUC!-X!Bd;t(w=4)|d^8otv}S5ZJ-b0v`%PCKo_4vol!Z&8 z&pZycL9}zhf3R65b>?yQx>Gus+TxDv*dI-Ld{Wu{veUxaY?_)yG%n-vgKrYp4qMl| z7_aO!Uf}FMn;GTWGx&CSw2!^QukJ`yU+KesJXdD86hrK<{rnoWjzj!cAc@eqb?b|p z4M0k6(su;sp#g6N^j363`Y4nN08LcT^&haakvI}~;O&1lfya@QzxKOb8nB}viz9~* zgHXmEsR$;me)~&@2|RcHq`b|DtHUYGv5vT*j<7IVO>T5nmvzxE!~QqkEGw_-nR99l zbBtropZ%S;wt&vHxR-8TsAm*oc(=sI=y*OmX&baHZ-lAqyA^rkI2QXtp z5ii583}K>DVwu*mGyfQ)*;jodVr(Vz4=0QpMUcKm3`L~P3r6>hmp;jn6%P3KO;dp2 zi^Cn3*3LK5ZEpy$0x4{+`8DcGyHffPtr(|P|B4S8`jhw)AZ z4tHJlc}K@DMU8^B3p-D*S@--=q}e7opttJSVt;w*amKfC8r6so={M)ZvL@HoKrk=o z=A&@`qx`Ad$Ok`Dq%GoICp`$b8y&Ox8ja@5Md3D(@uDdVG`NZR1r7}8JOGG{V@RFJ zycI5!vU9=>t$(KoSvS8ZONZcKo&>+VP1ueS=Lw)QV(o)&Cr%aBkV_>AyU0ShN|14X z7k}F(TG%{9cOkR3v**aE1MTS)=;OSS3v>M)+oEa9M}M^5%GcwdlF{Z&FQB)=5Z3r~-iF!CQ&)|( z$yDLQWaoyB(!;vzDz5FzVUb})9p^<>^t0!$Ub$D$1J?-c4`z0W`3oQ-=-Q8<0&j8h z!cY#DwX`aVkBqI1nEe=Y{JmwI+2u7&-MpFvn z%c>2pLiY4i2F6>a6fEMjT3wsWqSKgpx32fq%e1~UjEqD1y8eR&f&s$|5&L`M-b1nE z?nPl10OYIm&;k`5?GG7CQa*^MM7c{}=OvC6@rV}n-H1xNYa+fUL} zy|MMy8OdtgByHq-7p^HEKe=*4yg=@_4f9JQ&S-K$!TRLOob+tQzkc;RVrr|`JT+(} z&3i-^y&F2@>N4ld)sR%krh`x3E|t)u%lTD87W?3TC-vvp{1MdK>rlDW1<^Xl%@Ic~ z;8Fr;m3{m9SvLKmG&bFQ#LXm{Mg7Y}6&+Av3Eq&lDm53VzYpppf;E{YVsM6xJ@&^f z36#<2jpi}65@Q9G&Zvbo0`2+4^_hu#c;3=(e7Fu?sg;e2O&~_rA!27;rC-Qcq`WyX zF{-JL46CNiW@|&}Ho{4V6R;48-EDa#a2<;!3Fxts`#o3S%5MO5JiZgTPOqCEb zEa|J>9k;qLQUIhR8=!F)8RS7@ zo&<+inxb()I!X2tNz8g zz^1M!E_$BodC6$$pOd!q*`jkK{-nm@IF?d;iT8mllTm@d;a|6|h zm>&MU-o7oWz#TxbaLu~o{I~zy8FC-6L$GANbsHe9qV|BI7vPGTmR&W#+w9xi7!*j9JS}##DfS-+F0DO6)LQo1E&1 zK~LAkZ5gR&t|L4c|A1v4kQ_@8uF(xVFgZe|{ywpW>ZNUJ0fTM2rBB)9NG;`7E2i}* zEp~aGG4^l3hCH#gLSTDcyBLNjM*3|BuMIt@q-BW9VJ@L%_IUeH*05xTpUp{d&I!%H>@%~4}D$BUY z*U22s1SUEY&OYAehQNF8vST_(b~)^;(T4aMdGpTY{4|TKwHM^^H5+dtGlHqk_~di6wBUC)!~GMs zuxy0T>Me0R11QOTb3G|h_pt`h*nJ8~0c6fB0A8*;N~*gs*F%iNzux-Xs8yg5LXOit zDbFhLSz(D>JIGS1y2y@N{CoV%+jR7ZcTW~v_-ZPjt=X6@ffdt!e{JmpXBNjQ*@lTY=GmbI_R+?B zwKEGj;yRX%9zWcZ))F2~-F{~rDM0P|$nWGPeo1ZZy8Us~C*R5u6w5pZRj99@-|lL! zr0Fgk#+Ou8cLru<9}rEJ8FbhKxR0PNJYJ)Pzz_hhBmj>b!oa40G?xPXpS9Iw^T7Q* z0}4*YYh^i;@FmVq?Vku`gp33PCW2ye4ur|a$;q{W=?xxLza}Qq0fR=MN;uCt5!@3T z*z9^g+&p&dSb25;=#ik-s}HpYHGrj-hb+M#rIQ%oFLXa9QDUV9qpB+kIxHv;O?~vm z4ds9Rdb@Pu{oS7sYK$I-*FhOQTuTsh>|N#q&e9#lQq30*UAy#hucIP%B^MNvvDaD+ zdUjHk3I@dqjnTeSsiRFF6m44dR_-Ti6HdAutx7?^NnNUrh+;AkIR5dU=-c)4W2#UfNsedD&CE$DsQaR-Zs=WHe2fcA zTT_=1s_Z1JgOC#m%}k&^&Gdo&tn=ZO!3#UK2M|1)Jn$z=PEU1!1auBg15;aF>@SJ} zJPII}1D8$+Bq&4WR})+l@bB-OLLAZ0DdNsTZcS91&0(coR#`ZsYbKyRJN?gwyuLJ^p*uA^siX zL|*JdgiP=`P6Pjr%AS`ltW9YIm>P_k*Y zfeT+IEE)pTXpkz0^TnO!SD>^)jwrAlnNIQ;ew}IAa{fL5&YG%{B-iStYcM8zf79{e zZ8FpVH7ZEHgC|{otC?c`cP2! z({jL!Ojv`xwF_rnT2N=xk6!2JZnkf)2^&}$cam7zk35kZsPQ?0dHc2uVt^@K1VKQU z*wQnE<^raRGtiYzWla@~FAzZpv>{KK;=m2fyAD|tPn28u|B8x?iz7sUs0F!>pUV*k zBumG?`P6;73J#LvV8+$wlk}MzM&o4B#2fqvxhNKN6&sSxe?!r6UaSyAPYhv!W_qa^{O<)F&zN*MNYj)+-&{+eM=^7Tcyaq!bhoN)xJ$yA_=MZ46WNy;swe-DEgF1UKK4-A_r*d``D6!C z=MkklVw?-~M+2xy_00pFYyq4i-^1igV5(zdm(QIx;zuPW&u^RI6E|IftlG$W<;s_p zL@1O1Y-O@mhDRfH5yA$`8z`<6iB%1tv5l=^<7_BY-6-kE-Uec%x%!jpX}vGYLdiNu zk0LW&#Li&aV)4j~BNpfOPNQHqKf27DvDM3@`oOlyfgn8(9%;#>?^~z6O$I6FF(;$# zmP+D$Dy|QXqoru+N=(%AdR5KcF6`od2h~eCfyk1atH|55FS|4W_ppWlV_fp+Rlbk2s(xJg7otbaIw)*?M{17uP1*&`290;swn#L}qgn(4vlXcp-?ZrZjqxtQF_+Ac3rfzp35okpMLG7jlFM~<33lRvHZG+UTiJ6gx}%y z86qv~&kVDrsS}!s<%#dC+3&Ax3=4Jg0B+s&Q=M~S=3BjnjOiW17dh*R(2m#q9e7Fd zJp1BI*6kI+CHbniN!s(V9J{oO96AevPqpsIOSdvjlPGWWQ~0Q#kNmOmx=94N=Z-M5!O4>T_?A0J%S`*#qRT^^uS`RB-yiqxwp zDRtyMwv9nT4UFy)`mL#%dq77!{$s?WjG7J=Xm}IId}3fKb^O>drwU7GpX8N4v#_vz zB_>xQO#m3Gk2;C}x23w~C&pGc*OS-9C|3%sv&&OsyaKB8?)omi_(I6BtHV=| zx&#MIopNYdba2x6n9&uG&-W**YurxrN_Jg=X7oBXqbsN!9sG~gruggr9i#Kj7cW?& zyN~AF#}kwIy&=SjdL2iShrr^$mzvrQ$N}v~0d4~2l<-h7u!x}6$EE59we30AA?-t- zgeQJ=G4K6;snp^%T2_MZaLUvNMP5TAQE?#>dN^g_GwS-1WnVI{_tMOeg1n$5OTNCI zbrrrKwVJk5Hl0+d)F5@aZN(omB^vQ9W_eibxM0=BCSrX;CsKMRjd@pqte4|ToIM&z2Ua8WS%)A zOoUcqv=-mcdtTY+&tbAq@T@)S@PK(8hmm7o=|_o9eN*u^ z4ZrtnO%~V-43EB~H(a;=q0@k#Wo=_Dpx2&xqpQW_RFmp9W?(!M-P3=JZbdJ)KVy>P zr36OQ!oF>6Sy!p~-+Tjgb#EBYLKHYUdNk%(cM7=N)p-;)(nzU6Ne=naJ?B|L^gx)e$)q*@U|8JZ5AT za>RcrL5EJr!JuxP3yWPUT+KFV87U#7a30>#7{8ej#g+0wlYF)EN_yrS4Tk(P2K~Ax z<{k1kqaP_XeJ>F$x$BZx7f`MkXL0fI$-P(K`*CE+(c=(GEfGqh&4f*;9WQAi7KY}H zQSC5P#Y13wbptFjr!e*=7e(EF5WK;z0h(DWHSNEU;|ULP)W8K)kju$n>9yv*>@rUm ze_6#%Z}i0dIqm+|rl?I8vx@3#NyD6w9D5QpV%OxjgXJcs6)vCYF<~GzDqI$nzc-im z>3ERk7f=4jB;wGU?oIO%eY=pVtX2Vfe#WVhnw0LA@mRic-6#EBZ0x4o5(57YrrP47 zJQED2TKF=q7YJ;mca^|g%RKby#*G`m{jf=%nFM|Hi%uf^-_D}_g)+$W@?4<$hX?(1 znA&&$z0Ggcl)Owq+#W`M@yENczWlG!0wmH#5)w z8Sh`Qdz?0>$%%>WFJ&t$D`Gvlx&_IdL}1$eDz`8JGi1P3R7m@eN+IHoi*mw?_X!-~ zcB)!Y!pXJ_SoALzWH!I^iPvo}2>YlB8Mh{n+LLG&Mxv*ow^dHpj5x;IXPLJ%GR>4( zUQ)u|pNfnU){U?`|jC zKqXAXcm&#=CfiIRcJ7@-V45eypW0hEqt4WIDGG0F;LG7q+VC&XnU%Cum@D1l?;2(u zT4|&sQeOOhU*Sl|b4dTPQah?f6y6KSG3LBUDJSt-_ne=c`lQC+xMA}rD<)nvHx480 zu;VMmt3#*ZY!HM&=)Qlia6^DY0%-vTts_*_)C9nz@S!SQrc}%=EGEnC?H@dNfOMr+ zSwpJ5$Q6>f@?g!}<>2)lQ$RODKYk@7hY8w1AxM*F_;;t2-#fOZrpIBicRwr%%HMyV z{%oMRwSW8J2KDvCZ)WYy*d_#Ir=T|*ZWu?NsM%CMwKPEZ)1`g))xA5Ejvpt7bQ%b4 z!o~$!7>#5b0qc(25)yqWl}T}wZ*_CI4-5tcm6n}Hx{xpcQ6Vm3pHwv}Fn z`On?GLYIiD@%zk}o&1-D=gA8gbh=fGkH}yGI@M}z4(*yRN6l~FW>aq*Ozad*Z(?q4 z4zva~h4s#&#k3xCZ^?_VQDn-7UUH8mhu$^mb}BdhJC}ip$Y|I{fRP;>A|gZJ2@o?? z0sM2Iph6}OJ@1hZqYfy(N%`Oq*iCTUFOEs2M)~9YV6g>;;zm@Bx))nNvT+S3-dq7N zekS(L0A@gWLK$;v`(;jG9Uk=jwO5?wii> z1iel__vJSqDy}L#a=*g{Hu=3Of6%) z7JJ?uk)G~~V{{Z}ty;)$#Oyll!JfmL8-Zsvh5p*bA$JJ0ae_pqtN~PKkXixI303cn zY)}T9X3hXR8|aEs)o4pg@GsgVc}!(80Y+cnrnL8Lfd@YuGoxZ}EObdz*b?I0n}cCb*2M8LE`16``nZ;P9OngXiUpAKR+SQ^ZDnePu7cBr09f5GQ6U7LPO zaSQ!*2ctyUs88%+V!7$x}Z`SXT9C4<1%Z>Xgo zFTUL%9zYo;UHyR82NKB@a`WwaX#U_V*6s<6rJx6YH$5SO{CtDm^-tpEjycRRv)xdc z29Sc zZExtSSKauWjWRi2254cM1H(F5<^WY{-~v~qa=;!0lH(RaGBhP3Bsf%;rzXPjj`S)} zSwr-eOREA?_J1eRJ~lC|Q%^A}0_vAcUlsf$qHW7bL(gT{Be-&Pk3 zSTAN8DpBuL)hNI5_gk@e8cpP_6u8TB$^lcW+23m$BcRJrP(^u^g{dqUz=!JsmL$=R z;Q(sGb6mQmx8CZAxfe67g|xw*8y8W?HTfv$$MCx+QLdVQ`6kGq1_mQFJdXrHhh)TW zLL7X;Xe4~gwzpr@v~fbW33T4wC{Fwo46$d66cA?#bEH3kTJ`{t=Z*octlK!G$- zz5@sq;x?Y?vlnh%`n%;lbiAR{U#=!nr5GZ~Aw1hdU)rD6flpr|PXoeIV7N_KCZpoa za7=eq^cqKNO`?KcO@S5`TVh?|YCDdd{ZX=;XPB!IN2BpHNaOuYjp)gZU3&GbugNv< zd?fmE6&ohWV)OjoJ}hGR@*4JJr(a%e$>t|v@)VqMoO^I8^_B{ARKgnlpp#^vu7=!EPK z@=)sSM!4Z%36E&;5!YbE;74u_6iGIq5C?jyO+LVpJ6lLG=W<_lb+tECfe~+A+ci*m zW`oef;KSXANK@^ZeuN*6NXU%Koxc&P0jWo-Kq_ndw=9bm*X&j9dKYt49 zi*gB);T1}+X;xw-2v>}S!fTXT1IUbz=!DyQ2?t=+09ZXKemwwZU0b8MCHP?dyi6Ts z%JDiXv8tJV<;#s-*FSO%X83u2K+foM)x&n{ryXx81lcE4-_%yvntpEh1z&vgus#Qs zH1B_38-=1!9ei{Fweu5dzFko4&H>bk6%5Y9#8=4m?#igh33hT3N90r@`JK zKR5uY_Bnt7O=S{o5l8K{L6@*j@mOxtZoAT<3?N{lL93wxEwf8i5f(eri08?Ze=>cJ zg4q_JroYN9_n#mZ838ke)!LeX=;Ui8*nJG5w@>XF*hVz72eir*I{qG{L_q$NNiP1& zRog5x3wa(#__~r_N0S$jmo;q!dKVdzRWJOR?zt9R`1qY;frNTAvFZI>*ZYT`4~_3~ zb4lpmKR?&D5*@6B*$=sp`@UTt`{yp|dmYeL_}!+ppzWA8017}z&eqI)h3H7&P|ty& z1Qd5Mu6B;=K+ZwLT;NVF`0eZ0U%~}oyN6iqwT}c{BLLM{3yJH-OoD4u|Enn*EGtA% zG62MuApA z?0FntF4Dbtj!n_Ce`VY5%yi$|ciWX4p8t_ige|Tm);c5n1no=q%`IJx4q;5smIfxf z4*%2;&oWg&y>=VDIdoEa)4gEQLBhhbZlH!D5(Ykcok~K&MefgPc8F>=8{U5kPlx0`#?q_FZ8{N_oW?`w zO*s9Ab!m2TwBDsTxsAEQ473tow52pyZ{Az8uAK=pIGy);F5AX+i-wIbWA6EvLAv+c zkN4w$3n2GT=M+psL(XvUkiqCf;jSHei)sPQRnrAAK?EXFHaK==)Gcy{RJyiG5t0kimdIal`i{L_89!Ioef!}klw5s0 z_`9L(8XcDThan-LWc5RTRiVPneXa{8|862ue?B4MzdRxufiXjNTCOH2t7IUwSws8s zZ&8~7Vt0Z_Pl$Kf_nZv;nY?jt$*8V14}bow_v`g60k6Y`(8s@O#t@iucE_*HKzyuis-$PK>K4N~|ST;KW;g2O3d zh6J7A@_-Qc8ziNOu{+Xu1~yAD57!3zx`MKDG+0xD!Wo2SX~!wqvH;0N_9+0|3t+O4 z%9~cF&In)9M zJ%ARR9sz$@>l?A?ZA^|ZT3GhD-Snmr1xs*?aeJk5Jz2rbxHTRi6aEsnH)Gg`x0*zy z(Bdk`?JhUZqm`N$>f}uPJCr?WG*2CtWtHS^zHkBax}KY`N=-{vkP?5d=Lfz}#QCy( z=fd--=IP;tZ%`Zid$IJw+y>fudU>&eCp7fInYaJOh;+yR-~osGYarJnuk31PQYD(M z5^0q1{NRKFI>;jL6@EoKn5;lNLt2>}t*$-s*q5w;oZ?t?g2K*3I{T5NO0d+j9^cZ~ z%1rM+LQeJmlhp+S4cg?{EKv*FHi%+tXLd`bUPu_x=Cse*(ER<3w})U5DXC&e%IBs) z2?Kr6D)KK==xyhIvO?O_fQB>bjVH-6g1d6@QL@jxu%N5keb^W?Kw6NVVY2Jf32GFC z80jLd3umjH4k8rVzXA=*&?q6HTNO61yBuEq8k>t(q7XV?kd{5QHABX*L%#B-ZPikA z=8xeQ>Yc-hg$C*0eO~5yp@U04q?Alk0+RhvU@%{!;VhErHy(boJWQ%9I^=EkhbyVt z7az4x`$wS$XP~cOtMhuP@5T~hAwVlq;RG{`bPkD{=m+AO8@S?~_xJ}T)m{&K)&BL? zQvqk@9~4`&GAfH{$(yuH{nYrqWM;=}z;(r}DAldXR>#lP;av0|%MTa7M<*~V+?#t* zfSYu)R*(nAaymnu>DJ~3we{2$!mSs7yd2{yC=X&cfsS9|VuxpCfDPf>fNB=d*@(6C zn*X;YjY@#}6`U+Wi;NP$l?3oGqruls$zGGx(H#0q74_Vv)wvLWBhWM|L|{*G^?w8T z^PkZr@@t{rwl7lX0Tp=DvH9NIGu#8Kp`hr;d>Gv)P}mnJ;ZjTM6GJ!{0O7PRzbL4& zxz`Y3W)(4Lq+_zLD_LCr?;FH4f(tViW;83?c%D+_L`d`~lQ= zePD)y;wNU4(bVWPw@gNuI&qymD?`ceCz9ABoBTW{;U!a3L=>Qbm5b$;XVoBCG z_oFqdvv!+|Lhd;$0pbCjlzho|fG?+F85Rr--w*Ue;Ts)=!z~$sRihk9Lmp)@@-zO& zT#9_Xfc#Y*h2fq2h9|6>{KxRA%epIL@wGwS%B`-ylfwc!2k$j^WjV_q-teX|*rV)( z#Dikq{J{ejR#rky7@deKOH&mT{Gex+F2Vzc>KUR*gkvEeO^H$?14ATZpViq0=Q(Ih z6Wwe9B-c8S{3HUXodH^9(wq~7L(r$g3Pke2xv`%<30lFY9$J6jP3q76QpG#naS3CZ z8WjW;7hbhX-uZ^pLsbI9bFy}KBy6W zCXyoTUlf8!qEvgmV= z?H&xW5;a*m=4?EiFQf638s35e0v=Mr6ZFuNlha!D>*wB|)#P2-EFyW^{^5c+fB*cG za)NH582Eq*pN}$V0Z~x))kO@ToMkvpl+>9&;1akTEt0XCIc~J$=}ZECC1n`vxIl=LXXB?b6DWH+=l>P9&~H9gjT1^&0KgVtV8_ zmj7t0%}hI#p9rw+*V5Tc4+I6c}=!L!ySXC+0h|?|*f^j%Tl+qi;`4~^FU%q9DV z)_IV}rj!P!Vh_k=`xo-!=#=6aD&w{?a?VJ1B1`f=@UK4T2NX+tY|Y7!(NKO!S{q6}z0!Y~g*Xy}c#i zsNFBoMJ-4LtnEEjtW8Yjl)&?8gJ!_b!C+r9UI5#Pxm}mic62_M$43ktycuh5MB;Z*2IO zy7kWS%gUVdG2`x4o2C44(Cp4v+1M7}fb}?=D=rxyGMBcyorl~k7ra(a2*>azu2nX~ z-E#5Ep{j4QNDgn{crtmmy@rDQ#EQ|OUz4a(_X7jLg!$YO%ZetZ$Bu=ibusG7r+s

-iNAmhv#>i58q;iny7{b8vr$5x_b2x zL_VIIE380~Tpay;Xt3IkR$o6}@;^L`jE6x>eE1cE|TBF}_U>x_9 zoHp<|bU@p`vK-483_h$Giax_U{-NNl!xfZ=W2xNe!P(y6U{DKduDQMWfb}Svh_X!# zR3-&h+WxUjD>~47QD0B*tzUD5m1*%c@2-HLPgt|e&-KifW)IpJZK?4T*v7?47x2Nk za)rkM*idYakyg1b>@1p!t!T3aNX$AT;nR-Hf~6$L%oq_E**zz=oK z<~>6ggrgx^1&8dtwsv+zjbN=qAD}m_1M&fF2%rvqg46Ok_!(3wNixBWba|xDOTi2N zz0%GXHU^C5QPJMH;TEpnM@bbrpsM-A!hh`^=j?hK>qXo3i@H}HXLV3r@T1CVSN2_f zzby5`DNryep0fr$|E9Z7(bL{QhpU1^{OJ?EW@f#;**ili;9P!@AKmo{m?7la6gI8pUFN@ z2JKy}2FskPZNOjg6PPVwB3)osj-L=f?XMH$cIso{`8!X7eam&uY958og<^+yDmE`9 zQ3abVrSv?pNZD>Y^*BB%crZfp%Vi#xQZ}iDOLzNS-j<9eyc6*K&p&>sYlG(#6lL$< zZVJ&8&XQm&>pRh!zcqBvb)9hS)g6iPmAx6da)rOIzyBTN2twW~Ebv@U0RqkRC( zxpWByLAOYL__Jq9eL&ax1LuNo4;=PtShRLkmlJ8z?SVOKK;YYan!tyGnt{>!C04In zS{ScfVI%Wg`_KNEAwT14Dvd6Q=G~=E=KR)mi;459==nqb;$hq$pNv~1_R{ViOz?S^ zn3L3|bcO9wIsf&aEN!kFm(B@AZw<>|`YnBlSYD>Y!!~CV^L32dU`#rt<4duFr1H(t z{?PS5cheSa_g};X%-&oQ#k|gfj8FFU6&bDhuoo{ta&~p)|FQMn@m%)(`}iA$NZO&& zP?@P@M@nU7g^-=BkS%*v8XCyTNM&V@BvD3`%*g0XSw;5VnZM(#>$#F)Au*Lid>43=bHt z&$F}fBC2=(-&<0?Xq>QlXz6PDiTz$jasnzUt5iFy(!LA3&Bl)n@jA*~)aqp^vA-ij z3g2JnDR_8JsXcV_2Dfjx6&D_Q-zXy`YsFbQG?H`fjr_UC-79u`sUvyC z8f6JZj}03FMY1z9iy^^s6A|KhTHrClQ9CjFu)b|kF$}>50 zeD`?Zqxo`KWtImNz@Fp+CG}fb-xU%j2 zv~%CSeY-_Om|3rdt9Lz=Ii0{JAh3nlfX#2u zHdQKUdKejb7fQnMgY#x2D{}hI9XodhKAc#tHHKKkeRS=YFuxGZxQ++Xno05K-++xL zsiCtf(`_iSN8gx-hr(2;CR;a!bm}UVVtfv-zr4O)H09(qwsDI--Di2boWo2e4+VCPhWjzs;wA8BVd8TVqU&PY&;UDs|K+dRp9O%yq}{mPB`!TY`#G;?gTky<@$7 zJscO*yj0Kp`N7qMJ>wB9q{&C{%i49orQ{kR%1S^adIOc!)$g(BX9F`e$n|wW%)@!A zZv$+P0z*To&z?Qo+|u%{riKB7y3;ryb-1K2t=d@9)6-p(#yjd88nR&Vv*Wls6FjwF zdoGDWA+6Ch15Xm74E_i>v9du25G#)WdZwkJq1mZ%MH7bJ!nm#vSjGL&GVJB!+XyP; zDRXl!e7B3%*8YGfV^!ki=K7yM>HPU~e|IYglu^e$zQ(0zc%7AzDMlk}0~P`TFcrYd zGj?`-_@SMho!&?(F+da&FJvD;=i&=0Y2?!M>G>Rwg{#n67468`d&ckSCFvz`gE{;i z-nhnZ!IeoCOH0c-DBf9qeaYEDIJ^FiioWfKy zDWO@?qhGSvDYLjE=EF4GvkUt*st31!ojdPi0DTcnXh79ZOu%;n{Pu;e*nn~J z2+m`c!8=M=k22t-YoReR+Ks0UfC6?Q+kl#eL2QZynzR%!lc_fTo7?SSJN>2C#TtT!x)Bx7ji*WGe&0 z5!XnQ0F<}=CgZMjhqjUuN{w`#&lgVh1#_w%hE{QfIL181a3puID?Co{i~9*dcbuF< zi`7_OH^hP$OOZ8{(3xO7sctGIEgg$fVLrSB?UP_Z(ybdeIw6z8q49vRWZ&Ms^*5^P zR{sfszr)sL9?q@J;);%w)+d{V`*|bfOMbmMlqG31Il8FV-Yop~h-G&uURL=Do-}X2 zLcA|9X~g%Stw5$4H@1FK4(Uk(}^V z9WH;M6iuAk2xRxSz~$0Gr4;!6=frbta|;V>92_z)L{#Nab79xRABqz1zJ1#cew!h^ zhqSA!D7sQ=YisMp`N0e=p%pH$wXYLz9*d_X2Rc}^R8%&Cl|chrDjwZ@wYgdOaFlGj z@qTx?k5LF(w_9!`lZ*DVvtMdVJO`~PUO}tY#2JVFTr6{D!EP68pfvEr=2TIkn^Trx zBMgQss7;Z4G4dJc9>QPA8c$jq80_w;eUcG0ISt|+1(g4k^I4&15oBLlQsVG1<=*4R zJF$O~IO7S1UOXeUGRI~wiB6=4+l?Qo4gM)yi273e*`&|C({0fgyAr>-^O-w6d2ZPE z^{(Vme~)0q3% zj>k0D?#s}9Lk+hWchIiOt2Zw^O~mdJwgt9YYfzH;jvFeO?damMq^+sRgrIi|UGA1Sx97?nW3Z_x{`ipw8vNI|_*o%O zOE`XaN8@62;oC{pw!OAxBX*7Ro%Oi_+zyyhr4s>$MkI| z`&)jnj2<83z3=y7=Z&8m0yiYpZ#5HDw=_|wTQ9an__($uFY{x=t6!R@Y&SUzZ`%<4 zI5gz$8tqaWu6f`8m1zQo?`cDTmb9=9y@fRHQ+$4qr*CCeFQVSrh#{i$@?u`VTYQ>l z;Mu`&ZSzA7rW-eIJjKAxd2Z}k`zJ8j*J_b&Qk4J81wgEZYRTZ#j?XxnP{XD~*C7d( zR$VK~*q961Ca+=5Qm1pN4#q6FAZJIy0kUOI61M~W7{_M1csI!1WWr`tQ%j5P7&#!0 z!V>BowKEfqrd~#AXf9uAL*Fdwn7L3@g*7tXEJ}bpHCdnwYC5z&9 zUEYlF8r`tyvO64ELYz$pHP+g@nR{MewIMt}u!GW5mE!F7th{IR-ifCSk5=@(Zq~lE zlqqFnpSd;q@#B=@Vu9YkJ!8+d{>dLbsi@C0b8!}V7~HDE(TYk7OntA z_hTvP8aU98ySLY4im;!3_~y-jTR6S}i3kfWNLX_prpPi&@Jy>6$< za$Z_SMuuX-4v4SQ*Q&*XLBdibolGGtF1{02nL|bvzqap#*1yBzJ~r7|)AGBdQ1yI? zTlb_SwYJ{ODB^G!$SBC!UpA*vmf5q#z`~eS=_UK#{XA);4%riFti@^K#evK}UK~oN zNPe{~Oj;^Q#g=Br<2shA2hx`&KS;||D0`O12_`E^+^*P}a>?wd((>a!k8Iz&&!0D- z-}(p$J7fej#C1Qqx8> zS%x1BtgRXIbRG~nZU6o~oSbXG9YioG#?qiofBk+j*D0BlulLTOU?EC*>Z7{61}67lQa-T z@Ov3v=jWHy*Kb5ty#3&Tl$jX^_9KEu7ox>nu3@w92Q+RD+0>K~Yw3ODj9trfU5xQ= zP;c;Cw^P)tE!7pD#Q|zx6Gi7xqS?TJL|9nZ%<<+C*vqp-ANNRhD8MBW6%pd$k!R0S zc^OV>MHyEyjkJMUYTeh+|G%rC9x+neIn^QAn~{>`9Qu%x$J#xTYwo4v{^s%)qcduW zuhl8F?$Nwx@Y#fycklRA&-ZPw&V1+&{LE!;>YMb~!a$Dw5RZr}&D{s5*VL?hFTN60 zI7yj8EpTFk#q!dhmmCMD(JTA5dsB2Gfc8OaMEw`4NT$OE-jzM_cmoJ67a@sm)|j{< zH8pOR7Be&R9n_(n5aKuq+ktuyyyy>@G~u1m-M3JZlPiI*$Nt&ZuU{KL)^HA5taz1& z@@hYPSWNtexHR@MiIHkUvWd<_rCGDnu6jKX=Yj-CtB($e>~3$25|sPqTF zE&Gqc-S-X6?j8l)hYm3!;J!y*P#b}u(|+h(Ttg*!R`A75U*C&ROKX04 zdDCXP4-#L{i{3)6OgbU3Jr;-`uI$e8>gtu=T~OKjfXN;q`gT8iw4=x$|DFwkQvK0r z1=)m!nNV4?^ls0FJ&J6)MFW4z0~}8DA|nN4C3N?Iu(>@taH5DZttp&=g}-i29RGwv zH~(e*npvpFl9RXY-5XQl_gC?%^`eC&|HG)a=ez$T;}QE&g^S_wcfT4s3|3}_R^2e( z7j$rLDZ&eX08Tj@FGBt=EVGA#exCTHlM9T{xRJBsNYwUUxjPIk)ql$+?_ zFD=fEGXWJMMuQHcK(_ATHNV3`!mvB3`Gqk(E>3W|n~TduNYf-LKf5NCx6(5_%z%nV z{>ky3a8-Pdm%L%)MwO@Xr$EQ*bjyIy-4IZ2lHr;}=^tJ6*e;qLyF1TaL$z1Yp$>}4i5GZ7AK6~OF22npyZOV~<+KGSy zbql4CS>xhDI_9yRm@X67ue%Uom+jCYrPv`9D%`r+xw#*4qUl=~7pxh!3%*AQx}KGl zm!GUmh-wn5(ZfCZ3W@d}HBlm)(9=nw1kVvY6-Fj&*FKT>2uYd!vj|DVw>KABDXb!s zx51h91hjyc$MauJv%CS(QdZIHzMo$S8jZ$JXB8EtaARPundYE`md3WPZVzVmXM$7| zZURSq^X3?y`m|}2}yTC&rue3zM9@|ZR_tO*>ie16_6+2k_2<&Mux0%x~v36(v4fTvTt_)SrB_4`}J zN;y8wRo>z40WvF>ER65OFAe<2_?*nHba{ZRI$P(eM;p51zLZt8r1SAV*MQUh>Q$-! z`g%qq*TuQ4vOIjoVpN0sXBVN&BzZtUOI!OA5;CBH>-FNW%Pzxn)tIL`9xK zZ<*!iWyuZ($9yzfx1q2-7{{#ic#xpwF<~C{Sx?^@TCX%{;^fH2e9Wj0{Q&owg)oxf zG(@{@-A%}}e_>82X=%Ceb5;M!@@x@;j#_v~c=#Q(5we0&TRBx$p?34ZN?ut`#5FY5 z$c?)F`RNHOa(O7S>T>|}3}!uC83$cRrwHbw(Oi2_r+ZkEfYSc^)$lMRdEuy-_Q3L5 zzQnXJ);){oVlv;3I93_VHg8STQ2eDjbtf?(u)>>BgG6Ra{fz&#+v$Hct+fm%?oJjx%8@6qG?ofcLiKR)S8B4%h2^Fvlg~@}&T#{%2Gbc~$ z>sw>9^*aQMLRu$b4fqV?2A4B<-c&#|HQi7e()F65U~$fWnvy%^ zz)ifK0@1_2YKmNH9_d=G3+Rv-<{@cLd{N9+ej!*lPIF4*q!#Fp!QHNqbdYjEj4MMU z9P&Hb5@L?V$)!MgP}IN2bDq#;q^B=M{%bT}9~4neM}mN3LvmRO9@rKe2Zu)4SIL9K zfOrmlsP7Z*iFsFU4h~xE?>#j2TP&!5uC$AQ2S7B~7<&000G7iRUwA4GjA7~A0P{Q> z8=G<`5450jFk%cY>_C%`Qs@-^?{qpDN8Wg?6n49!%AZm#UkQpRTgzlcnVCFViWSl+ zHC*e!{;ubLN{HWo8fm?7XeG58@9Es+#(8YU~1`)(h!cn71aR zG;dm7wX13J#6rY=gNyHOX#pt+^bs$h7CSsDwWIy5tWhgM(S9;aX#*ZVX5i-L&Y6Jp z=l;Ax050V}^M3_h>@4<~>xr}uRy^1aK~OD*2s+;>sw8y%FOxG46CF4qEs*Vgo=gVc z!gLBT6IIbeohL^wQG@@LaPEFGkKWs61BHk4{FnjrXuXuVT-pbhj4ap;K(}9LGz|() z%pf2HR_njAWQOO~AqY;G$T1Yp%*-T0hlMre*Aq-*P8|r^15}{H@qC9gPRjhQ@MrY9 z|Gm<{L1fgEt?bfvdMi%)d=+;LQlicosrHcXa6Dx;nUNE}_Gtc>6TPCAOze9Z=B8){ zX#A>FyD5uusAASp$XO-qo%~$au-fas)q}Q6k+J4?7N2LCanG5E!4!+xL*wzOdW$T^ zsy{!CPvDH-=5u-M;^Mk#xLrJ!?QbviqlC@*jLni9i-zEkkS%DeV;samMo5EU-L?v1 zTj%}&mpmoaYR|1xhmzAXAZZ!{kv`F5`i;}8NlMXT@6aOzr*Gp_IX%I11viorn<*=$ z(?s#&G@?@>4)20u2wAO+e?|E)4rLv=!clNUOQCW|uM^9uERgr*5sSBnyZi1S<^*FI z-mtUB<*#odhHd{3WO1-1LXq@}baNMlJ2hpzyZ7Et-dD1OiiYk|MIZD@xa4!B*GG!Y zQH78B%XITT_uScpx@!M{kayqLq^)m$d#z4qFW0_gr>#$ZNn3Ynci%_=(`D_#ZPRleHagzJc3$_plw)aQgLnRr8rc{iTZs!m5to*gXE3l3z$z17v4+Y_#>DC7Bo*SPj#05EKb~1OrG_rU~FHUA6R$T;SeS<%8jSke?I(vMQoPjQaQ?8-yFE6 zP_y|P%}?DALb@By?Kzh<9Z92dd#0N!vyglJp_ykiMp03gX_=myY{8rfu3RArysd7& z_j`qX0mI{q?vRCrMTi>#P*)PPvTj#@R`JG4&f8#vzpJn3>kvTP0QV`!4iv&Thhb1h z=fKE(nOqwMWmeUnQ{C5;9X;^06--Tw_7BX9!b`N<6;-N0x`Hm27mhT?sd+@gY_6M} z4~LESWo3rg6k!5A-AHvNV9%*c+*jS;Bvpi6&ryNx+qZ)!mgJt1eDf-B@wCDEMra9- zE&j5PA0+m4wGaNv$_-lm_8pJ}~^nOG+)J&k9%7xiXUu1;n;1lpB2&iyF3ZmgJT<(?0J! zlj@Oscz(9Zc}%6$%k59G6z+qXAjA#v8V?C_4D|x|<qE3DnC8Fu2QF(qX)sLecns;BOOMqhbyLu`a~`4fLt(#51PC|o{mQ- z$hRYqtLH}t2Kt~7jRlBb4j+vC3}kW5Y!e3DS%-58ieQ@mEFhyMT8*e0GOBPkXgM`i zX2Uq+pz47lsU9b0S0X3)CXepNuU_!(FI?7h`l z%biuiXAxpsa;?3+Wa4&WfCc}?M4{6{Eq55bAI0WZ9EiPSdhnwu#d#ZRMRv7=duH}* zS;!DS6Y0xtBQ_C^%lrH5QdnT%Gdq7#1-;~iC$26o{b??rnwrk{e+53@RLKNE|H}Sy zX@6GV+*~0DaAZLS7_H*eH)lB&MF8FOD= z0b@sYnHlt~BXMx|(S?(#00cN=944}}sxl}v+d5J}&kxlhn^M_$>VJIWn0WNFW>_;x z{`Bd6H~%g=l7a(Q4KY!irmXUbaMSpUM#*VvO)d3CHicgd#+39UVQ zPxA11r{DFF^E@%;uv@nEr5&j_J*&7c+xxne^}T&vxavN>1s-+QO(JndTu(m5Bn|1T zE?e|m{Y~QXO_un_H-2Kj7GKOq&ok(GyDI1*9G`^ZP6o5@ruWn{ z<+ro>(4nl8`fyE8A9z}bC3T~;eL5a7L6n`ezvpx777aAe{ZV0rdWlcxV^od+PY4Cx~`vcZomr>?EUIwuSohee;IZ=M~~cVU)Fwn3#YJn={kf)AIwoFkz2* zegv@9c{=ORB7>W<_Mq0w6F{lYC982>IVpc$6Qzw+`c$dubc+Lb6DhT-ziU8cde#UP z@Sm>W%HO1oef{(6I=@&AcUbE>A6T>bYOM-i=FF6M>be4Uo(6DI1Xnf&j#L&%UsD-;3IyAK4xz`4bc_E)k%f>Y8Su{Rw9_OzNdly6E5Cm*x^ zsrQU{)dbi=(QBtgfeU<_L%J6|KvTPRs^$^2q4c;lZ~Wn0?k7pe)g4ZaA}dSc473G-f{3%bKgC~{BP*c@(cZFSHL8Tm=( zx43-y4iq61r#;WBUOCG5UOZSy4q8dw9R!<@e0Hab+ERONZttlmqEh%f2w4d^Z5>)t zw`+1 zs?i!Lt2^Hhav7xR8-H)fy3;@BZqKBCt9?tf!k?0tM@>O}dTdOYn;nYqr$s~wZrx{3 z)OR}h4r|b(Z?;>;)Ptyf_{|$>;XP1_fth@d+jBqO?cNGM-Qqq?PtQ+VR5*IbM>YNQ z;=VKua3op4=UZFbPN=&|wY)H%Rt~Y!Ep-1?KnBS^{YBR7!Sf0!5n{^Ec26vbwj0wi z6kol%$P5T5Q1o{M`nMu4<37ar+U>6TMGG8pk zF+{sqqpQrXZi`${y<+fDX7|q|fEij{-_%Z?aCCZX!w@M0A%%r^D2YHFJgC`R4J(2v06z}(pw zdWDuRe8h?@^nCDaQ=^&(fA7{ZYJ%R75`|@KqVvELnpO@R`6)#48m+Q|AY#+NQ#M@i5Zzm7BN|1Z*Vh6K_Y9oWJXD{}<=l5?WlCpXeFO0TI3s^ZCfnk$sw z$jNXv+&2@+Bh4X-{=FW>#$C6o-oDy$TZGzu2j%9YOLuneQvkc<#qxCK;@nQ$m%G(b zV$XhE|Dsd;<($Ij#A|o|WS-#ED}8hhyzD|Wfs{=FGadX{HKkRNXV2*nRtloej=qiB*um=3r_dtKXW5B+T9QCMSIwXvJ zDcmv7cYFVW9C)7ay{nES})aA8#a)N-|b|YV;}3K z?W{O&o0p+a(x#>?Wu&sRu+1|H_S4ihG+Z!eYJDm836-#I$Ft)J28;8Q~I>Qw9OU?Vj=>UQy>A~`HM1Bk(yUIA3vgNth~ z*#c8v3ol*cu4!$QKOf;G>4V<4|21D5=Coy4s&04F4O&wSMC+lB*Z2?LGRMoO%qcSu zFx2Gln=Z(F@dD$C6xI|1OVRzS4(o+tYf9q94TAeBzn7QUu@5a(cSd+_`v9pyRygj-Y}u*xcBjH zke| zn`{RfIq~>dOg}}PR8e_Y77nPX?`sY>ug+@{BO~KZwJQ;gd4*X1GTF!&MNG7G$kO&! z7cY~JW2Q&=YJ6VR-`c7JKOtre0GlovN4Q|hkLF|yV~@D_cw(vpnWz)sql5^C;wWvQ z^Zijk7Pw5})h~Se8<+Tc;j1e~Tdc>`mc4Z@xoBQ%oQ;9DXh4OLYwArDz7ARcmrrx= zl;YO)UJSSIk~Z#o>vGWD{vBWBeJa0DPUkB|YKEH{jucbX0Manw6Ni-}qz4ldCH0HCPY)c+PfiPKo`{v%Ein zZ9X_4z#GuN+{pOEgo>N_vt$nx7^-gsRgEkxfc5In&CgSk-~>*LmUc*Z?!bazF~HUU zL}qn$9i1J=m**}Gbrk7`?T_4y^rNGrvya?D;wi&isSZMvpr~kd5o?BwnDv`sF@LV4 zaq7nhdSa{!(XnTY zj98{;`nakS^M*a>wEOdurOa{8=XV|F`_m2)UBvCRqu*UR!?qTidl`&6cQ(cd6{-Aq zSvzG$JEycsgN@nuW%Z7=`cCJ}CPyRoFpORD7tPGfTo05qZc~oiof`U%Rbs;Q-AAXd zReyUw)0AoJd@0!BVRU+IQV9EKOk2z*P0z)3d@t;M|Dn(Jmjdt%2npGr_Z;EKycgh- zqTLc0N9LyCRN?XjtKr@*3D#Tdc9szM2C%-DmMto2v%657;6#454M`}CO3wf{NR}|5 zKiwGcON82x}vDt?}ndqmP`QO+*6#gD$?stIe)MsMN)rWAe^X4irk>2j^KK>46f;SBhCK=BwfFGN4 zp?BSwNI?RnJ=l_`$Za-V?|`j@>lE!D{zHYE1=>Gga5P{h-6KfLAk+gxe(f@O0LZ~A zC8b)gAp!}7wOd9JJ4I0nas~_e%hQuo@fP6Jlvg*l^`-!<17fz zx0mnyH2@W6{B*k}`w*|7|5{$raVo8WUUCCU<#mXvO@i_@J)}3^|lKuI)xwc}9>fpR1O4``lH(U}x zHcYtx*TZG%zf;U@tMHgaq7fuT2HkkcbB{LvhAF3EbTDr=DRegDmW0HWo5|NAQN^z< zE1~RLIHsHy^tw7ux;WJ5L^p+PxX~0*^I;qaw!B+12Vv{wZC@bt#H;%elLL z;|qaA5_kt=ZvBvj;|oJa(^x`5aG=Z6NhhFUCWJbc-iU16?z8EbTuCa0Fi8MZ2hb^R z@*?fYlPBHt_&dj|Gax2D%eFjKUR70!Bx-}%V!WFXA2TFO5hLHsej&&u7(;S-i~=wo z$4)$Ll7IxjxlgmTAK;`*iE`>B+J*fc`f)NFR;^x5jFY^ILiI~uylSvJuaMF7b2JaJ zreZobD2jm-GhVQGRPuS7P7r~8^zW!BW%6RKdSlLe(}(XCT?cqs-?|^%ca}H1_(Rf_ zx;#bBa-*%1e0Of&yV*+Jw?K2);LU6KGrU0aYz!tMr8--8*tQr=B{+^>)8J(Pp4Ty2 zbpJY8B>qn&eoq>0(DAuWDkBp)i5qoj>#)k!G_V#I)rg;e;7Jo3*+dm+OI4FTeBVdRi=i& z33Uk2)6<8LYe3o^pBulFW}()Dnf_^I}rYgdk-e`c1oyoId$|*$s1;aet2k{x)K1M)$;}d=8vT~kN*%orm^Xx|E@5dFjq4Q+>-+Tzwc(u zb_jjb$SvHi*?0Z6(x(&tPil7yo~st9fBN=l;nLHD03IY+4Fzc-r4RZvUz}F64qCac zX5Qw+uAR!-O8R#EGMAWJ^)8LhV~18%`FEVWY85@^{s*$+ba8RfeCvD!$Q^-Ohb&N0 zQ5^yMi1Kj@HY^)6^!4qO0FPseulv-#+BdmB9A!$Q>i&e27-@s93IU_fs%O5^BQ@yY zGpz#Zxo7AtlE4qxEN=`oHNz(^!6V#1OVDyU+$ZmAx!Ctq2kJ1=(UqWRZcJASLC?Y_ zC^)k#13OIyU>%^-s^=oeGjimYk4bA~gtDYgpC%f8Ez`5IXV0qUheB63=%~OJ2<|$h z5oB?lycf%UL|;brS6^1TzJ+9|y}2)MYrqA+s(sgmw=7Y5PM)&)c`+v7?GeuqV$9H7 z?s8>41`(5NClcCfY`A`!P@s)vmd&qVk8Q*_tZKnRh~bQ!xyibooqq4TcaonfbKL0t zvm*49ou7X*+=$*|tP&WVK7Z64)i2@SR^Eb9Re+9?jLZp8l*Xs}RrmBJT|%c(UZpzv zj?gj?hN15RZc0`O&wEJJT)Iwnc9I~TIq2O=I_KyCXTKOk@7wMNb9^2*cp)P3|4sb8H$*nHs}!WBWTgD`6Rfd!t!{xgKNsnj4W{bsaj9A$mud{B zl(tLp?(@H0zVEdfNwlU(*Ryid?g{Uai3$$KbXB@1zXnbCK0e^~-{3Igqxj-a)FTla zc?eJ^Pn;kTI{+AFV;c(S4Z%Ih%+B7Vaw{X_5H%w!PaZoc@R;U=L`7>VBNfiUBKusf zm97H@Jj2wW9$Lp>htmuz0R+tgjl|=|FGXHnM#jdRZ4H=_mH%95_wrRKEs^lqa?U2g~rn~&zGf~u+hswxkI`e(U^iYu2Q*@;3+ zfpY$eOT(ge%+0xZnbEDR4?%V|igi9&1#5Rz5RFB1i zXexYl=uxEu1z4r*)XG z`8id?PQI92)nJvN+5?En=I0z0( z8T1Lp=X0LY9I=oY806J^EBy84<=B5-$}X>eu~Pi!&1c}b^i7@^PyS)C=la>I>UYsL zwnEz#%rqGI!cCO2*!S{rA1tF1ctf>Kog#3-N5koZvGj=B%FsrrG$BCd9AT>(YVW1ypzun%-oA3+m65iE9D}E19!r zOOf6|qPYdU<~z8E4>uW|@9!v*fQ9ry%Zbr9V8~`+!v`r*(oWJ4p<^qr&TSC8FBW@K z;1Nl{O_~ntYdN)k{{A1qbR_a1K#pDD%Q$@g{80t&stkQ3=9Z(v~| zP^;?4SV5#-8xW(`SoL#`<5CA=$m^b2=DY40S+>YXDa5B8o3_6p_3v>h80d!~n*vrhHHgLX;y z-Q(N0W#|{b1^sThe*dwSP5UmpQugQap*WKsgJ0vv=0r}n)|`yhI)A!$o)vS++w!6I zE>D++go-{bQSMmO(wR|m1TVuoVi!_TkO5on4a`ZJmt|F_^gUQFoiC{0aG(IOH}8S0_;I4LVu*B(H#rk^~Xj%n?8nEO0}Dlw{O z_zQR=%s$o0vjZ2EAIAoz-gOLYwuy7zqN5 z_)J_v4~+FbbiTVjUL(};)N5rKi@CSL!nT3ceGyX_0N1CbrHQSH=6pwPw3xxx4}yX= zh4Sk90l*meQT6!_c9IL>`QnOQhD??qSe>C>mxqABQtm_+RMsS~7#T6~AkSmM*v z*0zW$0)=>1FZhFr8&V=&tcJG?X8ukjN z{29vVcq6)s6wOxFhGS%JeMhG~m@AsZSFl?z&-Tgh)}HTC%83)F!pd3Z1BGH=H7ccT zJblCWv2?qKU1<-Gkl>M>L03;3=o+wH4F3~NRCo>^+yLGn2B5_?H42AJU!jggX($al zhH(^VIqk%*5RkPlP#Z+k(+z-CuHUqY&0%jUC^rPDoZwh$CWssj8%)7aog?`!lHHe#d^4ZzM=!HIt;cYmj82s1V$tVMTMhh1d z%SA>B|1tD$>p~Qk2Vlcp7_cL$zerC{&#dmLPk=q{65aN{NK7%3ew)1MbHb9snV219 zH77^?#m&3=R_SB%xIy;v#F{Y|;X2ExrzcitUZD-x%+291ub?qnFD&+M+m*L+v^5NO z+#d`yFdCGl4>|{O^>onvd9Euarlz;>YwX2}IC#civ?oWk2^K5_(ulD^L9~VW(C}~; zSb}&0AL`;C1?Q4AVx1i>8ix>A06<4arW}2@xl&;IvC+eO=-Zdw=l~GmL8cvkQso7+I%s9nj5Nv(s zSsrtXizXO|TDA1=?r=;eZ228@HYDv0tNM%%AXTq`#ebJX8MtS}F5&g2uKxZz$Uuhh zU&+kPB@ea$YMsMUp26kINo0Eg5Pj*RB)nL$sOIzR>=9Y0VF}xGlCbAs{(>Cl>$@7n zI$zjNYbhJAV9?Ej)qqp%E%{iG@x$Ufk-X$)o12>raFao+OCOtLSBO}J2o^txN~GSI z&R$NA4%-m(?SnA`5-2F#GVYi=ulC-!U+yUiW;rt91$WW3AO)3NGdex25U6(YY}n)t z7wd^Duc%32!rWsz67%P7W32ms7_p`0pEG}{TG7+GvIsG&D_XJ6NZq#BxbQ;vyyk_8 zue(96OJhATt51rIF`VGdSRLB9+G==1kn{o5d-}#|hx$3hganS#Jh6IvZ!k;tAIf(5 z;sq_O60DA)^(@7S8AG9jTXqR6@edU&=l3DgpvWO2A{5P$IB37saVn;SXv6jyXf(S6LCl-JYLxU`~piu1>XkP@@ zRPy1&8JXzF$n8Y=i{(GMiiTSV=R|pYIcWb_PwiXO$gwD(MU$RsW*KrtW&uj(5_vq= zG16WTIXXBpGQ!dnx(m%YYH)Bj`g;1-Y&yW9`z`Y#6(1kpjp$i*F!Tu;3`*J6_yxXj zbq#j}tp=dY6>otLbLw-?a_`qo?;nATUH# z($|vBj{L-+TZsR6ND2Pw7*G&m6pgZABj4lMVTVdoAjHBcz+pTo zcVS{JY}ZYTLr#ZXNs#0>zgE=N)}9(@qDLoO2BOqqEICk`)~^KfT-Zpk7%|o#1Aj3F z`*c!{9!aq%+^{rMhF69fVW9=59=i93uyMz zQmU*zy?V&NY0H)k%9*LgzGrkC&uz^z(8zq6*lBn&kc+bZw4Xyj`Q|091l6zp^YLEwi zE;>fW*`!;*PKlo2jGn#l4niMR=@*H#>P7`3)4t&J>KyrIVFv{(>6(^vltVvT{mifW^bdu-TYBWOpFE^~yij_Z<4N-S8v`Au zM9q34mgY@{DQa4r%Qa`(yIPVL-aE~c?;mW+Fm@E#VIoLN=<$tZU_2apmEKqntZTgX zWb9mVL94cCapEp~&(e`f2*vWRxzUudsS1_)w6E>Vr&6WqJ8rb_Ym}#5X%| zKnm?S;P^mv#?!rFJHK5-YqQc8yz9S1Lw3uIp`-A!7RCZ+L+nG_o5krG#s5*Md-)P6sH5IfG_9TDJni!#gIZyR+e*E zU3sm~#M1d-0@9!ByzYwCK4=_12j6S}3q{JVuKB342-9)w6ca|nC@a5P(^7DVx8+7w zU?ELSALi4{{z6y2s#)cJdp;C1HPWVy5ddCM6EhhYV;sUqA{wr;!O+zi1v6hSWDr`M zoC`;n|`&=QQ3mxm<7R$8PSxq|_ z-!+$lviXYi70xlJbj;uoZyOv&j>wPOazQJ|$!Cn3rrl+XdC`g~UrmtS^%TQ@Zspq{>Yaz47>W+};u7w0VM9Y{wHqjLA*h*?q zDpHij>9-C`G%5wGJ=y-2qT;k~)B0-Gb9AVfzc+7noN+I=`6nV4G)ggzb}5^g zU(R%$HYXxoxdoflJ!LeFi>(_-q@UaVv6R7MS&{j+$9M!eSAN-+^A-tKX+5gEpeuh!z!BHXgxqT9O}=!oOUA?i@@( zl91I|j+)#f6ssSLxv0Pji%69wpQ4h!Sr_RNEKD@1E4|@odGq4RFLodnwal!1UjY~q z3|#4IS=Z{-t6hKGVPE`mYbT5y)6gDocDaJr=-KjOE$PJJ|I$e3u9lA;$Mj<#haWdc zDfpQE(xi3`+l9y5_nEynX1EVG0y&P4a|DNl&Gy;@T}cDW#|+iKY4@BxNf?T<7(N;Xl8KeegSz>R)&-Bcr(LI^ z?6}1x4Mku+X5>r151ziv<^M^w(rzqV3&|5X0cH~KpdCG(z+ywkJtKxeb*1ZX8iN`x zGFMQM<~YO@^XD1*V=bypGnUj|@FcCoHLToys*#Qt+85Z*W6j0Gfdd4z0EOh0|FkLRZXKd37XKK{Dkd48b9HnL zLu9_zF@NJpO0%osYvAJNvCbirJkUD1EqDy~s$%YBo7?tT=;zUEN0Af8|ja3}iX+hBGKIWKkG z`-jFCw6KZ5Tnp*S&>ue*SM<8DHoU0Upoq~si@2-9E#Wea#{lCJ*udm2b&Xnf60p6j(*lreV? z`Q>TQ*ioouZ8WFxkk?x8%roBSfjlH{2E*jDPD{IMcCw`{Ra?&VjK-C2kAGigV!uH- z{qp0uT|ztRhZt@l3k$p5O)k69|Fv;nSIh5XK|0KaGg~V*d5`FN0F_&SQVQ}~z{KR_ z7I2xMuMi&>$FXP6v+_x7)f2tLQmX(YYQ_J1|IHRF*7X{*XK#5OYR`LZbkmEfxMIk? zro+8iM*Z;|t$54xJH#(}-|%6aMf=12<9n9)6}6TE^M=UZWF6ngihq;~iHxW^Q*0y3 zqp+h{j!i;8)|$+EI9g(2QXpSgL{WB2>3!3GPQi|<7mZjzfD2*%OKqHN4uJ>%H4Mt@ zT*Up#MV@XQ{3vJb$h$n2vCp?GVwAq@;8)kvzkKzc*hifA|MDhRKkkuDm`^&1lJP<$Rq7j&P%blJs#Vlb@vth>_OK}N{phCUuj^0!+y>F7_ zgaZ}*nQI-WNn>xyG-Pu`WvV(Jdb*yQ=w67v5OC1L?mE9w-sbR5H&#j&^EBc3FMg^S z3FjSpX-sHJ*blYE|2*bz@wH%h^Oi~mnLn=(e=5&pQv6$I8_2hnW;fb?lW^a)9KuB6 zEiKgdQf|}NGBBE(t$H`?cq))TM%UlIT*S%V z(Pgh5(x;r0{I2LIR1re=x6Ng3zR;r6qpcgCu`75YyT*8L=h{&{{n{z(gx9pWpIckD zuj@}|RPS4urs*Dc{`blgKd#W=fBl2O=?0G{mCq#q{4`W%PgBK?u6%NGN@k;p^rCpW zn520&zw20%r_w1Oy~|At^+JrYder>aLyRxv=ja|h=p1*KMdQ9;gt$|~#kSec83QZx zhF8P_toZ-a)92v)uZ%fvzqyBt*CMi|t~tVFvNO9Y+(qlf(xbrC!h?EV@};S&1iE|$t`>%|Hj{#x%N+BAU>Ag z-T$6qZ4BSl^6vt#moy$eJQi7Vz1FkER^FGjL+H@)mgiY|Zwupj?hY4`lt&yrt1a8D zpFFBLb;8d-_37-WWo%;I`mPq~qZ3ngFFWqRg!kXC4~UNkV%wY5nGh$IgBq@0nPhldY5$3cKaq^xFJo&%M6X z?T3>0JTDzmIHNu+ny$ApFN38?{))=KcF|NX5SYoxjebPiVYTUcru?M?6!~+&M2iq4TK!$CPbe&6fMP8-LcF z3KKZ|a5ahc#1$G@MxHROb^Kv@RuNM__4j3vbq-LfCsrjnS-p`tXz`w<*3+;|H0^6h z!dpuJam)YxxK2w+IXJKX`8v_bJx&@szbQUAazDFQI`3WeQIYiP{e{*}S4DXWY_8A? zq_AFk%1t^^oUEyh${=ZF-(?k={;|#U-dAHQftSb`!Xv~uN!yp*q<#kRr0FIRKA*M0XK{NL}BxouSD-(SaFJ%*xl z!}j>bZ%{Xm<+G=s`nouLyw@RhTgHXbV@dxXRaXHO<+gOF$Zdp*Ihx|OsOrEXuC)bU zmkN7CAKli@b07$sRYbD{g9R#84vwT~553BGXtwTSN*t>y3~&nZ5_Jhg#^xDR4<%Gk zfW9msL`6Nwwo8WkRQ@BKzdDuxlS)XW7 z>nsli%Z))^lX>>U<2s|}^Y+9EPhbO%2buX{v-U4IC{{}=Go?Xu1MXqiUWd>`+#`x3 zy^<>rALog#2~%{{GRFuN+trB5raoj-^cpebb6(sWb22^Q;6ORgp&_*#m)V}nEMgjO z&4Ydvj1%%DVx_+*%sBw)ZG6HvmcM$-t*sR4gCgc;3?Ne{!3-dl{g+FmGlZm-dBb# zVwKajRj8~~c@?{iKIIFAZvKdVSiML&O}pNXv+2Nh1|%v9KMm49PXWLl{WAosfwtWS z<`41}!>g1fc57lQysz8cn;*RZDHAMOB}!bws&S4??pH(%j6@=t_fS8>l)syR|3jjMY7w~wGe30c{OD(4 zeA1xaSN80~djLhB&9rXF&gk#-|KfUQE^y`ffbgdSM4X*bB#sVW#X>rn&GwRCvDTKh zW0l5v{ti}glj%|xpYt9_^Ax-s-YZ5}NpM$sH}bAwmZmY|i~txD5Vv13u36bTmo2?! zn6~!|t(p_;p1|tOg_20wr4fqAvCe}u|Aw9EM-xREBx!`Z_T8TRi^N?TRfk@y4({Hh z$8U4^NPRp|K&r`EfmE?O9~~G`Avf6`LdTF_k3VP1l(Q?&M^J&nOH99NqIR1H7u2I{}Psp`4#hMb_C$5GC~|i^tgR}&!9<7vGRhK z?Blm@K)wYH&LgNMsIkP0c_TZ3sEZbO3nOp70R)g(X^~o`7#gR{3+`VcuF%{BZ@m8MCpJ~W7o-MZX=*UXk2p~l zi8{15Y*5l)08{|En+Efob z0cRnE>+NTNb##K>!vBN_xwHHvP}JP!Yk2iy{G?{fD4t;GuRwA_C!;2(c zeT_Ue>-5l)h8o+c;A2&+;FOS|eIh~ULV+W_2tENf;oYShJeiKN{*g^UF+Tlz0cUkP z6g_bDu^Ca44JfIeOH?BmEz7+h4*g_ZN=M(djA5nXAD0s@_Sh*w)ph$_%rB0+kf)Kh z)mT;dI5;%CysDFvqd3SrE}m-r0!--IbuA=>&;zHmpZS{y-%O*)O(SRKlEUS;-U<%9 z06xjyHUD`?#DTz(DkTpx*NZm14e<#6oS{uc4QP|yCx*>eTBaU{eDcs&4qshTQ$iKNr zE9{HdbEo}eujQ1T7!m$_=>C#)*{*XA+{6X$2|mmqhd`Ka|1*u9T)<1OJ7lcAIPLc;*h1T0_&g?DfXtrG zK#qrW@UXbHr9Nw6Z_3&!ovTB!{8wWRViek+3*CqIMXzNWSyVTX>B^jesjQ;Ld&Yf0 zc82OHe-0Elm1F^#a9SmwSsZdR5|%d|_=aoTYbrI?xa0A0aVgvWQ2hcr<&C0+oGo~6 z>MPGxw|#%TfsqoOCKmMRBPlwr*SqM8L{NRH@2D zdM7s?8riViB3vuxj|l^4V{tXmcG@oL^jjk_dTCbMk81}`9d5`}Ztu_Y>mKN6XyC9g zrvIWfO$fMvu?TR`=uRE?aB*jRk&FlF1@L_EZN^}PXe~%6(>}6qYOSZrFJ&>Kq+jT_ z+Z*@pIscK7fgXe1BDvx>&Lwcb&pnbn5LYLS&}~rkDUKI!E{X1X`Sde}{Za;f^t+Y$ zIH!e!@TM)S_*PiHw9*ogpFc=;Wn_Wu@DV6`r?*koz@>Je_i=74^DpSOqi0}{S5b)q zEf|TQJ#a`8E!vffGy_U=dSq^gr<6F;v-5L&SY=<_yO9c9jA7Pf zJW(Ih-Z`*06wU6sEf8-7XpZsZ_Y7@5lXMV>3v4DY&7A8AG%qwlo8xeRwnxvMGy0PU z-lEkaU=CKe!ONcsloS+Zmk1{`^nf5W21wU7pN=6F#1$a9MNL(9pj1bW~a%eh~Jf7r3(3WO%)0vmW}>Ayo=PxJ~LCXCE%M+*yko%p#D z^W;cv80akfM2=<=NMO5^GuY|rnCeXdR)&}ahtly^D>+qF+2|&hjW%MZaM+7|XYbHU zQX?3zs^%ljqhcJ*J$hcKin#`&H=P%kje#!@(I_=XoW@bKccqk3Bcos!|$oy4TSSl5D!6grku9e?bGnP(r(3_zd*26A1f~p0++d)=qby7`5k=Q-0)ks z+QErs1`FJT=}MHIGSTnC#M!|4q*Pc^z}y_31EQ&ZrTk#KQM|34H4Y10Ujq6JXhCa9 z(a2vrni@4Lr31$_51T?D7K#`6=V?COFWR9pRRhsvY4NJ~5ZUYEW~)AG{r9E1e*41? z{dKoZWR+1z^0)6m?mQsc33n1S7uby$fD-PC#}%4)JhRADrd2~m5{_c};ozDn(bUzr z%I6w+LyQgJo)O=MNf~h5u~02?3aw$_ye{NHEe{`#P7r}ue@R`}(Fs=U88`_t!&daG z@d?vKU2!5|_$mgmgp-k9Yr=ut z4yUDlKY7l&xWsf#`*@iuY6HW`aPr$%P$A+NXTxKs^=5!K;aX>`!t8)H#QfuWvo~4& z+?#OqtFZ`50a}djR0_BSOWQ5#{rNrzkS);w$wESHf)EkPJ=lj(De?~euKRRV<5D~& zV?Y=xjWjL*hbWB4nft%Qs7!t>m9y?5_^rR0sKj<%#hqmr2<$ov(%bH8X*EFbN2X#2`Q5bpp zpa1~&M7`$UJ|QtR$#@L5H{jb2aWsg5(56WX8UXT9$K&_el(t7Ezu?7vJb}9KGV2zlRmu+ENMywlX(m zRTc`)Ndn!~^h``r;6+;~xa0;rI6#-5gTpZtKy?{3bn7WA8kSy#)Lxs)GeiDw@Z8B3 zFGBf-GEwjjWM5I0HW7d6nvGOWP>IeAe>Aq~T{LmcuuiajhE&D=z<6J^Cx}Ui8@7ob($b*D`G(D37wRZL9mTN8b zzBeiV?wBySa*lD6kwru~vOq~w7^SXb2iX&Rf+Yd4+sUS?+>71iihFwn#C((P1@g*w457L-gV`|igUMQ8M8>yb;XJpwn{(PxYxsq-Qxa_lM zLhv7tsKQ#jXD|p+OVypjU4-qAxO5Ws6vr|6fkk^fko{g_(-tB7R_?T)zf9y{S)bOm z#(gR26(F#yp5%v(m$NH$WHk@U>h#vhm9JFIL={ecMFOC+XPxX4NeoWwgKNDWt-O&r zDg-1dp`bZ`X4^?IfHnHCWL)A^j&4w-L`gM5U#NcB12aD;HS2%8uyo^C6t{2F8YdeCaMVkN^!$0iW3&YlUfe-^htX=yk$K*_rl$TEU1 zKD~QPZ96cHJM7FiGM7CrnMD9tIuFQ6Cj5N!;Z4~K;7Nn8>tgT9yEf@)+|yhe(4NV)AH_YjWiFd7;^(b4a` zR>t+c7+8W;%IdOAGqTun^~ar3n+BYWu{$k>T`aTi8#to8?j<#tt(8QUlTiYD_tbwU zWisxA^Z{U&ZD-T(pqU^a=`hZo<+=;f^J<7BJoG4=Uaf$^x+>uXlDQna&hbOR?-ne& zR3qgh+CyX_op9g6TfFM@A%-d=`>L^f)fDea-g^%jawfIBu|Ab8VY`wXVHN#2Cx6X! zM2yRb(fL4-T82vrep}X1+$_wsuy#%OIcvtVY~6IMzG&3>t1}auOgjMp>(vK4FQ1^^0=(E0ND$2o5BO@)BKP~?bJxG%;gf@N3cG*4} zkRG;SQP;>D2q(JOwsnll6oY}!JD9p=dd^tWC>I~6?Pr-PY!?<^{BG%WycLt_*94Z* zUKylLe7aLApPbXTi;FDMv`uvN*q4j>X*`MWwQ88LnO{^Ci(*L#i(7!Vm+*iSjAUEC zk!|-ZcZhdwOco=vi~k;foy#El@|jdiSHB4}drhYr^A9a}_E_GApjl9J?b{O75!fa_ z$X2!b_vj4Q?`4Pywk&XjaNGMM4sWw6(?pn=DoK3N92aFu(~~#>+)&jM^Ju2{e9=QG z-4WR{4+REnyksx0`W@ZFgor2x<+{mP<#YGLL2-9`4`C}@;A5YcCqYa>&;qQ1{_2OG#^kk+ zUin8SC+h!+Fi8nsBb7c3A#?@YC2S01Zm-g;T*zu2Qr%fG)->QxLFdVYbmtw~>NtRC zrdt#uX}7Tnwln z^mr6*>Y?USxZ1`eghdP+Ua=l0jFuk<4-@t0#O1IHXq2c%1ZbwicjJqSF)zmJ47~Iy zc>9!tkYzM>_zkAPxG7};1GYRshGPRFx4`s**c#^!Xn$ zzn;5(s{|(6Mca*w?cRUX;TsmB`A(JOVg#Ike@3{*-6)7%53w+etl0SKws-thnvjWZ z`X}DfJ8}(m4zTy8QQw{7ySUk>>TRt@RFLr#f}cGgNTKv&=#_LeVvM|JR$1TrbuJf4 zxCUXjI5U>$>zR495}4T8{uPikgWiUJ#)4d~#sLRVblJQXPgJMoOg6Zw>DXSFk4I&m z)m>|^NtjS)6i_?Ok9W3|^p|hsX!flYHzEUd zj_vu1ARh?-aU+}7pWS^hYTeik8XoSKi>^c|!r1L~4cK#uOjBt=VU({UH*8gtuCbpj z+S%xIL9#ZoxgBiXf$^Gf`NG=1NuH9^d?7pNeH3@CIq@ji8kD^VnObQ7tV+B9h06=0_M~X{MY#0b z5~VQFA|Pw`+9$utnmvh+j;CaFRUnF{SAGJTmc6@Hhf zSaXo}xRM=bc23P24}az_fnE6in^gZ`0UDY*i;sSi1t<9{7CxkV(@Ht;2#r7fK4Hl? z_>&xiAg5R#qHIX{7PT`|GayFD&fq8NC!5m9rd;6bjb(>qfIq7J_Ur0Gsx*w z$%AFZj0auSJU1Oc2WUjDc}B#I6q<~rs+u`LP*6XpJ}7h>a~3L1--Ju09L|6I6jU~xmfMO2=8$EP099Fq$Ny0gT7KOG83Tnq4be~$J5hYBlDvMz zvmW{kWZhcX5IKQD1_@6l$$p(G;vo&=9Uq}`vz~i;Pp+O{*9(zhxD=$L;#X?d-E_pW z_&@O&x7guWCq>9u%9#k0_U}9Ltw;xiDl#|oSb0Pz79q$y_C)=2j-E7zd1BEfKWHjS zseI)OUJN4uOh@&PysBZ!<{=dWfM1Px7H@3Ft%r=O{ZJor^e*YY@GLY~mpshoyAid8 z5R{(5tA_j0lx-H?kt?@OXVP*+Tsrr3Wq2D!6j{1~rmt5xjX@`kQ_wiZf9aeq_C|ZW zxBiiC7b8%WR#oC(rPfd}08}Z}GYv7CExGvEEzyodhwH*UPpDlE_;ikzkAL+0qG#`j zn@Dra_)dvlxOv&b+u_58yWbh&J1b%_6+T-KF9JXniq;m)L~LpvP#iB-Q)zi%FFbL7 z^dTm{jWQ~KZ(hdz@Ty`EQ5EMb(Tm<1L;(hRD!xcT_JT&-brkbjS zWaaY69K<KUZM6ls&|;p#HJkV(&d1LOflqYX1~8 za?D#xeW41&umO?~kL{&Y7gYXR?DXvyTeFD}AbgOsFW)L&SW0?DrRpb5m6M!t2jOq! zha7Ml{jEf~^0@{Dr^7UolKxA7z;>xd4_XBtO4f*MPLC*&v-MXmKLCjAF2??}5=qCe zZQ3+NsD*k&lx{lUPGlDA-$F-f1o&^N)uhQkY^qjK)fZ!34bzYc!mD9$ z3Gdlb zpv+%mlbwvUYLYc0ZKq`A;Cw3+0uI{WU z&vNfRt-E0sr+JkqOsCRQb?ZEbDA1=hV^eor>=PSy-65wWn z)4=7@4mL^#hHV)n0^(0JcHJw*RWV}=s{Y;{j8w9x%Jr8?Qc_IFj$U(LXl@jZa=0t| zhwhRFLV;N63_{~{fTZqNFi4aeM)jq{yRsJqib+t3=amFuniu3@wtCY&PCQu8^nG`(VP@{(G~ON2xb%zJms!jeN$qO+ZwAtK(G}3c2+^QhJJUBZ0E9K= zd9xXy2Udv#`b`HxwtJK7A#MtBs;IpSJ$uz~HIK3gbbvX0CpVan^l&jj?H%Y1lsFld zw6{w)b{Qvb%=@NJBk3CfGnm-N4rzDko@TmFf}4rL<4?{7{f^%A1gduvLLVNJ$uhI zJ(QkW6o1T6ljJI2TLD|XsigW?W;w@w(E$+&d&7f8*OGn)(8XfAZ^k(0CJ)D0OR?Z2 zdw*eMGw5q>XB+c0VM7n{<1IsxXUc-R>IE?=4hy)U@c$wa4k@!J=={3-2iQa-kOy3)>-FgL9=Fj)6Px5 zIu|2k)x-4&0sjFBHO4iTh$RaHNfhWN`TTw1`lGe&V5*XEj;;b~vKgry@w-IsLZ3PO z7oealUox=e1g(+MOdEDTR@A8(O3>pC9MS+r^xso^*=+DMfwl#bPhams#+4OT5qM}L z@KZZOit?lb*ygRiG6X_+qAl(_^=Y4*;UdJ)#=poS#>OFp-&Q8qt3rrPNA!mJc=l(w zQT5gq84@1bwDGouhDXkomYE(7E{fLgzyXw|f|Gj@X*?$Y|B=-G!vK+Qgtkth>eMC5n8 ztn3-?N^zGD<2X{~sg~GuGR^(;wEq#U;unNb3Q3oGVp{II<EjgN3^OV?`~@b$0CbDfl;s?MB?kr!r(|DdWS^&u<$1v9rmV8#Q^mfU7oLg; z1HKhHZf4GSwXzfAo{izL!wO$GG?$raU7{n;Z6pu*A1E8c1j>TJ+dNsI_eay{0%57q zfIGPVTl~`m8iud4g48*YDwWpZa%dS^($ZfkKv0Hx#^>%h?(G&(g|RPYQt3y5EN&0Z zAn`euO8w+R-}kr)B${=P z1djxq*Do?Yd`5ux7a!c>zm*a+?#vurZKyhT`qt&?Nm6j6vwlfT{M3&xjDp)x_J{U-oBl=SySODQCaM5=J4` zQ}cU{?;SU!>GZ0id+?x!bUdc1Z-b@%vtH6qD^R064ZG{ouI6{-6iueKhlm~B4$4yy zVQG>F^iD1DWsTd z?XZ52w}o&`hMUj^?wfF34X|QGeMK%7Y;!ZP4AqK=I!$Roc>%ygAw=Z9Ervtzzk5j=0@8fHUN%JYRmZg`yiIb(6826YFw(M^Dr`3J+n z=Z*?2t78dk+MIO%vZnNg;37-uV2TB};rNZ*D9mJY&yt3RjE<<`?ML)3I~JP<8N=Y1 zJGP97j=p%3j(tzn5IjuEoZTdKZ8uiV*oA2N^lTd~^>c|*ia2GWik^Kt@jD**!wb*0 zXW>TRO1qc%RE%r1j|XplGuDOra#xxALFB+}8)=d;Zy#DBt_+r4A3u7W?I5^Ob?QdW z;BYOl0$pWC+C@;on9xvrm8+OK;go9m;c^ROrJTQ`a) zM_g6E2F*IJNt_Gx=lbdMv)RZh;CJn4dT@wb4H43GFdnBebF+0*Yp8*g#t(Z228?wB z*<>bMH=Q_AnpieSoci{2S5=UNRFKH5!&fQKtHs@e5gi+@1XCOl=2l}(Wu0qmiF^pJU`7;w)bYcD`^}* zvG^`^Mp|Z;aGCPavRA_!*MUz*N2+7N!-qj%6j^5N$uLo zO7vJZ6!*3sTR4+D%=rv1;@Ekw)nG{mJ5M>Au1^MYaXdkdT+klo$R_@4?G&x%DAeQV z19={-CsCEv#%Z;A(RESMAp>%-;a#8Nsjk!Bc&UJpqGF=xT^@eq@UVKH<5&VJu)a`;> z-p^5>KoH_Vq-oFgpE+!Qp58uMvb@vjf$fGGfaO=cAQ^kmvXo~uGv5$pAs^Ayu2K;) zqq@8Kr+vF!t&o+rD$mst6T+|3H`O$SrSq;?*ROYJ0etRHJM>W z79USc(dXeM9)&kbW&^m1%T@xsO-59MLr=CimnSQm)2!wU`MC|WmQoO*7fRuKIRz6x z_y>F@kJinfeO;Cn@<|M%KYY~>+x}!)+6*-P-G$66QQJP~8t)4{^Ifj^^9z<8b9TI^ zmOc>)Z+OT$*Vf$gLlzKPH&=ft1^!AKT2I0(Zx_G--_N@3gw=vsa7MoUM&;ZBXaNq?`V zn?@Rne>vfS`qjyzpL4Qdvdp}mYhT`VQ8tWN?(#}FOef=tEgjE`&^uZ-ImI1}KP~6% zl2*~YP#gaJ@RBp*34Il^>WRvGZ-hKg?CsLPbN9F+y46W|Hi88!b|7Mu0Uj+EOaarH zWSh5t7_-ITV*b_!-CV(1i`xH`md}+(o?<<~5xji${Gl0FHGP+>J4*u(hqwxyB4a>Hlk>qO-4MGJp>z`+|m7WH~l4^`FKODIdfoElSc`L z!*Qmz**=(Nu|yV%#lh5_%%oDP>>~)(c<>^Q`1gk-M4Jdo&o?f>xxRbNYzTbCNTVlN z_QbbCfj>=3v#%9jM;48rt&$?cDLv^lLh|gZQ9=P~zTUGB(OwD1zpn14t2cFxy?Cid zF}t-J3j+sPU?xiRR{nM03fN;(@99&Y&P~0S$?QGKk|y)ukCu&nuJF`Om?%%}aj3Dd zeX5z$=7FN{M46%Sg6&d8_Q>~mQHq^8(u=Y6EiZ6DFjSZM#l1?{LOSsSu;I>qPskV< zKQA5K;*Y+IsZ^(p55Rz~p$kFGA>U}_HKr5ZKJ$>p7n;S>Ir7vpxIvMmvm(j78_{=% zj`CHxMK~nK6~|HaaBtVlp;jMv<4`ff!;7jf#$B}fXIvBaw@dZ{n8IoigQUgXnMtmX z<4t8aJ+l!-kX{f(6m%ApyPa5$9GKLOm~NNR!9FD^N{icGQFv_IBV^O=+dHgarL$%g z1w#%wv}9*FJ|*YqHawiNePMkHA(z(2FmnT2jx+6!l;h1#N78!C=<9}>V%&|CGmqof zUzV>@g3~JU%swS+g_vtIIqnW6N58uu#i0b!Va#pYqi$ELhL#NDH!^mq- zUcs0uJArb)Ql1n(SDj#^WQ6>Uum9OriVFEJj9MZ0`(ttaKZyIxF%qZ8K5D2gGt$oO zVuv>==*XX2ed3dX$(T8<(V6_cj=mX(1VO|xlYbe>;vN;#L8iq`C%hM2Ns=6FYn>pd zONlw^$vV}r=CNY0Mz&eN8r-9FzRS?Ke^#w$X$B#+Bq^H5iVb{k!S(Ic zfy!Dtyget6S!*k9(A_|CNzYn#Z5AaJ{O!!df=v*MwO0D(ImY*y8>*A0=k|_T=3y&1 z^Dg&o1Q~e}7>+|;t4FVIY?C|gHQ>5b7JUpG*`b84HB0!-Z?)ZWahm##Gpk1lO*`{1 zVxX>mj*DoO-wr`WvpHjS?@fcNAC(2(6oj?K#}O(8AS^!K=voqbCZ+#011X00{hmn! z8}-w#k;k99vQv)v>Ikk@bG8{glx7i#@^Mgq(RE z*@93KE(Gg>?T4;J_odit(L=>G47o%hC-xLWgoY@T$f0MRKm27*SfzsDZ+1gt|DlQc zRcB5ScPiOihb2NSar5v|VtooG=@v7GS;YJt;|;gS$NcC-_P(>O2_v*$gJOT&&a~>O zf5>!yIMDifvHt90Y|PR*hdUDU6znCXZ0tezao_y*+VU9MuAR6`_;zpg!FJ}CWHP~h#+U<^ zqUDIa+nKTjJ-u8>I^e>KeF8T=I}S2tMsbHO*vPJR^WMwR?VY!s#C=iGQp>{nPF$0& z7h&qp{^y!=8Tp~sDvSp+Hd@A-t9415gKeRWkh?jwEjQpka?im9=O_{DRXG;s@+);b z=!<7kRMHxJUn7{v>TyMEAMoD?qXBJjKeWNXKd~j!!wtK&MtvT7?sZ*y{%|Ys(o=yb zMScID;2%adhQWW)5k(^d&WFzCRGw?gZ*F0mdsmFqlSoeFENLyqYmKped;z#JvF;jE zlv8IlrSQ{(tE=3}_=!KeP+0XE?Rdrz93T)!Z1e6?S0`R50KxwoMa(M1qF|X@M#|99 zCAvVEq@N;z4J`4qL>H@E>_k>8R(+9R-N-;)d~@xZbA7OVLM0olC6vNo$GlNh32SbT zR5GMzt;}$Vz;;cf5@1Z(gY(s;OhEs^V?@3@ko%n;Y?@7yK9Ut!7QkZyRc8>44pK)$ z6$i6R`C&tZfyx|!Ii~osVxZ32z;)kN!+L(3M6}K8`bvT_^SfbI+x^fxzU*1e4RgCw zz~HC_Sw2Bkcc_Xq4PR2i4@Yhv6y*Tw4zxY4`Os?hZA0ln@FLr(@`ms? zm(u~ketjCY1yYiCW_`3}WubR~rBu4XSj?PtP=HgEeyR8N)U{Kk!cW=QJ}44z_NdPE z$K+nFZmKW#@WpHz{}ubD5DBDH>J_G|wz(L$lE9WD$WvB`XDpgC_>q3YqXjGhrxfvO zuiv$M&SmdNY>N9d5t7nIpm`_3+stuE?wPUQ ztT)VP%QR;I&Vg5YsZo!dXZ_?)4&OkhPw><#K1%+8wr=*l&#!xXFi?wnX0h*-Cd#!b)KpOI4um8q=~qap6y}y zrOvtZ+0aSf>}S~Kr_+<~*-jRt>fL5s(;NYq&$7ggM`(Qge2b_4XsB=xNkD zGmRBQU2r@#0WR>~*_=(8C|P zZ+Lrp>rtqH@MNER_iC-rbZ=jMvx#XEg<2RdWt%w>y8M2?Z5_5Y!|vPA_1>u?ah>HI z|JC{v3{~7%)_ivL=-G{mTN3-aLnU6j&gL76g(h_n zqE9jLBdpCJQt7~W+hM$K1>h{yZQ!jPz_w(%851DB)clrqz0)e8-QqCFhEH|OR6O)S zvGT6K{z{FTAS;#?QT<75_loX2-rH7aiTU)?rJ`<9DBWqcr~s=zC|P0D{uR6STJf%! zLsztBY*$BK=iChu+liR>Ife={oRj?LKC8!lF7{k>p`y{VwM&BjE7^c_D9$VT;0nck z9B-~Lu_h8skz2K21Ek=j~t_k+@w$cAD0x-a5k2LX&e( zfprh@@D1xVyKJx4!BaCu6QUXY$H%F^@BdEJ?r{=8Ori;oA3ofzEc_-)vEkW#Zf*;L z)}ZO+zsXScq+vaODQ03o0(L0J8MDdO%^|JcBN(8pj8;O6TL>=H*+6ebbgeGo2Umhb z5mTRcX|F8W0WeQq zy9{~$>)pQe4)YDTqwYJCw@s9u7P`bopNHH~w0|TPO5)XM-sm=tGU26MY)YmiC`g}6 z)NE%z_zcWQI7^P~y86xgY{WOU(A17nc2*)$NBFU&@>Z}|p=%$N$F zZxLlkUi*0*?tXOl%@GwyAwuz*HK>6~C%k-g_hj$HigZtl8#)vAc%aNkR|I4&SS*oX zS2JU!bS7H6wDz6z4LM#_3&K9h>NJ0zZ$!AeE{{bg3-yV>uS^!Dh-7_oV=KodA(~qU zhyE5=jZ}N>(r0~KU+ydB@V0#Y&QID+|H~$paQgJknKjl zl$dRKAH5&}iGQ4nV9fD-wiT59oCnkE@A#@=S=`OG=BeVIq#ufn*tRU0~WF8f0gCCm2R zU+n>yHzUYIZCgPZ_^NfBpPRrW{?{<9=26Uj#sn#pK4VO;2lV()tYwLcGqW@~L%v5~ z%z9F)5^@@ogK2#$8pp;rg>H42v!<(~Cj zJht8h(>#3x0X!1xb;n|zopn)|Q`7c7iOY(LncnZ}ADx`J z$YWB(g6~n>4-~jD&qd^OdbJf(m~%Qe9)(x&>C1%(!3ul&WsQjP>=xilQw6UV#`##s zd18{w#iqCN0?kxmPj4`%X3!hX1hPClQ+g6K>-pYt6hYFlPvIDgR5|AuPmDd_0&wE^ zp;li3|7BjDoCXoe=i~L& z`JK_>gd+%_EnT1KRaa(@9rDEEpbRMmJq#oGSCB)e0uGRs>^Kx4PwJfA&q=P?G{emj ztOM2{&U3k2M5krwgx- zEaXKBdP3ZzyFoNbLnf2@%O>IGW6_9{bN{4ZV0I~^(CaQ!R>JD@Hm~y8uhmuuTe-2> zDXOs_l;ldEa$sCRqBn|b6#VE>J0CSp4f;AXk0VL4v^sPLtFN?5XszH362Rfj3Qb25 z$x6}M00i7FLo2Y7i_L7ki#6$?KR}mFYRS*WZj*AAGA|gm zz{8P>*O-%_jyO0~P<*~Y^#;M?;y`_WH1^2knKCOacs&hI%9UUkQ_?nxF2hoT15S*0 zT)MtwzB^I6#xzrh6@mSUg1G@(PI2pJD2%PMEy+IX0L;77##Dvb5#?-JVwuAKsCDQn zR<2?N`Q*Inhb(FcX1Kz-r-8s1y}=~cEoP3pfeQx^9QrjQ#tfy+z8a1Ck+ zvv0w%jNKgp_j{i?>&G7r77D-&Ya-Q+Cq7{(#g`JIt%%frrGHpxW@N4K41^uyFDvye zzMON_wO+w$1D0BjI-VO~Ra6<*-^NIZ;dTjLc#`^y88|9*iEwcF5 zCa&?Pw2EuYgTl2FYH?TPLK}iJ^Zg6H9)mYNNfHKG3rnnn3Eo7v}!g$qqRZpz6CU&)_ zCBMc+F3Ky2AJ(glS2}S4Rxj8fEmv>uq#(uMO@)r&KsA@Iv1UxecC&4w$d*evXP!vI zXm*ML@?S=NGUzUAS8wmOU7yfg_OMV{S4J??(UHH>EM}eE@^&28Vgf&P)rl2u2+j!SWS*tv}8t)c8l{h6k%P$%$mr%Aq(7sP62$ z^g0dww--k5L1iNaE|P~@k&r_0vGz|XFvT|rr%Y@&7_pLw;4Du4cl+mEtPgO+O;hO} z;h_Cy;q;>qT&(@r8SulrUY3eUyhFxb?<#40(dTCBoIgd?j0B_A52?3}q+(yiYo7C# zM%5M<9~4UD4jLu$Y$v+Wr^AV^YhoJkUn^bp ziD&Q;m=hYKL+tKUKXRD4=dePD%w)?G_6<+<2U}D?Z+Ll6&=Ru|WP=fK}m-ok6Diy;ZmDtE#@y z(wC$$w2cFY2dD!G;H!F*UkV7`hXsx2ET%DpoJm9M(?5YW$>cQg*u@7N&6KY-W#-0V zCScva^0}<(^tPeU?(F_wvMU(DY(*@RciNkcKdN@sToWr^@K(_0zUioarRym4!~yym zZCejoH2r84oJpi{8DjyA|j8O0CEnRBpexmI{tV z!IHJj6kDI1Zw?O5W&Va|2FbM&P%VqyB8?YEa=SzgyzGArs7dj(=#amMzj309K{#{$ z@y*w|Z=#859Va0cx-&x6<2LdFk4?~T8{@h)OQE*7mAnFop$jtK+AR5_zUx{)Mw*Tz zv0WNlZ(V^n)7};v1XP!TiNCBZJ~+<+GE^=RB_=GlIR79-h<6HN@f;U7VjaM~M)o7; zF2brkshV)4w+TVchesEKxAvoPa(w&&OFIer+9>3P9TmU$Zh+20`2ub@C--}dGPtDE z>0*LJFP}z@5e=~&$;42Gu_MR;G6H{sz`E7bz76QW$4PPzkrf(*8)HU9Y|!GnGj#!m zdJ#o>++~$f{NP@;y;{w5Z=ML0@L)oy`_NhYU(2fj2uHPDz*Xp;1;Iv64DAKY)v7L^ zTyFHKeY=(}Ah87^nA;T5r;0mT96PbvmFH5bB4a1gg#^?^lCsdEV z*NDhH0H)!vzqMU?#67yx^xTanl@(6*J8s#(sPFo@HZ2feI-3(^iYu!4FU=X^w-~Yy zxW1J~meuwB9yoX>_F8QYeXHP#I1=g7J}lTwSYg>)c>88UpmIkD1dWWl!`bc_;nnD| zU&M^yi>a^8@UY?rBC0577>0{{KcSbd&o|S{k)V6PrQWmxm;{xZQez?-4lKM;^yoe& zl;<3bh-tQ6WZegX75#P5f<80Yo_Q@1Cl52vj4UcChYs#Vw+*G9KzA* zqd->o!LnuHc-ekpUNvDL@+fXtvGuB1WyJBUg~gNsX&LZC>Ya?T#xnBe1C; z$9aF~hvSjSC?ArQ(_q|M=x2y0Wn8?A#(n3!oSsQ^5oIYnk|@^)f6J)Ed^-RVYmf7s z2@O{QheAjSxeEeW$rcC4-Rd}ek#~Y$2M7tkV^v0IP0f8;IUYA%|IN>Gl=hqczLZG~ zQG%I1kKm~yr=FWh-q`Q2J%zv$(H$W z1H08KF*ze~kMjr}Oho3jrPwHY;Ib^iQzW()qYVj15z6(~sOYc9rWO{Y65mJJo4`zG z@C*`^P>Uy`0vXYssEe)Rqk*pk5aHyXNp?JAx%`+pvxs zRkat;BJvlhHca+XjXzlCJDR<9)`dx!9IKdY%<=<(9~#{_VTXY#4*D7>XlE8nedqE|WB4K}nY{c*pnP$>AB<{_95w zTOiWPZ^m9i>%N6pX;S(se_1UGsG1_v?J6Fpun6J!U4BQaw@$7np{TW%t*@}G>%NxU zA4nzy^@5)jKwCjmM@Hba+SIWdWk(B<5M2YW{rHEbWe4+8)4Gl$phWn08noZ*GcX_g z_h&KMQcK0RO9p-3`c>E?$#_nPsW3~7)BZN8IZgw_?8m@>E3c5aFr!th%WFrZKCCxk z`)=Jp{O*-@LiDh(x`A9hw5@_4TB52*8U{%pSNG=WWs_9nYzRwHzI&S6; zwJy*HkP-Xyxvi=Rz`ZYX5%KxB-dYEtceWSRbr-RcTZS36}*!B7fVe4(wO=z%Oc zP$(FBt54K#{5GxaCG)+OcU8%G6w0#lnrrvvFGB*gF_r8G)FE(}G)~S~2Lg1?7469; z{?W&7uQPRAwT~(#{o_kNwHL8)#&w6SA z?kUxTJIxjrgJ}7dN0pg3c0_97t_9MYh{2w7-8S_V&U>g-?}uNvT3pvR&Vn5$z{sN; z6Gr?>@^y_Fm59x|pLa=!EL+xhUa9@?rcTY)@7V+ry8aXpv87etzmAN*5d~B@h)GkU z&vLk{MdW$)Z@BYI#Zsm}?GlV{l#Ic37hDZQ6~tD5frTcL$89yY+@ z8=80PMeMK1S@)X!D7T%ybcOyKy7j`47{1mlzVTfg!=-n_tnx2(Zb$u`; zoE64TOS7x>YX8~zv5?Aj|H`}l(!RKB*OcrxqJL){i*jw5e~l$mGex-rQsLg5TOxJ> zQTF&|`gKkGuT+aYBaQ7+d4}x(lHN(o&#{MZqpiMtYD4%tg*3PAlEZZevF8Kc2namV-W zW=GyPS;1Yan{)R>fuon?Rx8G~v*q%Z&=2^pwzrxd{+KDg=2C9uj8xQRe_P1tLDQ97 z{#5h`vZ41y7Br22l^>~d3a`0f=ZO?8^zG2eh~1lYZbX2|ko8vpi9r;`+g@TR(rNfF z3THkhvi*SG%$nBRA%ERfqGQ?MLr&T$9Y5o%IVwj!`vom3ILl}BFYhEkdMZn@gdTJg z)ZHcK*9%LzmVQe+zTKn)!2KVKeLi~Lzmj1`|3y36#K{hfPNtwJ?6BDj8$Dc=-3bqE zmM14?M3x8=%~F{IkTCdw^ZCOPe1y*PUAWcq2jdS}71~sMj%YClH~Wn7)YM(c85aj8 z`$H<+H?}iP5BD04w~*X2PU=BVp91f9QAuH-uHDBZUGOVj zMd~%B|50__fmHqP|4LB_m88r{nW5}WN%qLjZXjFsrhyj9&X#MBi|idm$hyY0uWT-E z)-^A`_qo*P`#bq3&N=V>jMwv==jA*d^rs#symku8LaG#fx=dwpaYl4e2 z>Ce|R8Rp6AJgv{c=6|1UcC~Nif?|gf=r_to4O^xDkBzTbK~&xvS7S%Bx#y!`D8RBm zC4b+U`wSaoa34lH5*@S3?Cm`BWaO6ED{7 zKC9i=2jU6FhWK#HcZ>zF*-GTQd$RQCESdUQdSpL25}jdTAcXz5A7!hrf_$5Z#^Iii znnc0cfx!7#HKPk}&oO04%w-8?%D0(2Hq*@k>u|_E?vmkeVzEaPc@9k`FLScWgXat( zXbcz!MV`BoW3gp#(Q1ZK3wp3>2|qsjPPFnP5BPdzoynia(exu-^jb zQdFoV)hS%OR;n5bn>YUw5c6zhiW6}^hBaQevkyEm6l*vZM5*@|@a(#$w$;wR~ z=q~Q93XfHK3O74j-}MxZKpJ9P>Bq<1q8%4rg>P@?tPSdFBqGI+nuTvw5FKTsYAnr= zjC0touG&6NVCpI*B8Xc8PQQN@!5+T{yXi$kvG^gcDc<5y;~C-KLS6frS9;jrRtg}R zlWOTkr}nmo5)5}6=ymLdqmjyLKBa*fk_L@)jkG;gWb|U@=YInu@FA{r zqVe2ur#Vi54mr#kyoYk1ZlltN+K#h$LpcSU4%rdaoh>^cE0D`I=*6$*fYe1KLZ6^{{s0gVg@>$&<_LczrcU? z=m^a4#wf1oSYli$_skl8n18&Z#}mnqMnjeq{5Y+{DI1ehNfMV#63X&lu}Gwt)tNf7 zn>8E?iNeviW9k~l-%^?Kre07+Y3dt)E;95>sE(~uHEuVPE1mtG*gn^X4E}p~wfg>N zu62wZ=Pc+!C`f45?gN0s)M(Zx1KI++vJ{LDO`&VlmuACnb$mbpwrh&H_N-edMm)QylD~b@ zo`w=$#M`iwKt&ga6_scfX=dOxP^zVmqNCx#Yfw~W78B-$rx^^cNJ zvt0GoNyKlRHLl~R{f%}YdEN7}Ee!!-Tu>Y-iN~1`+tJA8e+H1h=KBpH+AF9BC1)vu zo{bi81C#W7ya|0{B(qr8S6N@hBKn&-Q~R4y-PV7P=)JP7*qt=Hq($zOgqV)U~GS25-eqlHEu zlR=GJQ#+r|U=@_|njs_jRhi_w=0>gXJzsHxy7b=K^A3=$D8$6xC+um56jrqZA zQuUBE7Uuj$b({I=i9gkF8>wm+qdgZbTcGYjFx?*vR2MoHs#K>|u(%9`nq2tomd!K; z33{8c#?B`i0vZ==cf%4vypgbFtvLUiNt-rS5(6GSp#je?@amUhX#MYR{bKG}dYCB- ztYV)28L#jGUe_^Ig0c@vPL_z@7J62$r~Ee;;HNFEU!FjCinAZ+4fBWP{?~2@kuWIh zn2e-M!Si4u%+WZuBJqju!EL6SgR%eMel5CxsBo6~aOJH5&vr`6(!{NeEm`rM6-7wl z5@aKfvE*wII3bBA7zmHM9$hySUf#K+9ne;AmAK@?`E;gXx2)ON0vnZlJ}VFq9M0l2y&U@eb-YU*#rSlv zQy`luyx(suaMW;rUAYouj4;n`rn<o z`R_4%T_NNQ`;a`;aw!qxtz9E^B?*@i& z` zBEaL}huv@LEH{T5FiwKJzRT(GjavH&jl`IucU5ZGA2D_+08#rdtSJ!i&z;RqD$#tj z^Q6F%+s5F$%@UJxK$Fp{yeveCt-a-lK%g7PVVvyxje$?7JG-glovD;dBTWy_zV&Ym zfA>I`eqvx*MWobAlTnzp0c0hP+b88KC}Icm?xsqQw6z}Jru26${k zB=ymD%?^FX>%Qyvo2R*R)Fl?BC~>5K}zc@1@jw8DAB8$pag-H&L<;oUL2ze{bDQ4vuLBC}1pk6HB`^M4)SwfSS2R8k zFp`U1FRgW743C67$X~O~`0WmOwVr;B2bUET)sEy&w%tDvQA;8>E_REN;r@+UIj+rx zT=LsVOQXC=l6jK@gt(zX*2PW|Q~#2rJHR+7l0QhA0gh<4HPuD5FFi?9osYN9NRoRyPjKi$w@Yy z9OS!+V_!0_L-;fF1tHwj_B%wP6s_@h0}~ zSDle3{(XSR5%fje8bj%$@Xq>~ZK#zUI*ZSD2|;yKC0CJKvgLr*LUqT4SeUY%>M{TC zSe*VJb(6jjim%n^!Vls`I};jtW6|l=4UgM)kG_JFF8EhDNP1d5##+Tl_ci~sFTK+j ztrsTiRL!S%OX_4Ag=G|=uk@}+hj}W7oIS9bN{?$f7N61Y@?>LUtCqH>?6cMV0R1s+ z;5=vF?)D8&r)^{E3l&`d#_;Xkzp^vmI*o2tkda?>mM8a;AN6AnHexqg{rGK&?R_0_ zJ>GzoRuO#P2P%S{XXF&XU`>MK`Kc8APiHYu8FmZ^uH16MYyZt~wR45cgHt?nVtJyfb(e>DHa3sinN*l-wo_ii+{aMeFC zwybZKR@W^XL9+6RL=&13X@5h!+x&*4hH;?%uG3}MebXELZ@L z7$JE4#Pf->(3k`<9*w&)dFwusoDUvD<~^JgXD3KG{>nl3jWK<<0$KBB zpFqNb!H{)ZxAKO&`6m|NTG`7Y0Z}-@M1g`ArvJWp_aE1dFj$d@7QczNi|buMX&B11 z{Jxb$W=vg?mPJQayrGxgDPT7@rv4R+$s2g1{;CCP`$~Q6Ms!nNlxIlJ*4Wf#^!U^dDjm4=)jZe68}EMy|T6Kc+BCh^_qzK z)%PL7&R2RS*Y-tk|Asbs-vxV;Txb`Kd5hCGmrg)^1lNnEzaRGdkI%N9s?R?OwH1fl+dWyS zyEYUU2Hhlm_IJo1f>7NIk<|P~R17kZ2-;_26J_<(RDwp#57B==C z*9iMn6|KGhpC_}A zc>C1;^l^?%B@Gp>OK9D2nk8gzNzhHqS5K4Jz`D}ANh2r&AYGz1j*d92>R;U~ut>az z4Qh|0=j+0HYu<)tm=ZR=+4=cqSV4wfZ13V;zKRVGxsQU?NZY2b^a+7Cp}l0xq6?of z+`T;}Ha%jTI0K{w*o-CHb=#g>t2&jt$nx=J4-mfmbi(V2nQ=o(%1Xn>U=l{%6Jj{@tUV^!O2oo_p`Nz^P zZ|)X;KD(55tmFkf1=?TC%dSHj%YV>9QQWoMa5K<_;(4OJgumY!+1f zEZ31=aV@QqMv=Ty!G|&IF;9UYUv~VPuCqR_2RFc`XDXh4mVQH`pHUu_XOB-F_7dp- zZauUHsOYTLq|eTow-tA%G?mTzfWx! z15bRiwB+HCwz=^u6ZHerC4`-4pWfjVf(C>b< zv$(IsZ+TBnY4?|&hqPw&a%u73m5pgSRZr*%n0=G0tT585y~m-hW?Pcw!)0bK8w|z2 zLRC_w1q8Q5vRcxRq(Xx|JYs26NsOTpaolF~QKf!YZ9j8SPb+0m#{1<}_aGO$HG)Yr zCXM^2WFx63oaa!Zbe8U@z{<4*fgST%1*M(64NQV!ODoErv{Wl0#zD#RsCj>d5tSpk zbEUju^hU-h?bporPXFExave(gt@EjQ6J)XK*;NznDXCDb+@SLEOi=jb8^c{Qr0rRl z#gEsRkDE=?6yp@!+ocLMh;<6pim{gD%s!FPlY+8eN|)raGU$KO)JnXtIiXQgx07rp zanyGGg=K%h9mp&tWg_Ob+zUAJKxOl^_;`B2Kg%vCr~{Z6%PQ-k z)LO{{u6uz2bLhGXJu(pY8%ASMl)K0eo5Gsvxy|MWnQzoH@-fIRcb}ua-GXYC`vY>j zG&LzaL>d}dYBTs{Vq$_9L4NAg1Hkv~0+Fr_StGPN6D4ew36d^TXT;93qXwCxO^wDp zj_I|_z|+H)N56!mT!&t(-Vz|IkQXE$Cq?0W9t{+Vln6Zqd2K-=q!v5^epIeT+Php4 zXm(Fp`6|f4+nYvYd;Y@m>D$IkN1fW6KI06uZ#Jj_uU%$mBtjqJXyP{VTuz#|BUV5O z(9voljBC~#$atRhq^lSQ`Q6AWFV~9`v_-CUN`b$4W&zqdP%}A7_d5{Jm#yBrD6J zV{hCu&^Q?LLuei-w5{(iyjpeN^D4i5)YTYBhv`kZ)$Jyz#tWaDyOah| zS>tXNJZ(8&gU1cO2zih__|+muE|hTxkl}skH!8LHTX)gZ>Y>^zd`O8eJc)(^**i7}2HU_&UPJ z*7>DRMXP26)7jQH2EtG#IM-xZCppYQ#vIk^s!aXIbRy2)uaVK*F9$Al6y*KCVoz>_sl{Hr51u-Zq zs;cUMLi?x5$N*bHdWkj4YIUk*0jz$7fH-65{ZPg{@J!4bg3`(iS>2OrMfP+dk?yhaDLqPf{vd`V8OfGhR$ymj> zdf46esDHvHQ2(w1O5@7id(yr{CM*(NEy3YBRNY7~dzf&T zwP^O^VI#}>S(Z{x57o1|tcQh#hbtLb_ve0Yx9or@J&Wzpk_glpT7G%(%Wgm* z*qJj!t!tP9&1bzokuhQzFif&2$2inJAiPYt4MpXTDUJ%Pxu&$d^<6~OeA`XNZSD1? zLoW*kf_hxU3CZ^!7$;LD(^i%`5vx>HC0QAS-Joh&3nYraeEH&?%>?KfDW&$*L1)d3HMO+h z8Ht{)89Pwx{#J|Y-`-&_?-X62eI!ZNQMmCe{eEqsB4a34AkZZ@<7dHHrxZdr!+O|V zs=Jl*OzM~=Ds^K&UUjL`d$$NhAmSu=gxb#gv^Gi`>r6T4G>ADP*i#;T^28ZB>RzdOB& zqGp8695+2~{H7;Gp>7#Y*}RTSE`8gCQ9E!&rr~DgMVF z*`p-2Vm?%C3Ah7_MIOAJn0Q=su)k}JxGd#cefRF&59>}9h7jj@jWM6ojB>@OIG#{& zaQw$UHceJ-r&Ne{%;sYJAt+q5J5YmgCKahs>cEJb54@}q zJq-6ufYXw9)Se%bXR!MiSbG!iTGLyMm~x0PLVN+0?XP8(|Exn3oBotlv7T>#AhACA zn)3qPGOxZDwuP?}lOS;BFC|*Rhe0&~qGa07LiUN0dw&`=Pw=kR)a-mm5W7fA8>>P(Yk6q79lPv zDbDed$dr?7F!9UFYX^*rE^=5FNB61}K&1f|A*AtYNmc38G>@+PkIf6y3RiFMZ<3sO z8+@{FeYkR72%E2M_o%S2Qr0fCsWv*-EEK1kaEWQZ>3s9$*BZXmr0g2 zIDVefk-9dj&iQ~)eFU@9l_En;M`vAZVQ3gnLdm$e5xeS0n8fVD264+-Z}g_qv4XTH z>?-zpT*29liEA?CX@tKIaPSvRcwJQa7$wQd<)<*T5*hIjN1RJkwQl!7j!(`cwm4=cIxu-7EBkYFd4ezVHO<_c1q&MkWa`XD?44I650Sg8Z9JQmwPtM>8Kiti!p5M^ z0lVBb)NdD4d@GzdO|j+IrnO&LlK?rvW`_-QP(Mn3Bd3oKT)!{H&eJF@QSSy=420I7 z!Q;3Ud5y&+GSusKpQVCYidNNv(Cfep7oei_nf^cx1~W?N17-voYe1U?q%7r@rC^RO z0#`Yf`G8r#s`qEu7+`3B0CYmN@mKS9S|v|{;Nhsyk|Onw!|{a^*Qqb!*lx7d5smNX zQJpzjzYZ{8ZDFOlJBvhF5lI!quDfj|O9JISMoLyvd%y1|tgo&8tz`z)MdTR&Y?0XA zpJ$+C!_d0mv;-8-VOse+bZnFB_v!2orltKWG5bH^N;EcNWW#6K`u# zZ|rXhEZcHZ?PDA~LjbVRfS^?}0O6diwE%T?(+(6DrU6COj zMFOtkzSbMLO_$S}zzO*Fl+ZbY&*DT|tX@&Eh*Mkjza8dUaV`Rz`%3Fesl*@px!D{s zMRnXgQ$MPve)n1v9stBn(42L=8eZxjbwlU9eECuXm7x-so|(xOrx|HC+mT?5f*6!7 z4`$lqyo}H#*3oHr!nun4-c62-_e$GSMq7XHkGAtxvl?hO zUnXiN(O;oQb8qD~Kh&a@6+qAgC=s_!sQzebEU`(r*m|W3ti2!c^!Tl+Vo=)r%;>0N zeXk&}BAGV^C=Q)`!-oq)+5E*E+@+ z%5U*O%W&saX~%Fm6Z{RWIqz@!wKDpi4yr*(Y+ad3;ZXn7Q-aNrdHyaJ7`uXi3DvD} zoUuxTu3m05&9atp%CO$30-0;3NzQSjfh!$)Do0(?W|HFp>>Pl?8{W+1SKV7uUM^g- z+R6#mad>62IWjH|vk?ney$xbh!1*&qIXOB4R*=V*1pWc(k4mG=2_wrU!JJ8ETd2EA zWl8JSevOv`0SgS+BdrA!$H(LO*93@Umgk2Jm6+xcEG4NQ`WbKwZk~P{cM@87c=ZY5 z1?<>9NCZSYSsW;AZEfXnSsJuR(gw%MMpdg6i0>#b72tnzwL3^|bh5HSeNR3;T-AF( zTN1l#LTonVFjw5^m9WY-WOj>C((p=w;qMu1$78o%8rGD{L&1TC{##Q1vNz7MrZMp@T&~$Pj-&F3j$Ob9!NEaScP~Eyz5xCF z^QZie@81DeT-7h@);5CCo;jh)^r!B=Es1~L#EQG~HNMVSe95)z8I7h_ppHtLK74-6 z!7g@cMLxu__Jz2Q`p%c5hhdI2MxT%!JC(q z3DWDNFsNugDvNAo4{Kyk7~n9Y4_p6=WtC|F-h3M(yw+r>MtoG51hZcW<>Zfz2;%ucSx4kd(@JV;o0WF6u#;M$p!DcrU4TE`sd8M**Av4lz-z%qzmSqpH=ONgwHw{3N7u;7(DTC=zpPHHa289t{dD@ z(#gO$gC~KRo=2l$u*Le__Jcp=E?J!SQ)JD9m^L<&+WT5NBW8OFhpL^DRQu=6^11&o z`OVFBS4ODUl;x>E3^2F4c%j1OKq}hOFyod;n;1Er_Ia!j3?}x+mlzgl@bG|<6s83+ zs7SM4%j?ccR{?fTs$-DV$e7SYV?<657U)=a

~gN$$)Gn;;f@if&v_{IR35rQ?QRrt1&fA>R>j@M)m#f4G#A zA`>(eKeu;;)t}TUtO#;hNsOj8`Z&?E-#ZtzlfH3}ArxaJd|AUWt&?JB^TEmz*LxRD zr?R_S-wF6qHk?_&Ye9Zb_C?6^u_2~}G+(jAh#X;7s6zt5kxj)eId<@htEOf2o?aQ6 zSsqP?p*ApxW91BFFkf>Zsvt{G(J1FZYT*9nU~isohoJQLj72OIcJ+K2kJt%OP_TV zE>7uA5T!@+bt!Zh7>-?a89o5QW#7rUo`!2ue8(r_u~EF~GFI2PP=-^ZJmCl_uYc(M z_$2J$0dW7Su(egce)n1=`RHt5P-P<8KO)>#?H)Y%#3j;-p`xX=QlcO<qMf^x`Q^5=|Q-)W&u(_&e<_??Ml%?jMe7-6S?^ZwH#=>oC8)fB=H zpCf29puR99OJf8Fct+>UJ!+bZ7iU~X^NGeGGy^j|U2FiT(E#O_g-4Qv7miIz>VU?? zO*G+MaBxYr)XSdFd=`olHN*4H9HOG4FyLcrp98!2Sl)vn?mC><6Q1#17P2&&DTP)1 z{l3_9sy~|UuRvS<#L+RHG*Y!OS+W_}q%o;;Z^ysu*uWE+>R39mJoF&>Z6)c7YA!vjAx-isJsLwdfRFyF@o% z)FuiErT+$&TKx#QF#kezg=`~~M+2`)oR(jv@LSyUO#idt-w}*)YpE3QnM+yG53Z;T zE_TgQu0L3cabOlW=MCf#Y~TeDE}0|ldc?3RTN#6Ztafw6Db&%)37Din`}9>fS;SFo zv#_u58^EP83B~5jBCw{pGu&<9f}@O>b{?bXK71P8~LYa@=psm%Yf?I zki}Cz$2h;xqH)hKIXt3cGD@;qC3Z}ANLXoTH@Mio0vHsIyZaKnf1CtT8`r=0Eq&$@Q=*`k>#(4Vr z)~bRW62M>C#tTnR&rVLR#|Qvv3;H2V9qv{6^e1XEiURS;5eeVBnZ>3nT4K;DK4CB_ zNvXg^`nmmd!mm~oF%}U$9J(uuz#^snXoqxM9yhd~AXpe$z7#>dwh_IaZ;D;=o%iI} zT|%A5tE5@QP=&$309Q1zmQ+`K#%$E33gI<69*ndhmX zf?jysMdJ4D2i@J`R|)EjBe?pE<$e;J{Gb#u>))KV>^6i##6B#N_<_JP(0;#ssJ$|E z&g(15ByReu^q;bv)kSubYb-2(HE|1+FNsw+Wt%p_Z#n4HZ;r3f6ifR-)ww@=Fai%eo6e%eUm~qc76AXL+X7E8yBC4Vd>{juPCeJ! zg@QK#YL2U{wMOMT?t&qyaT%1}EYk&{r5XwtcBn*2*YLS)g^M>hH{1w}N}OOxE-;>rO(@7(fEqQ0mPV6JVI7ZeKv<%`iKp{gIb%hea2m-U)wPB{!Dk>8nD(=F+))g08XoP>Y!B-L=@|Gk#CW7>Wd zzq|Zio0Vlm{@)P~Xg(m4rtT@R){b7P*e#z_%<*)4 zfsbL4vnUYyxYR-L>yEz=)IBjv{JkSS0>>R`K6_7K%lfdVY z1^18oiYsmITPLi(e;3?Oz}0|Ip$E(D&yikDG!6o+ndJkqOnVoosV#wEHbxwAmTHXpY&i9^6unlRLYsH~xr-CMA1O9|1rU&-dfju+k>m$q@hLA zE5VUFJ@J4WX>InAZQr%qP3jzk_wV(VM?1I4X)IlYI>z-iZE5XT!m&F|)DuvK2W{T= z#NHBzE1wO)j)H=2kVimGb?#h>q|c6fjrs3}fT(rj;%A>w8%jJiy%+~x=(ShgT!_N^ zvnrKbViTc%F>iFjL!41Ua#k*HFlkvg0ZnO_H|!}W7(s{y!(?J9KQ0@vllv(xxXLB> zMA)q@O0!CzT|jf(VfNzZ)!_lSR&?E7unty9v4?8>Ez z1~>&XJm-LWboK4j8FJ?@PD}c19>SlgXB~y|~ zehmM+LiHeFPP)VeC`2$!17i>bfTM1v-Vf#|YhnOV=drr7bIkYMjnq_C`$HJSI;zID z2a3$z`|hpCffx~!Jt*l*PSz{zNRqqEj*hoR4l z)*|wi^FCST;nJ)kIaieQcRpx=py~CKyjN9&SPXlNL1vitU7Pa4%23~Gg}BhCmvRWe z3s?{b!d}kwSepUCybP4JvCoEfssyWA;-X89T9PDiO0&8Xp>Dv)sAq;yIXZmvxC)Jo zPq>X-7M(@a4QszI-{RB=BB?;Otu5`jHT<_dNGXZXCqLzUZGKn*x$djss+b&p<)nbp zn{K4s4ks`FcljECxb1I`N-~!a-VL0DC_o<1DgEgik*P(dR#n9XW0~w8jnfC6Z;Muf(<&L@ffDeplTP?Q zCUR=Ko3na6+(>mO9|X`xPn`}I{lMmd|33K%oPFe`(vJX*F-yy(VU6dt#aIIjU&06r zz9h{VF9i?_B}vZb!nxS@idR`i(yDlDvvs2v1vTt(JIs~YG7{uAacrc1oreSPS9}iv zs$cA?mIU$Joqjrsit}n`J6c-0nGUw(YJj2dySdZIw4YpEUCoQ)DIY&J>N;%eyGfY2 zfu8^^^%@0q&ujoJp(RfvF-rTWzBcG!Opu`_Q@X(*esWonFm7po5qb^f$1NCE+rUKp zM%E~DH5wkwm)CyV%eh60ZX<$3inR~haOKu@g-Oy9qN8j^!iI{KF~89;0}!3U(h?6{kMaY=HQ>^|lW-B~f>5BmKHP)t z;+SV5hQD1w#=U~OVC7{`;MVV}JBl*IIy&h}co~uQy`$jMaB58Hq1|rcu$4-*{CkLC zUW5ZZAVVnuhr_QUP#2%#~Eeh=264K&Ym@LhXAHZpItSB3G*YpDYRmS zm%4k?s$4JzQd`=y>F>jOYklKWvb4G#RZ2* zI}-;Yr!K%X<`5Gb#<=j*?G;^Pt{@_WTR0NFRKLTX3g%5Brp65kdGT9*qo}i5f2N_S zW<1()Xq&@0KBw>~wDSPT)Ov9~tsiM(poDOa*zdpNSy8jz1hZTgwwy)bEbdCb4it7# zL(jYmJuRStZDzi#U(EGGp6ma0u^h;kIgpuw^HjNiKQO;yhIZ7kjSI>nL0OmCjb?*P zk_Fwmok(6jz8Yh%HmD(1B2LY>-icw_+mKD z;^h*^kdW~6A$_uOA8bg5=C2?62zv@dqa+B~xVb_;JI*&)S-lvRH{8WzMV!*jJL0pr zjVdz%00POQ$B!RJfHWtcUEKUGwhjfbr_LM;kfgJ|gF(dY9L~U^PK-ezMg%X!_UobF zJ-blsZrOp^tygt~>5&iPySLzJ(1HQEP`#>IV^ zXFy^Ri{Yqhr*DPPi63@#7^CghGGIwPkr0IEU2EJrb7YO5bcJ-Ez*#D))DvVE=a5P~ zecxV@w$=E8BoO^N-Xsp4uxCv{fHS0kg_PszAO%_t_U`=|vn?8^ zbN$vX3v3#8pJij$$8@Jr$8Fs*8)P;0*&}(GH_UUzlY9A2 z#5!uyfJ7)}fg`X%ukkYQePCYKZ``n4nfPHfR$Y|wHh4OtmsgL4`^&3HXw5X7NH@{1!xnneO zA@gXdhy$1h;a-q%ONeeUgVF1ica4zPhAFo)!{ zr!yc|+_r}HFcBA~PX1a}!Hw(V4*r2-znZJGCrO!LtJgx#Q&9!?Dl04Z0^lbHQM;oEV%Yo|1e@TjDM*>jau;XJllVBJ z8{9S&vmH<9kG~Z&zXt7}nDrpMMpDos_Mnq9tycoKDO+DH{3Uha`)j(al5P2P#<&^< zFEw+zzuZan;t(bs3n1qRD6$WL+ict6Qpvt&sQiR<)r4$lTjGZ8h2jb1uxHh)XtWo1 zy4b88lc8jNXOx&Vzi2ufppDwc z0|39~6+UUU0`Z2S3a5;j&LqUt)KlBRB3Zc*dVsVorTs{RXMM48AqvJwc>s>B%d|-*gXRMKpxiA#BtNAb|8IrHJ$dd3%7pzF2ri} z97%bH5RkEz|AK$fZ2r?I(xoR4GtC`Q>T6}>b38AIB-U$Smo$g+a?X**QSS$Gj}BYX zBK7#J(UcNKWg+PIxYqX>d^`4!)jaM(9Zo2Zic9xo=Nm%OVg1G1r+}5F(Z&f^!-l(d z2%#t2PN3waG66|_H5B#$^cx3c<3|q+4=67?KsA#t<@K8N#9onYr3J77G?0bfx?&pt;>gp1)fez(z$xv^?6-8o z7F>!DG|s%7Xe_Od!HrAuhdumYIU@Hi+tvs_`W_ysnVS>pUsYle)?j3AcS^aFy;tHu zpS5iG$zKb{|J}duYBH@Z?kTiNKCj@8=px`pan)u|I-?vke+4xnk>L*9z-SLF`K9?$ZE1`y|N>s3;FrC+bc zO?Od9hu}v6Z0N_ok2I;$CB zm6O7NxvWg^z+oSri>95kSBjRp5pe%u&tzXdve@_r!Yxo?jVT;=voM{;hK6bxDdx7( z1u}o`FSHLkD~Gm^!Fw0InKuqc1&f#ZZ&zMld*f3hioP~lBY!%y5Md!8=(KSsZ!BqM zZT}GiW*!r?W95uCKm2wF2Ac$wZ%L$SD+alkPemnDC4LpfRM|VTXTh`8_q=@@mx>kOA}AEp09!`YA1X)PY$@HW995j>5@xbPA8slPIOSSQgp7 zqFScw3MTd<0Js6pTKdR{w#vf2qm*FSO=@i=+P#-P_);GhABV46hR;mY^s?RFi^fXT zB0lM}@~#QYm|(Q@fVc4%cHIV!+F?`K=fO^3&}d{t&fP%1K9kjK5BFr?ntN4r;X*}; zXA(B!fTbyr?l8~^v*~&C`hs?It#1%YzAf=9g6Sseill~*ey^a0H88h#>^1>g>*0H0 z5uyK$rlpNv*Lpl0X@5~Mlp$)__`1NHdA=aW)Kk~m(|f{3X?BLMzY%f+VD*CCE^xYo z8zM%y4Z~fvmdQfUh>#`tmgnv5HUIKXA$kFgBX3iB+h*_SQ7*Cn^s4G^SzV8cM!1sV z{`{HS;ir7XK79rt&HLCGk?BLpcU*dM49Q?3Zz6szVXJ$`w_+ao-JN~r7<)?a1xC(3 zD;6X78m+qb8~8_t_$~PwCksmaa%1q&^J{Gg{jVsd?(PqUcwAA`!e~QNPu7wAvU>Bs zqs-h&{O*eUNRyTx9otD<$DrKaJ?SL4tNlbe?zqgMDI_g@eIugDn|aBEo8jPr;wW>) z`|F_wLw^zlB)+OeRQnb^c5IQdF8fI993D#0TAND-mtSvzsL27$+ z*G)=Ehd0Q7g*-hA-w&9UOnnch9Q7Zfe76bot|0K_XPRQ;QWZbA43$mun@%4r?()PCg+tLSZ1mlsg zCC;q4!)=qaZPXqc1p2+|wMH*?!%v9q(eB&oA_5aD@?X*KT_z|9br*p-?!ISd%lBCY zl`vzUYCW}L`!#oFP3H&F!#cCiM&!?Hq4n}~FD@Zdis_&HJHL?GNVwFgpE5>{F+E)I zITwG1?n6J5GD^t=`zNOzFSf?edan=fb3EUR{GaSDmH-(%0 z7=ORynt+`&SwO|sVZOV+Rmw11)~@}rgbBj{5#+Kgk`52Y8lQ5e-TTn^y9<6Up|?!? zI1f1Eh`Fbsq;V1{w!GcvIJ}WCnQj#>BP5ye8@A6ZYHP3`e5y^3> zYtnA4P?vSQyWMImmPLleW|^h4Z!pmiKmQb`9anYgpsjwtz2c88>C_${;PG`E(Y5;} zb+9^?JKXi)Iza}>>kGOOMwt8(N8a**srO(ER^I%uu8~7wG(P& zTDAy!V=@mPK?C@Y<<>O7%F*LbF+OcBDPbo2mUh!C*qE!ts~bX#;re+xnb1Kg_%SCX z?6Di!@;ph2BxFdOK`?(*JgE)M?>gsixbm%WwN$2*Gi)=~ek>MxLuIAmF-X7odzRQN zLsJfuKA}xgPg=ujxvZN{=Hli4JKKAYW>dRW*e2ulc3C*?XZfSN0K$hG2JtgdQ)yTg z3Q^97w}l>xbIy;%{HkO1aNPNdrp|j9_A72Mrc(&E+#N`{7_C-kwduV+t@(8~1Cbl= z){*8mTXb1%*2{iWida9Ej2~J_|Jomiu@%p+o}~4|^dITB3yX|0hd1p!#W8}ez4-kw zH-?yK)yqq(JmB^}6TMa~ZxlNBc@)wU|Lh%@Z)>*T>y$5!MUOaHe(oGC&sU}(7jTzW zl5}2F-EQss%4spW_cP3Ub#-?&Ky!0-lpt7~HG5{bp@D-m&9Q#G5NS1^$Qn)l0q(4k zkx_+R|CdTM_Li#y#n__{OzO}KnFYs0(67Fj5nLqLd}!`@hJoTQ^cu zR1-^Gc7&q0J$|cU8;{;@o$f63Te|2ACQWVdhr4;(+4ZoeONFa|tqQlNtY8|}3> z-Q4#g9ygx-K+HN@8Or#XlJTqNbZ&U4jZRHm_&~05pm;QB)$l*PagIb}hjF+U_ zk5?X@Klm0pE=d-cP>fnCeRr9C~$u*}ro!Ogv5$Jb$N5y!NSzF)od6%|u92hkdp!V<{me4}ZD@TD7@! z-%)y)y#rCXkQm-yA(C%MtZH?Psr}cN$kDw+n&O=+#HQd*aE6D5D>u<)XKa)yjf*$v z#2ov7@U5<|?(mGASw_cqCKky73E};X(2ddFQKCQhiO0tl|BtKpj%zAi+eYK~D&L68 zne7OJ2y91+g1|^MQb$G+kfI1kM`_X}^b){vgsoCEp$7s;Z=r)gASeO`2u*qmN7_g z*$kA&?!MBfb2KlAE7OMk)qmp|EcXuBY2fN6qCf zzqg$@aRIc!?J0yG3KBmn3Tad=`(p=f>_uZ)l0V(7*MBmuX=Qy~#*Bj`8gx#!1MLDb*#wy>D<@986ZS`!BwhDO z`vpu%4(jeu7EjDeOgchlrsFTp0G?rWww7tpAw!NJxdktoFU@Ag3SneMxQ$&q*$(^& zXso_5kbXW<8lws%Ip1R*fT5VgHE?JRMzm7*Z2t#gO-cRZjRnA;&S7D*9~X zKWOq>1keOTIfh@{ksJB8S}~h9kLdCcUyC;u=Il!ghDCAm9J8Mj9d@#v&i6zUalYVXGP-=r>sFz~BwVb#{P|@MH z%*!%vN4>scUx36)mWubri40JrbSQ4Tl^$A9lX95LV^XY7CQ&{)?6#uBdw051#*QLa z_j8-JHWcuEs!#qLD(`WySU(E zAxP`yW;wc6>-$Z*S(hO8JqT7!rv`t<4_5TJ&P9bzYN)0IZX`?e6g;~=Vxuc!u~Fbx zJSce4b3Hr_LlW6$!=qMgX37}MZXbny)Z8%4^wT}lz|pXB3qvV!TUGy|BmCdt!1(m* zl-0=7zH{2Te09I#TeiP-rZ+~|y}Jg^WI6scheXL~d{nD!^~|Imu;^+fon>Q|VcOoq z|G8xZzI1`~B~kL|WHLd6JxEd$HyD$bMHzN%{1J3FlDhe#hSD&K8(&>Fz+~5d(BTx# zENA^_H7#6kH!kJ*s8Yy%!Ag(b&~eQNR~LY9MV{w;MtktzPC@sK_n$Ckgo!5dS}K!O zg%PS}>H#ID(dZX5#jzXFJyzmua%nlEsrwY9QBv#Qd1 z+2Qcb@GzHIsPv}Fb)=qv`~;}|Ie+fK&8Q7T>AYYWl)A4gwIwl$;Ea6gQA++&vH%;d ztB`SPUHGI`ZvSG)MI|4t3EX$2m7Vkx_$|4FE741U){3>pjq2O@ztRPNFU`iDi zLAfNXm{Y)2S)=?Whnmqk(tIt_f79g7hN%>NQ9;sysFn^7Ob3KWH~1pbPWr4YVwWcD z?++;C8)uGE`Tj6pw{2bmF1bs(JF3lA$bPW1k)WS^SptB0X;Ipt1EC#}pn%1$$x->Y>$ur3x4gkQhebzL;Ga{B&xW|AWA}FP0`~80>Ed`N zwftd+Cr-#okI(J4L1Q07$@b@D-R#tQPdI|VIyifr^IVpjvIt-kK8oK37JYKBoeB?0 zD9W}aT>Nxf8q}PQfsCO@5b0Ty?y*Tv! zgMP%QcavAwOn`6{xc`HEKk&g209|Z0kk~^a;+XD*udz#y>OhpA;B;gIuBc7URXvFp z-N^&+?}cu$?Xrt01BI6g<3te)LE;Wq7cOhJsQWTMidr>AI&n?spwbU~KQt?@c=ork zG%;)rLw3x({|0Pz;wO&Ig{3V<;@8@;M>2ZdDkE+-Evu0I-P6W5)k+A|rizMjq^I8WxyhL7LGUWbRE)zObq1Xv`Dfv}#jD9W$HnqP$jIUYBt zD?@kH@$K)(wW)muESC^P+WY+4+6b-NqAG!2U_1a_TICa3tVzdcgUeAxR^&o2ba|O9 zqmw9U8ClNswXuWD{TjK`4Go=Td<7O<2$+b;C;w)I?rxMw~)&Kyj)D#fCxp4Y@nNZ zX_dIhoCjT6(+OWXDH?w`@gL5E;Yv=oh_VcH(F|`B`8DmZ8)L{~ii;qPu7gtSkOjYM zUrQNFhWWsq^~ZeIuZ(c2IKqDT+>)D9$d#p0_S}j27$((Rz)e@rZI*%yJE*hWL%*n{ z?dP80Z1B!c)8gohyRW*OiHug~mArU-VcM$>zD2{z>=b++-)Pp*++?xfkkD08l-*t`9wyOQWiaU0)J-#l|NzVr!;66(cn0CKsoY4@Nk>SDX=J(hrWhjfL zzqUo4q_f{gNS*OJ6gwx=iu*oyB6Kp`>cFJnEBlSnq3^xqJF}{~ zKlccWOsUiAJzbZ|#{1+4IcdbOlgAx7bJ52fJftGkBxKR$Xcbt?s_@}$ev3NuFl~2I z4%b73HT{`~I5%K)mU(w_M%ykaVxgVXK}JM}!*ml1xT z#n*h1Su@m8MJu@qyeeN3{`(0z>-x4~W=F7?87Dqy7yQ0#A{EQl9iGA2x-t()batA? z{xmH8SM#z_j`ogSJ}HQ2cJ?*hhJoXC^yi^(^!HVh)ZUDP*ZD3wO&aKhQa-^&hbWrP zETvmOZ$L=Vwl&pSLnL`b-SAz>IAisprh;SX zArlclgee3TmYzAJE>+}!I4x!;mAJGIi0x7^y|0pa)DGbCM6rAP0=3L?6nz^%L~Ae}E$SrB*FWorNoBvK_ z%^LcXMyiu*F_F(61HMr3DJT3!rEr0w*C{(Yz`aUYMqUGAVcX3ueY{8{xYP1Tp*l{~ zERgw~$T6)5K;gbdCDolSPx(5Oa!88H_YO?ASN`0P$46%RYW`cB(egruTy9H5Lk-7& z_271s@S~fk!%F9|^Dat>`$Z&pqx3?sEUMT4nsvQaHft1aRo~XS8CMb0=$iVoEVHN}vF%}%ynR^u$y?>hB0ix{2iX{K_RG+>RYTD=^u2WjR%@f+8 zo2pXdESt$bC#~d*yVd#ZoSG($?t#q+neNPRUHMF{q6hs&4z1xH_10YX2%niK!J{J6 zv8?wV(8ehBl~tLquVQY7rTQf+Y0;+ns6Ca$%$Ks`ycjl~X9nX{DH!LD)tYo&=@i03 zC->{v#K+Qg~r-5XlDTzx`F)LYkd42>$H51go3c}Qqu%F16I7i$*M;x3L< z!uoajEy(3>+?;h=4BNpC-HABKc@91`AzEqqPmGb37`4f3YKxhMl+sLpyt+W2ULwjm zhf`!UpyYU0(F^4vOmmeYYF}!i{jHew^gm$Gyt=~7FR{?{TtxQz0|Z?u9|w-T;Q8*n z3LAUX$^wg$$HV_O1-GoXKf30S|2=iA_JV+ zmgUA#Ouogu+cUc?ywQ@yKyI!*j-7AIe0N!9X$HEKUhd}22i3PbD6d45mQ9lIVc!b@cj;2|Gz|bAG)zZBWzx`S za-X&7R=5q={Zq(sN8kZ@T6dp&haoiDnKCNpoADvSZxLb%$ z!%`CQK9%xcU*U=?S}&Viv$MInuw3HAUk`4=ysw9c0pPo+A6v@YDB(H z?xkd`+9rT&nL=Km=Wl=0&|N~Vkq_6a@%XbzzaISjTJHHy+DJd(>UsZFTp~pBy`)XsV5AD&Y(0xZ4{ZS&a+Ch z;gp}Yq=JviZv&|vAZ%Aw89l`jfgD8Sab)A66qG!Tf4fbFQP?gp0xqRDFD+%U@FI@+ zkAd)#ZJ1>W2E$JLA5g<|+)uUx4~S{cj4=L0w=}!j9LCB8{*u(bS^d!MT6G3|I~kbKT#=+W{D!briS1^EgQ1}2Bl*N92~#e%1#}a68`Nbs?cgw? zYvvYLlrJ221b=tsTa1DfQBx`u7B<{eZJom3j(TWmX(@=Yb)Yjhx=$P9Tpc)E;?ARR zT&~yLahwcF?-%C13-7%3&Xguqd%(k4tfgQ8(F+Q4oxv`xjFT)aUd@$7tZAY0%kIrZ zUvhzk+!wQ{k@8dv04VL^l2Q3LVE2QL%vMSFO$T|(JI@}M`}fSurj;Y(3M8UNA`-&5$V`$oMzK9$$6n! zG4xmeb)NE(a-fr|HfpUj$J%O3=?A_%4i1DTv<)>oyP;=yR~*1fh@- zo(U~|RG;HzZ-#T8@o`ZKP0-eAQ*P9#se90+Fcm>ME>v zsL#I3dUlX`(SP$y6SIWOi#Xo!T&;Pz0;8kS8aC2>YH|CPtCrOU(Q9X(wKBe5W)8M* z?>$&d%CeM>MVm?aGLZOWaYHR7nb0uT;Zbv`)aEnm#7wm|XBav2gzWf|rqIBb;Zbic zz0>|?$L8#*DpMZPonT=H}*_ zr!Mt|qJXV$Fy$QR5BrDp0-hD7I8IH_Z8R~f zupToPkiQqM=a&8i9P`%iJSctMGi8MC(+C{d)lSdcrjd?E82}l;67$0o7otYH68aCL zEc<(6PH7L9jUpE4X{J@2Y>(zAA88e-U`8gXCRj>TLt=!e;dn%advW zI&g-z^IEY0>}~$`)5#eQuFJ7pUBBmQ`?lO>tTmXgO&a=*KYr!2L*0{&u1r?eG(#OP7vaPf0SXShH=NcRG%*b^wweGlfHo|b{Gjgg{* zQwGrfhKzg78!j#J1B1upk`*H(m`Lcs%$kx@e+_r;^DlYMJGk6BZRU`CKoq!Wh2dA| zQ4x>>vK2yZq6m27E(P?SgVLujB!da+;PF&~9qxB`Us;rXWBs0If6LkI2LL{*7omZP zn(yW;BXA^7FCKRU9+2gP$*AJJIYGUAi$-Z6L z-o^W=AULg@@q9uCKV;d($f@@rYE8e}dX5LHFr&Vy#6$!}vBg@x81 zIlg=6LggV$kz5Q5^*-6I`6pnT9W>$D5iFH(i~i<=k1xTL${>gNKo4*+T(c7y$UDb+ z+W|S6p4WjQwYjaen{2r-0UiTDMg9ej^l9lHCzGX2Mx)bsHk1Ke|Ew&3+ z@Dpv3wzPETZ*YCLa3?LNzJ4GEoJjLRFW9JQWQflk{8bQ_)h&QebI4kP z1^?+57zM!s16f-!J8a>D{_9I~Z!23LTZ36UZu0Q0vNt!|T{Q_nG@Pb% z)4mG+u;qdpOH@TNboQk_`(r$QX~0#%Hrb#3N7;j}X@N;C9Gv}F82TZK>+rn%tYd@O zgilQLkugGyY*sm?S^qkU?^&QtxYqtc3w0miq06yY`$Vp*UT)buw1+L7h(C%OQkQg_ z&4?pbRA=iVNIguU{Mt{xS5PPq#^+Zpg;8%RjX^=*mpyrUjfK)iXWLQ_oI7Wz@Z#xT zfKWtR6lX{V-8EyJIOD*Lh%|aDCpgQFvQRK!ZQ;A3`t_H9e1a;=|1M%?e+vNw=VyiA z78br<;#7f8Q0sS0tXKEveD}l=3KX<$m@9QF86Q(mZW;2XXg!Gq>EOw5)J=JHwnC#; zjdI!a6h8<2^(&-quGgk zQM7fHd0(;p_5UZ0;Df_orj^wS5b$3cO4XeJGH^2_!isD8c3e)jgLBw1GMTOZSt~!~ zv@q^xtyqbb<@KKLqd*bG-eiz7SEjwTt;_7*7$L4jQ712L*=b|Yw|_B{e)wCEbUHJx ztRHM8=`lx|bcl6fe=cY{p^lJ|$3@ss34I`War@@Y7U1%a*4__XdVJ#hnPSyn;R!_e z4XYi~CXLmg`K0^Fb5T@)3qg%*BO3M+xKMGqjJKDlsWQ9Q@cThpnCMfILz(21IlIMp_c1Cc#_!`jMwpp1mPyW?Z2 z>bqy|LMt`|tP+TudZ3ANR>)un<;${T-q$!*DZ1@T zOhtU73!LY~X*v$hyp1d)e2Jy#>OeU_sE1o?M7_|md}kT%q6dy+I2WjHl%IbhS86L#{p zx5^VoavZ=6UEpwkgWg7{7VvF|m*8wGWClnbXckY`sE7;?fy)DCkvKGRwALDsZL0M# zD$IHpHx0m_0U}!CFjlek$`e3$WZi7Ty3M%6!r(X;3Jt0S2KYl}6mx(E4FRAekAgNn z=o)H?lN|y5YqXZ{&RIO3cn{2&k%me6z9ZRz_%%d}{MGSz1F1x@%&e|6B}sm?%ZAi` ze#)1_^K0Cai5vwkubAWOK^$ylw>3pMg$;TuWk*O=YEe=mSU7P&gAc2YK_lrubJ_KF z_ER7IJ*X06`SPyY;VK-DZRrVokMOr|@F&NWiQ6VM!r2L6X&KjO!JqR49?9R{I=qpn z(7V>3jpkddELYEKDoLTueek_=R&^DeM9y=-o!q&Hp?F)m!Dy*Hz?c5O+5y()*41Qx zG3zRs?AGtkxfpbr|A&q?!;eisLi}wSTy^Kz3+aFz0R{~4GEJl`zQyQ`JLfskJ0$Ak z+wEN(eBKfts-W+~HXdH_SYHIC5w8Y}pi7`^&u*I>m63X8Ba4gCt0aGzz}3AIj^j_% z8i_NS3jCHqG~x!^uUA_v>o`!Qz(ZRxmljG}9Ta7ozUSeC6OAl1>zxh0;e%Po&&%N$a0dY(Q>@3Hr&L`ZFq97RShVB2pZR_D;{Qg-#L4aE$HwH zjEky%j-SEY>&K?!0U-(Sx`x!7Jz1x`nB z0d!35)WlG_WZBwpK5PZEuG8`yQG?j$Z=BUX884qoAN1{Yx!-uaQ9SF?aqHE{D25#k z#?ln2c|T>zIaliSjkinTQ)^8SF9;SYXK&v9l*#rZjreipTSsk2BrTJ=0Son~+?}#W z?#+`2R2z113@PI>)0T5NyQK`uKYm^Y#OLjT+_*2gtq8;4e$+#szn#wPo66jYw~=v) zyD+02yP;9Yi{N6i5{!%w9}N4N?v`Wvoymu*(1&{h-4p~szudp-WTz)5)aPMrqnG;t zTp6$X|97CmkQQK|Ge;v-?7E?vMKi>)-m-L{J^-jD*fVC0!a3T0~dLWWps`z z6_*3ijC@G%vCt#d^ur#jDojecAyC~2+U_dJ>ky7?Q-IQrBQ?3BUiy5cbz6|`95XN7 zs|2 zBUXZV^G3SAXS#iW4Q{az8`1c4vZ8CHSC0_Iz2Bu)t+1@@Q)(XgL$B*xNtmb!43rc& zl4tDlAt)D-5iSFy?`AF8fLck_KQ$MHC8;Yf-8@`;xl$KD6 zdZhWL`H=Ri#kK4k0Ml=_cra!cHW-^mi9#ICNXM7UsP{A( zD!tYV1BzR~BsXZ!0&%{jlHHp(+Z;K}#M7LQPQ5O6+jRWj%pUUg`*=X=*}H{DwS+Iv zlWVou%vi2wRT`z$*6-9u%i-g@#WcDbA0ygGfwSwh6L+nsE+PVR=8JCES@BotR z54f?j^5Fb+a?RAZv|41ft=MeMl4^(lC{&NMo)=V}^mS-5nce2gD_q*KIN1))-YXr$ zwpFZT$<_=wL1v!yj{AIRi41W|DW5Y9?h@wnLDeQqgXu+a=5f zMv&vwB9|Jj*^gS}oB`iz<-tK4^sa2rV*DH)^5LVH4YqKY`KrT)pL6Iln&3En9BI~X za`LnSve8vP{UQgsPP$EdSVp^P0V$x&a5xaem~#PL>npBNut5(WpV#LDGdN-n54<4} zKt#q(0kpf;jISYUeNBKu5yi)q9#*|eKwfS3Kt+v=a$83Yy$a69Y4Nwa}#O8vU{1PSC;_L1zQm{InUFP z|JC9CvI$UaeJ!;++m1f?9w5_p8I>YpWl1zvUQpjZ-*~mkIs!u@nV@k#Qd$d->R3XG zx7`FPp}Z8DUBHeOg_&fWcF3dukEDI#1oD8Sy*l;`;KK5KCHSIp!UPAD05!r=5b0Jm zVY&sGsT-7|5Yo1NjZ} z|EBN;bIv8VauO;R)vag)`y;;V}8BRSWsM=i#u8}|A&YJ;4B{JO&jF7d@f6s;z1 zdNqCQlZp|np?A149X=`>=@bH{PA%EaByzE;j{TDMC7l4Dao7;P#4kNta=f$~2 z-0WVCn+^RQ6{&m>1EGk+U~21sS-ajgrTrm8`(3sN{gjD)E~tYhcQMQ?mn}&#-QDYgo*OEgU=m% zZ^A5FY_|hp=NiOj?l}3UDwCfVmE!)|F4UD;5?T^PUM`B4ujYmE(L?IZ`^l|(f)1bBzI{6{sSIM89JLy5d`+o$htqN0xlzcGu|TkGH4Q9w@bG7) zt^&-MUOL$Q*2NaF2VRk*SXh{8{Yrhin*g6;g||^K@!$&}hQF1tnj5j$U5}nJ*t@7! z_nE_g4(chNHgv_7KI)>I7)I`l<+~U`vzBYF#^cr90-PVhfpJr2sE>R?LPGT`z_~4- zITdjPoST9`0&0yq<-1u!6Td2HRLZhmb+`XkDWa}Ink0G{EWQb z8H#_?#g%|)v@_?EZP9aO6|Yas`}-PstRauRKy>{q_Gs-=FUp42Y#VA>;;+5wbQG!IS4t0ClxZI@**-;*YzbKGDo8H(sqo2VcIjE< z=jAD>s3apeAEX#O=MmNn&JyBfX5&8|c?8UIAC9;lF4ZAz#oD+;s6f#yiP*d?Dg~+s zT4v)bTs_#iuZNX}ZisaHZ!+(1pFSmG<#4n<6_2V7TPUP*kndpLH7*qq?!Ef`r>*wf z*{?6;8AY<216Z=TtuO1GIGh|8v7W3TU&1M~*zr>$CiQ95KI%fWAQubBJGmY$DuUtV z{wvL62u{hs;8$LYEp_Ea7TS9|o-0Ros0!b8w6Ry?d4e~Cd}MOIXP;COzGT;JWN25B zsKD8emiTmgjfH~&i4D}7CDZzJCr^F?Zeu!_gn8*{z$tLhF)3YJ;UMU@XJoS@tGrm{ z&KsXr{a5WEo9?)b7G=?_PDNK^vHM*8TQ&(wx6*Lh6F}UKx@&(#cJ6uCNn5TFO2pvf zevS`)>h5n&^HlZe7io+1?AP!DD)TeoN>%+ra$pzh+cS9Z zgl;F_O2bENrV6BRIY6`{SA@{Di`yh=%3W)VRHWMAiFtH`BRS?4O?Pcg5mVik&sB@W zkx}W`*4oT+IXQgdT!z==Lt`^u8AB}zS2Ag|@NAh}4*1mkh~(UIuoKs?NUBEl5Xys(eJIkX%D-B<58K8KjEgIm z{KFlv$>^A*8|x3~DmK3m6EfE^{_8-FN3ub|*7FTPP5;sO0i91EqQX*wb#WDhcw+O%jGxo3K5y`k&%c) z^YB!zQ9o#UXNF9LH$UoHP?NTqGAPjvbltp(eb!Y|IQB1&Tvz2;alM6Gol5G(NBTkP z?@9OUzcfbCAC1*}VZvDC@Wg>pindgC1VPLFH&dG@oQl+cE8LVU`8DF+)|#GVBH$Xt zo7eM&5*0H2I%j9MUS@*pAE3@Nl5s|By@ctFFV0)VFs0BxYsIYXch}peG9r#D_}qy4 zoeJFV^w?Z?zNfe_+No$kFqDtS@?TRj1ZdIZ|v{6>#zvg zp7sPc-dYchJ+vQ-{s?&a2lisqE~5tx8f_j<7(1)uML<7syYAy^{bwFvbt zdzr{2N44;@k_=b09BjeKT zjm4(Dt;}q48SYN8DV!7lWTNoT%g9=c!Cr)Wb>?CbBDV5s(K$QC^2a)u2+DmZt!nlZ z`S3fdh>C0xO63ak|80EC)+=%%-+9qNl7ds3WU7z@-W#TosW-6NAwhelPNV-72;HkFALkXLNplvaqdH#;I6Uv zic#Wr?~rW)PPuUdZ9c@f-vDjmZb48<8F04X{!s*N7^n`%YCUv0tU4%lQ>zbl#!sdE zi*qV)(2i$mm6`$Ci8!IDxr~tXw1LeP)Ykf$g`3mr0RuE^NbeC5$g+iTq|vcuJtOtJtySH_i>ROCy6lM9gkA&m`%n4^OOjz@s9)e@ZvT?F$1_Ns3p zf!G!h_9`BHJ6b-SQJDY0=IAgm+qezuK>bqLyY^RV<_#y?T!x9grkV++;WKDH2B*2| z57Ym-Cr+VooJ`n=yb>}ss_;=)S2CWBeiw0+ z=DeAVKUmdP%U|2eR@Trn60zGo?C8y))v&SG9Z)I?8=_f~svP)oPmo)jUoF<8%E(@5 z(NY`y{?sHqfN@YhRaLUe*p5FV2_D!1?vxMu9F9z7dv0gC(4|wevLeVp^>n4=hRtg? z>fat7GEMUYK37{O_^5CNN}c-BQ@sD>xVAM{t$TP7K-6vaJE!G8pmS20C=9~5W zyZ<(q;KplwR*Eev+_cHN$fN(;6>jMc!FH<|Vq+1Hw!6xi{T0DrP`bAfK0VSt6SMEKOW zK30Sogr;j$Zg*TbMX0pJT?L(S@ulO2oKj~UVOx&5b?ly~dOvaarKDiQky-EKGtiVe zV;;hwZ|G6bYGR5_T=1$>Qi#JI_7!c)X(PQeuIE<&FT-sr#TDrF-$X1dwAG(It?BKf zHdooPmby-)x8#?YcCp)NTZg?R;YANhxc(DzWpu96@MNOATCKZ&Q>aGeIkz~4%Hcg4?o_nslgd@M@=bjvEq5101%1_DyMOIr%qWQWtxJ#b5XbL4TNId;rSEAr+`KtCz9{tQx7iP+ zYZO|rKjIai#rV5hfCvlr-v}t}%rx~ykjQ=R$~(rEJwzZ` z&`Gute*Emll$VVem4-94rw%zUPi(GqTbRovUu+zo=*!gjovzi?P#T94w@N2$hyoz0 z3nZ|0Ot=wQJHMy5LF8eB^T#s-?6s*eNdY!>Wn3x7#5m!GS~`6i)4KHbx*bN}&!oZ= zuWcLT;Nwu$Y}(IO552RhaS^1>AnLg4a7pP1jr83~4B_aTIv$=XNokc6zTOnxTy3-< zvQ~!n_L)Wi2bbKs{&_6PVIgzMG@gUH*iKtpzZZEhCuGl>O$juS8jnpbUR`#xN=0|}d{dNoS$_5kd-FSR07lFnLQ89+^5 zDohZ5@H8^i%toIh8^tLn9Kms-i8HbYzNm%;;`oVq(M{QL&5UrNin6fCzQN}VD(dVP zp@9i)0Q7x!1>e?5EDbugFZ^cn9wx$)dh``BRtUSfjZGkWdgU_61g_Bz%lL28WnqhO zJ{!o~J0KkQA6=I;A4n8a{G*ZmRX=q0Ir17C1nD{sN)h8Qm|&klBr90{7zGk*ESl^W zzYBP&BNzIjAujSp1!~%mD>IhdVBc~2=1m}OrT2vkTn);K#-!t(zy&M4OTt*on%()B zv2Kp03`(nPKCmCl>_x^#S=o!(s8nI3gwUam9-gJ_PhI?#*{P}QB_r^+uL$7mChXB) zK=0!?ty+Fpb$9TErtTejA9K%)-@@yPvI7YLrmZ1^y`us~CljwKP%Z)L^yyo8TtCA% zGyU6(lMk~%;{qID2`+L$8n%NktMk^P!N=c|`jx&n!%SuTA*}G!${)Z}M?s?Y+)M3p zEHi>`g<2)fKC~AcSgYr|*ApnN)n?kIYlx!7qXd(<6!``ZY~$*_eqH^5S>iZ<<@a5#q?%hHF4ah9bbISoct#mGy?ZYVyU z$oV8}I9AV%*P?$c$5I$61MTy6-QU_oZJCD2Y`u~?TVHJ2XGMk&$ER z`CCfn5sg&G)|V1{c&*IE8=5sCA4|Dj`mF2qVgoNmXypyLJVgaR%nWbnkmr-=K7tPf zE%QY_W1f4tNGAq{XzfnHl>orYHOkRhw+aw_5&l$+6+VHn@Ng^``qR z(&AX4j5TE3%@@EDL-vu<4IVn)Ml8l?xKPi2PhjGrb`EC@yy8K(W-{RA2L+s?+ zydRGW3)#}2rj&c*h5FO1xG<}si|erlJnSsJShtHbj)>270Uk~3C~Og+atn&sINE@! ziEQ!{ihin`r-xkTb@<^RcQYXHPdV>K2^By{UU?bKV&h|_zZx4PL^wR4(7HDPtGtO? zC`=@{MQ-Z|Vx}IMcL89j=iS#kOS^m<)-ZK&@T??%8Str5R?vQ8{_-5^G%+C-E|a{} zHt|i&uAyx(q9Z!vVs-a2cYh%2t;f#bqd#^kqOq5ozWL){@=2S_*c&S}tQG*lVLbcU zEveI<#W(Z5oPP{9+mOgJcjg->=4TTP?e|t-EvC&03H`RP?oYPQX7gUcjMblw1K5m5 zY=VW6=EnU81^8h5cM*||q*Vb4L)TPfufs(6_o`Aiid~&*nVOeO^%=1JsQw?TR{?N4 zz1k@328dJ`@GGO*>;Pk}Aadp{VI?W$MF;!VV4gH;Ic`JJ^dxS(#9@=PDvk>+Q&glhe~jJLt|PQiAj;7i%2Zx7kT z@HJnVwXDpxe9A)Lpc=#*Yj5xUHfPH9+BqhZF0S-N_U57UH}6@d*ij!qe4fv67@D!* z8pr>N&nkcc{=D2=#8(go+wIb5j)0HSd~ZA*zu3Bz#tZ7;{bC9$EP5IZxfzuh>6{3_ zk1t8@%mQ*h74N zo72?1G73-+w`gX10#~`0dk(sdp1EhtHdd^vX3jYg7WDP>=w!O?Ila?80<6WYb+wX% z0j5y-%v=AcXO^lyQxCW*^rPJrU^&G|KW+8T12O6;f;fO?ehhVL*&W~FDruImfpFtmnkMy?6ijKTE%Z?hI5FIj zZUJK5@9=A7-hkoQwR@4wS3soLSsS&J;!OQ!g6rP0L;5i#!rPQfL>_6hWQ(YkPo(}S z|ET&Bh`;1J_>wvPF(;~)%csNEUg9gY=XRmM1v>@MH{;|5OTyK(nX%kSNu)T6q%_OF#yN;OsDNm)e3)AQJ-5hV0H2+K{qB#CvpnxTRT=MDu8>(B z63X7JqPF%gwgDF90_QaeVNJP7 z$_~(z)Y4prvhg+PV8Q}kfQaZTft935;2*an%4Al*Z>so53LF-1a}F8-imr%K7TNak zr)R#keqU2&+8oVuYaoxOH{Ekgn5m zK_^12%sjdAMHOdl2D9ZpTypm;jcj`y;%Ptn|Dk_+SQj@#FVWoB0TzHeC zZ9@yGW_-*uEcr7uMFohKE6YkqTbj+^o^#B3bj1p0Al+tMQajA1Ch|6&M1PzeM$lqV z8pV?AV$=W-=8Frv60FtG{F##yIpW&qXqMOP`&Bm)X{ipW(H-Cr^z}VyjK5g{mst8x1{zAVgZ1he_w7I4HFv2C4p`(L7i3~D z085aA8;9RyY~t~si00YX ztFDLQ^?KI+x|Dd$v!8ghJm)nrVjtL571M0{Z1LD6yzlM5ID8cZ8|^L)^fL7lKPBBv z*F31I)-7v+WNN@q?4zZ}Q@DrQqqvm9VD=%)22XI1Nx5I5Z+rw(^hgAfZ4=!XthOAg z%z*{}dI{-28|wgER2!$jB_rB{CKmp2UjAnjp2)vvf??bpo*HSTeC6A?2^>jgkd1i0 zU^$962_b?Z(jnqQNWZ$9Bs0riBlbbLH8Dl|nyuOHAxa=CGfErIj`J>Oy#{3q_`KqU z7)js#v9AtVlUbYl6q0AGWUm-tiC3Hwva}io4`1(kbDhn9I|xLnO5hHPNQMeB=-mXO z#5sX0XkB+7n<^k+934m$88fx#;8x%h(ve=UuG{#*?OCQ4!9+4O>u6_b(JQsJOMtNH z6!TD%eKalTx*KD}+Xijk3|vGkrP**V7&9svspjggp)oh1(W9z=OfUvHIlF#cb>Gj0M~uvf3Zuk8j>Q z6@iijr>*^P{ObvD0haIJ4w=rohp-x%diG6HxD_%?^dDN!t}f%@m?WRXLZYJ&NWU z&o+;5a^%I0-PbT$@f46hr!`jsgR+AbnfBwbVU&k5$p}u`8^{J4NKP&V0$*IX_S;B$ zdEXwi1Ds1dYB7~V&E!yc8fYokR)#IVu3&IBR4+92VMR%xKWp(laR~@V zPLVT%hj*|6lx<#+Jn=k88xztMbG}pQAh$Yx_vIob@`*Q)0gx{NF_#XJ%Y^3ug)%nA z{WljJw|Dtr-$ zV7c)gB!_S0>|OiqrYFKQx8$z{*`R8F5(dt0AJX~3MkC*2ioic0gGLQ?7TV$aP554| za70i@^GndSo1uKjOkBsr%vA9S_3d!jqT}-$N)`da=pe0W44R^vHbF7J?4AOI*dK7o})65Wdpz zWlM!kf&N^Kav;VVs=1{CWc-Z5+&0SDG+97@Xamz0te?w(OP}fe@R)m@9t1vEJX@CC zx)xqAx-1YQaN#Wl4S#et&GrZ<9YGoE_TLoPG!Bnl>jlR${e+Vf$*Bav=Zm?Nk^K+F zYSv>T86X9tQR4;A&7`+E5AYoQj-qatg?7t6#(80t+Prf-JV7KQJ2U)Y+p`0fx!a)+ zP?JAi9?Auv%QhNAV2SRaWgz3HXK?yX&f9oY1Ie4%b{S+KP5USHj0m#y=>je}3TeIf z?!y4St;LK#Ur=`y>ggNdUzcy=AU(g%PK=qfZR!=9?r1p$|{Q`_WrHvN8|5fcjz zW@V#^x9KD;r2f7$9?4DKrw*MB6Vl7 znv%CZrq3uNEVPna-C=Y7$Gd?A{3H7qa~|;AGg%3a4!C5Dc0u+Zh&bT ztoGvOiQEr|yw%?*3I$##URlT>GPPb#s{u!N{;Fvia(O_`vcO!A8Yi=xUoM#x-)@?$ zCxXhOh_yNFQY1&hNi8_BYs0Q3XNH$d-PE+TA9fUgeWi@b1cA}=sa(d5mHfQin!1-F zOk$!ySa9g)7g;$&Oa|n7+edd+8q;^DaC0Z$2%Y)0J&Jb!_}fWQW8*!xXmS`)!i7Z? zWKNnv<0Q`aU;o9E+S=N@XB)OBgAiU<76yydqn$v|v|A2r8#(&$iEjCnd;E=fkViF7 zmOLhRaQ6G|fjCt&fE?-5;^INogmJibpL$(b6h!E4-X#YY_^;`JpXRPUslWbGJm#13 z3XoDv;7%$viL{BaQdpukNqL7&B+6rUhTe@sc(kB|yrl8> zHn45_I;23-Cpz-b16e2tQP$Kk|BC-|GS;%KE18p5g!oQtS$Fk0Df8`9^=!VgZdxRh zJ4FT|Xl9X%v2$NdOC}{sPk>fDojF9Rd;@BA*U~6!;PU`a(YF07(sF?$$CnB;`O#wX zt7LvgBvY0~Lv zNDc&GD5*z}*5@}eVn@3otaS_xV$mjmCNs4*&gIM0EAccYLwi?)!vPQMr3_@LxLUgR zC%e6`lzA{HRHT?DV$`N*Opys*Le?R`P&MzB0ZVU>+hEWP#wM|(sdIX4#0OED>WRA{ z|GyXdCEsW)HVAF0&Mxx++qDJcj@pylBvo%t^zN+$$|tEE`aa1&i5R)I18J9h2F=jH zBo@(?#5qy-reEnZ)#%!N@6D#Yd?1P>TL@R)!`8k4pe4^K(Em8|L&qZ}GTwM|>dD2G z13-IL1-+T72ucnkM>uf-;hu_)Z9@97PDe^CDJ-ql{fn8RuuQjdK?q(s@h)m(SUkV9 zGJ#A{i&G!2?C+2BgV^o(LRGDfxXY9~ZhiHh32iuS$_N;_s)Nv%-M8Y34lOIH<5RAF zY%Wai*DT15tVdF}1dO6gdgVG2j>9{SyP-oKvj#i5ru;Z%e2FH;wRt>xhPKJR(Evevcj;IpQs|sBHqOpBVJ7 zR8)62qR7NGx24hd@``krL}7Me$NtarFXb&ED*)?IK0_BI$d_ijHEt+LC|mAsRGqoe zfMKQUP_eC+w8rn$-`n8A7Ke}&1y5&;NPhOId1v4L=1XZew1AwsN2w4+AjK$2HOqA&}_W1VAoLttOFBMy?^J41t9gRLp;v*rE@5bEJ?w z@vzyGO;2FxdK5x&nV<@xcpwRg5_5XiyMZ{U{mQMcMYwDQb$Ri_;i$WUq%8nKeZ1Tv z#kMNz>zGF$@lvIw*4>3pVbh6x!(Uj24j%N<)t)^2tHH3)?a*`L-(59sYTYA7%5O3r1 zKh%6SZKDVFu8^cfEFl+gEr7F9WELtRZxI;bXX4AIR$Xtmt^svhGZx{*D&A4inGQzr z$};K2A|9sQKRGOokoW}Ti5r)o$@F9)@2bjSW09~}kNM+`v&gBLyhlX)-Ad%J-XiCB zkg$+!SP?2B^Gh&73o|=w$OV?jMQdeE2|WV?#4Y5{IKBO?T7K}~bOE%G8B!LwYtnh%lhaBnxqHMn1x<~Q*t9kBvnddm%=N6cQr=D9|!*%@8v_@Vjt8fT+~C%OI?S zXC@?EcbaKyUBM9dTEYd`DKGQ3fC9NOuPHB^wMGaHhTMKySct8X;Uzx=WM*_a>;~a6Gw_k0DS9a z4^YbbFlA-|Fb;I6jz3GM+>FXyTwSLLVQstx`{m#y*hWsyAm84SSjFLXm&kd;DH%kV zzuGuADwkZHxi5+8uPKZ0p0GJNL)1qb+IpKvYtRw#%_p4(Uuf+1Y5Riu$!d=GK@WUl z0Mv2yk$z7*m4YB3LCLv@A^Y01?b;Kxdh zT!y<%6`M(Xj~@BkNrLH|?M>H)WxMedrL^i+Rn5OYF6Y?y`SE%hcJXoV49S?oF5R+t zfHfb82y7nxTw$fj@2RsJjsFH@CF_+=RIR{pPQei+8R;JuSaf2DRY>&6ULah-7J`r+ z`PK(_MShn!81q)`{DFS96)Xj(5s#Uv2&?QyP)`ov#oY$2B(>l3T#ZiX;f>0e+^kFl zp)f!aZ^2u!`XdUAZulLCXOf%o)KkmlE6ZsJHt=GDUx2-irMpwG&+Oco=^J)A0^!~y zOO8@t@c4K?aDz5dHw@^39LqN^g46)}iuhHGQ_Hf3x%U#@15#y^DM&c5N5PA2;wvrM z=FuT*6Ad#_PHl~u+WB3bow=>AM@*|HY4ktw8g}qCG~F(GXNboKv<2g-(Lt4Za37hQUsc( zdcEqmSN73moj2@GpOD6*r@{DTVWbqOtHx^>;I^A@` zybWgyvuxXo&+WGaAXaNAc2|87QTlGfLM-?W-}Rk|0Jp(d$e|7**M=MGa+dIVgm3HR z9XFaI2h(G+(pW({icBxUe3mppT8tGr8q8f$SiwtZ`4Ufp7C>`C))L0K0cQHR^*{l~ zWdnDk6wVgNT=_|FPq>u=R_wy z2=IGtE!q+Uz#4nX5VMb3UkcL@5r-tWz)bs>0OtVmtN(C$bHd#2rBAaTF- z`tCBMa}nK3O`Ezzf>m(~K(pHKZ7$>3nbs(oawBJ7jo-vsv=aZEf-T@z2fi%RE@OFA zMl-vZ#L#T=(E7x`=LLl=z5iT{{k6Zl5$hzqP1jz$xi`~X1@+)yZzYznJ&F)8Z)*W- zKSnNy&GgUDcWGH!OOC~$?w$!KIjCI#u19Z+js#^-`L>7M44HwA1yeRBT3O^uv(t`Q z4reLfUvGATI%i|&r7OAiPT8a>m_vUVpjN5N606-NOBZ|Fu_B?^*GpYRNpQQ}>7`OP z;M_&+;LnO7FeR4-h5=ZLyiLNOdiC&(O6J6aL?m1rnqoZH%*=2X}TrK{>LfN z@mCieL5X|wo>bK&S4L4slZPJ}!%^GABJ8o=>nxax%1StR6xx@LwP!^plOt`L1`4f+ zI~#*|)c)KxdoM39-m=-RdY*Ghqzw^(S~R8;v`|SS09Uw!ptQXyjOaMJ`f+R5P*NSJ z+gOytKf5vJdy$i}uvGa+HtXqpfNj>7SXhe;8YP%J?jtU>&$Ay)^?J>09nZ*fw^0Z) z56iS_%_ZLEg0dQ-b9EEt@sJa%`KZy|eLSvMH}{$J$iY_e%xpry!NmGXEMJ4|Lc<#> zrU-#{34t(uS8dH~z3|`p<}>>n?d@qPF*^A5l?^bPt-yh9e5Xd=($aU)09E%w%9qQy zVh=V`1VE<|Td4R^T>$q61_staxm!sAvzA|=25N3C8Y+WAXnMS@iO|K41=djY4V8&P zly&@vfGCOUE23zf6FvA6XcoX(oFyk6$H~3s#2wFW>23OwH1tD|R)PWS^IzV`BGqGrdZ(;Vu=PIR6-*`15ohYZpakOcm=7rzaWxw*cXKus#SQi$Q zCf0?9Mqe6R^vw9K_0uEgr6Zgl+_O7%?w%YQJiKLv8ngPAHK;`tD$mothikHG9olw@ zwyP1kC5kPjX6e(lt4soxnoCqv^pjx|2P2iQCvH9oL6}q4DR<2(vK!5AV8Q5tlAz+d zE>Zn%f2{VVX7;w0x}n0coe45l4Ii1F?~|_7ja%aowX75_%r9k34N4l^P}eqHna+yI zx^OlLtQ*qj-`jXqU3bn+f=h%n#!LIRwy z8sfjO6B1v9Z6ek;Hk8GWYjq)0Cbw2b4Rb2i{XiAS&H0QRQXN=O0{AFhbsJd3DPAj; zT3ni$9eCV=kZIGU8*FSbjz_<#6FN4+4AE)DBc5EJ)}YqJIi#fr%74_&v4j8AqwQ(L z6LyQd64@Wn9oE8w!EUA3%Fbyi53U4-nO4hudiM`yC&gvw+};U{hzz9V)k|$)_EH1@Gnnr3*Qwchofq!&m+ZY$% zuH3;Rr4Q-%5`#N_=oLL|TZVmO%^E_fGj&g#O(d^|RZs-)xtL@5ux01h*UMFVwvS>Y zv~zQFpMRVbx&H7&$J_JQ3p{a_ge5ynH>gega{j^7;=wFXHr}fC%~_}xFjU4AR4qlW zj8uwwZl?PA`KjyaW&Zi|?Dgx{9Gsl;a&mH(eVO4p#o(CIa2cpZIzlhzoEjJuL_wHR zx7uBw!h^EWf|vtu!fGwGW2v6d^4YUzHMWr5no%LWRN zpg*Ub6Mg2oQv%G|W3mdZu=7=W%iTX-Q!-4QTU{P5FLa($9$3UNltO8^1S7%m%)% zr?h^`5ebd!H=~!#UW>PJbKNrABVIY#W%HaYY)}|Ue|6?6@;jl6+G%OK%%ZGk=ENRK z#au(f_K}B`KkdGK2gnD*Bdomb{+2d`#ThU-h84KIE+9~Pp&UgN4EMFmR!<3((w7Q9 zGVbB$(D~hG70-%!uRRgwOJKKTzIW>wzjtCpLguRQBjPuH*sC5stE;Vt@H#uwwlWM z()B9*JeR4t`QDVyjT<*2ZX3T5bDoU@z3$}0N*J|8iOyqlVyh1DRtc!fdxp3Slh*!0n7`+BXBWueKlB&slcl&?9Rk)%V9`E z^#q|HR?ukOZo#ZKrEF*i&*Ut|;b*evlD;#kwHzn!0{}0S7{aK8rIq8BfN7{@Y_8YL(J8YKn4W!}c<|L^S|<}XVFp-S2dMT53MgEkYq zI5GS3;WAvGF0P)zZf6s+w^A<)H>~mrKfWfeTI9pWJJ+LStb0@HWa#Ao{`^00HTUR&VrEa)2mmnZVCuIjuvxK z170yCI5_dut7A70!NAnWn&B3b(Zx_+1P{U=XDJ|3?&9n_oy zN4<68)6W+Sx4nwdjoLbCyej(To|Dm`ULR%yd3|e*ZjlaFgNLtNc__hZx|y%38(}A`a8B-Bz9fuWuGy6y zO};S`=0golF>#c*-%h;A&Mu=6#@h=PN=jR_IK#q{{T*mgSxq&CSoWreG*p_JntD!t zmieIPwlUob*_H-4#Yw833XhH8FJERgRuU6gQ6Odz+gr?sFMDnMHpc<}$+H*AHCYri zoo?B-c8l4Kxzl>mDqrYNV-60V2M_fsu)L6kye>|!Na7j6qyK#Q_Rn0zcA^2+!>}1t zIBUI-VBO2oB(fhzk|@DoEYHBoI;f`PEs>g=o0F`32sRB4hc)DqlpL9;avSlGQA)vG zOj2^+8TZuy)^fr#i0#oP2-i5-*y`1YpyoF)`(E<$^63uBrlv^;z;f!$L&#lFEZJ@r zDWE>@9se6Na~>|^(!RGa#htagqE#sOKA?vZyQTWfx#T+(g+d=6A3x+Z{q?9z;bZzt z6g8pIo!3+yJ{yHDY@BXBlY9tKcz`pjX&)%E$?#=C_fN!p{d$c@ucV{T#dUcojd-wK z&ActK{_A>SjI3T{UzRQwkE_LknYXSNZ{}+u6o_``0CJX}a-D}1DMCxhS4j*iZ zX=s-6Y|FlT-|?foy_b&X;$fL@@Qoe@oAxzZ;(^9#KE!e)x4+(lCvV&4f}fSf9C-@8 z5ty7?VA{cj9$CelqN2YiVs0pe_LtRvpc9yMEVa~I>Ca7IQ;xA-pl4SM=a&WxFvDSZ z%5e@DVi89k@cp>ETwJ%hQ`-Hzf~VB(Q3?=L5?uB^a_zal%VKWV@77&YjoK%PEx@z> znn0U=gQBWhBWt57aHx+(iY}A6BrfB^*Uadn6=+PAt;dGfQWF<{)FEJpYRq4O{iv;l zAe84&zG*XUGeMs>Yy`b$6X3O6v7z+(O@t^1H#fH;U;sBt%=)W9pO;RzH=7d zf(>n0&b_EsFpdpoLvasR>z2(TIR^G3-;Gt?(4`(+{!Gh)yh6J13;M>0pZsPSYek-{ z`I47LxXcpMg>xTtgx+;-o~pcb8ENy+PCg42a-d|IF-c+_O9<~cLg z$@3@XW%yI~-k(%q&q76yrt6Jc zWsdlaK^l=qt$I|}##g?xaXLT#;oe7D(7MobrvImPdADHR_X1FMoJ9rGd)_LQM*3Zw zQ~EPH*?c*fT`xC;k-f_ae=9qGfojSgllAm0YruhJ)?A6e&t4B$FmCv$;q6^9b|v4=;g z;iz>>OUve9;S1G!FJ>ZljGsN@-ac4w=7VPkFp2j$t_4bJ(#98mLNurD>RTPn&Wdb~WkMT(G#D|1;04hc!B^xB@^S(`ZG@guHw zTm_hd(HsUvM<*wEc1mL6lXWgz47Eg_`FSLd)8PmLY(AxfZJj_-|OMn{azj6p%;1 zo7^0g>h~y7xoDu1{eypjy8iT8huOJPl|9!u2A=Yhh6>DfWlyGW*7|Dth1cpDshq4s zDsf|-+_#%t0{|#E5lDXO%jFBRFsW}kMb_bm-hCdx2?>v`m3P#0DUaPL){YRLe0%!5 z0S6qv&U`rlr~wOLxQlvF(6H;kfuqfP(DxzH9EGY6=l zY~rK1p!2K>nDfQSnw*roL$TB+_V5%3xpt$HsJ*3Pp={sRuaT3#K8Jed=oYt4;KR*h zkZE@MxW(Vy6JiuKpl$zfo)qrS2>5gCDMq(&FSUrV03Fm@aGnV_I!dKhOuIjFIH^)9 zbhqj>MJa0f?l4kCV}FlOh;E$zi`sD)0cvNNnwePuBoj8jT`~h$tH&oWNf9SeojXH- zhJ)h9>;M*o0gq0>w;r#BzAR>}xa*fpg(U<6lhS~h<$m|kNaDmiLSSU zj=L1yS@@QPzsmIZ(uF^%sO#VX=o9BKx6P2Y@uYdm+@v~dwdvl==Pw$Tu8XB3tzS*y z?TV(5E1#ded`Et`1;Dh`puoTj{!HSU3ZdMhrmMwecSq-yD7LUCy;tT^V*8>*ohm_3MG^^oR z+NDoBG}~cy>@I-P?nA~nlkqak-+4(5I1txQO;6)VRrgf*GSRIDDC>wGWWnc~spUgQ z7w!+{o{zVT`Pb$anGpd)dG}O6=tD_XeMGyO$E%Dd`o(RZ`l^lZJed$lH1?CM-eB}! zj4(^9%FL6eM(w<;8u9G6Kio(QKaMiN{y8z~z2R@x7Nxy3mXp|R5b*Y`N{Ui+PnNET z%WTKpwY4?B_wOHDTXUyu3QK`SiwA5s&KI$NH&VoItHf<{w$pR<`$--{E_U{mJ~*&A z`9syb^IZr4)sV=(5o;)=GhexW4cTUbY;M@X>uvFIB)%jXnVi7zdd{d`KTK~?Q$u}7aq2HR~<4>bgQ*CRAWzhHR5vskxmVb}$~ z{CwQ+Og=h-RNfQj!%-n{Z0CFXNimGa{K`8lVEF)5uJ-85t-Fwev9`_}b^5^^)_fzS zJMG1bqaX;i8ZL9usq`!ahAE|@qC#gu#-BckT5?Bfe0)4q0FcT*Cp_=ndjSFhp6#6X zv$Ga;b#-aqzJ05Q7fz9)=mO=HLXmxjNH+bQS3O3rN)=asX-xHDLRUJ8XnaDJq}G;= z=}pq@2!S=Ca_70KkgOloJ? z$o>jQ*`L-lfUv#5r163%;*xl`;u&1X-?edC56uy1D{)5Sly=s%>viP?UbwMYnVx*qvuwtsesCpAx_ z+Oye~$1invgdJufy92%|Xe~r=V}zZPAoXw1t{Oh&=jhw<2hYKEl2hI z6Y6Lj#hTBg9QDD!t{#O+)v9Qiu8a!i^t%naEX5G)z3=Rv!dZI9?OJax1>6&l3S|^PR4>s&IJDuXovVQND0e=Jnd;7c1 ze^4=3G^(T4qFQ~1`r)3CS^QPClm`ndqvBkP#C`G_t2qXsHH*0YSWP29GFR*^Ez_Zl zuGE8jFbz%3`EF%IZ&vY0I#};kLnRJ6Ro|Uw(d3Rof!tK-OC3zMP7dc=VRt znB3c2=g7%|)Y?~@ZCIZHU!1r$Qw#@R{T9-}KIV64#QEh2dU`JT;qlho13hHf<0S8^IwY= zs8C|yGMFncxd(UE0hFtrgkHAK@wE$?At^Gh2(_!hMl$jyTTj+a;=a(|@S~%qah6{Cfyu?_o*rlzLO@{<2R_C;pf>61_}EQPv&G=}Yf(PWZeMBX|(|21xC ziGol&F&b;)^0`a4lfIbY)bY^S4#GVM&H;NPOpsz~jE4WPOrM`DPEBRdExo zhS+9((Yax|DYb{0pXPG7X)#~5A{U>1IfF72enz~wIpsR#Yc=Sl4*ml?( z9nB=}nwpupSb)8M?;fD|S2h+B(43r{>06u2pFW+dt6%TF4)dY&u3oGB=6BR(bS*w< zAa9k`Msz~5PMVED>2-v9>99`3MA!EV?HISTN7b~S{Q_o|gvO3R_G16}3do3H#vn7o zs^zVm^@x}f!Mtn0AycjO{-vSLa>%7Q%_of8U)&R9DxC85d|4hzK{Vsygo;QQRm%cb|9@}}> z(k&+U!S`#=bYskHb&N_6p62TEl;Iv@r%!=6&$zHia*{)7VNBXbuf*_UtLZfS^c zp8XUXbfx3XS%zewRhk9)+Vzs0Z{Jh^?VaiJwn)su!GRf@;dQa$^6As3C9<)h(CGq; zTYc4Bt*pM~xe<-(km(dyB5ITeB59#gh0# zS{3FK=hOz*8JxJfvOr6G#MvYeoAO!UHmqVsHupIzxv?WgkPU*oBvk`3`kzVrJCm;E zg%+J(VafNdfMf^Q=Z|Ni-C`P0pt)Lda__V%BZYC^j{R#B2Og&_(CDfL+<+qlBF_GJ zvz_F3Z2@=t(T$Vrzwq4+3{?H;n3d4yW$A|C`a3ev02kRg)w^w0&92hUl~#3?X$KD4 zNUC4&Wfi`c6I^RHXyvQ?=?#|W2IfKFE($DyZ>e4db(RNhCkGXZ>i(7pyf3__JTV_b+bZig~ zjdm4eQci-v)U7ZFvC$%cR(gS-{2hx7(`)8VhzoRfLWdCw+Fey?%3>oe2zx}ak2CM4@S|h}Lt| zkRGgA0f=CKtV@AUBUTcngkC1i7H(_M&Z;+Ed+@l5oo6BZ-aY~Mqi^IX)N!k_9u4Rt?``4q@ z@P+u+Y4c^@3>B_0=T*FpEkkA=pm)O^pWJcYeRWGGvZH@Uc)!EGjkMYxhGn?d0myhldS zLE#kSW9eW0xxVF9z+zi{a^Cv!$I9nR8)7N{Wff|a!AMCyz|1_mF8ZSGI7pMVt(-{H z-8iOz+r2?kwovJUx0Q(*Hz5yguQ3$X#lXGhS%^EnASsv_t8^qZu{Bb}YOz0;lb4su zMBc8F!Ux zE-j-?ZR4lK%QW)1z+j(Ff6Y1@AET~$rIfSv)v0Sn@mIxC9;Z*?YuosFMol-2a>-AU ze5g63dMmtN16rhBjV1t@8TH)icPPi)c$Bx51jD9X6dqrHH#?6WoBmf z0Nudf?RPe2BW@F4*Jl}t`((TSKz_ke_+q+{7YBXaH-P^ZsgXFj49mc>!khFyZ z8o8;ZrN;%Up8`ZJT;k&5HOO%*fbE&F#>U2#^H>nsNK5y62R<<}ir36BSkh=O(VHWa{<&J8Q?N*e`m9a zD`#h4>=VGJGY)XTTW6qERaNOF+`j=u!jp*@D1!uSW04kW;Sb0mZk9*_`X_)y*-BMv zM)0*(sd93C(;Qt9QM+kZx1-RucELt;wm=V&XqEa4h&|Wp8m-mHR_t)){4*n zk=~RgWCZIEY+<`C4_18cpVJCBkJq%AYI4sjYV=d2U@miA(uNp9;d0pmFPyO14W=aJ z%+c6S(a~8TPg^}D=D>NIqNWPmxt0YIJ?=x@+4|x+dod89c+zL4B|HIfuohsjoz)7$ zIKYe23pMSKE{CYrK6v45U0gWOAC&w|mth(ml-6BW_QPK0a*^ijF|T9s$hrU5aR zSxMAXYqVWqxCOJ8vv_;|zIgI{Ev|35S$vUOAc`z07;}aaRUtqh%4o3^S;; zrZCp!-8_?Z(WOi0EtiA`ULH@v&s^5kP_bM(W(4&M=2HfEpMQLSv7CdLGbrKdJlEBI z!Y+g17hy{38y{i}kyE)9(SW;p|IHIT964H5dE(5!V-D?rWLt1CRF3hOrVChjd6HUl zu*inYzOP0$@pJ5XLEgI6^lo%N6HGG4DI%Vg^n>7^p0=fbdPjntD*1*EUT;pDs;#MR z#M74w=&;Rye_y7ZjWHV+_IF>mLY3}*`kTfj`T`Q6U6Qc*7`K2`28&lrbWC^9hdqTT ztOP;JP;Tu%4($M8^K4hoB}YnRSL5e1#O%j>rVbFr7$UlIt)78-8J{-xRmoN8-$BZS#i`FoSHC;g@Xwm*ImIa#8yiYL;wpAxG4ejuwrT z9m&G2FyM8v5sTd2!Nq+R69?XZjUW04@ZmB*?w8G5I(dQS(xoWIeV03og;XPsc)N)S zXE7I$?(-VDNK2ax1Y`s2LfPfZVo6E8-p@3Es0R(ig1XB@r|nTpwY-9Ym7cP)G8UK` z^GO}hXep^nGru$Jtj6CFRtG>%T<}k<;ll9Bw)XO8#*5i0*<#I4|1ur0`D9Mkd)c4< zv8vOKm0uVYX1FPPW+gBi|g5fVmV$` zS2G@%-oz4Vfreq>eNLEs?|O=AmAaTh-QF>ssreMcnt3c zj$nu=K%_NK#6W~1(1{dfLp$l1`e*+mPi5ZrI0OT6lBVt5G~4Jx&4%|}+}pFk%qd!S z61qHh2vE`l`kcE$W3<-y9<%>T@6(l_&y2ZOlK%Yk$&)w=*!Q@K3O%UF zO-)ToRGXS2J6=Eduz>BNxqLYVWFb$yK#dh*4WLZEGgjXX3F&nLir3gYd5Ua@(-*SK zmAJIBH%s^=B=n&CueIUINAcy3_k2~UfJyHwF$Z!ih}LYA+_TQv<1?(%gFr_EJUl$S zkm?%LCtSoJ&s1iv0b-F_P5z{lhe}oht+lFwQFsX=v+-8YmD@8AAjnuII5b66j>h)|9IvSy62eD{+AWvjrrFRVbt$4>DB#&~6CI{vnYU6~@ z{11;G&6be({?H*_-BHo+(e2AOWfOl&_b=z}$$tJDBM^Pd>5s4gw!RA_MlG2RDuMXB z0NKrEGgP9AAuJfWfQ)`RIB{`?i2n^#jJOtob_<|!fO6&F5CRoyy^&qa@#kKOrC795 zYb?SLgj(tV(l7%Zx!74E6@#!MwZy7V$WCt=kOR8_(T4j_P;6`tnBXT^1Fx(i>)(GI zRseS@Wc1^hK9COp9ms0Q_JCDRFGyNdwn0=y59OYgLOXSV7J^Af1g#iUH zH97ff+&+r&fUrAe2a=iKXaJMG_gdZa5AQ5Z0H+J27ZH-EGFFc3*Y8J*yJ#owYtlNP+F+A z62Rqrv(_%){(AtZJ4-Jp3rxO-o?aAC2e~c{Bqb??SpqKBrOYghSAR1HLul>^gZj0j z)p#4Zbym&vT_OJ0gS2jogwHDZQ4>i;UV_RW_&@!H@-VNDY}@LQsQfIEn`W^7bSLo? z%jUZ&Q}~K|0JcLf^3et?mt+wTqCb`-?ylNdSfolG>=>VAk(7Wnj%5+{wylT<1jz-2 z`|49j;2^K4C^#a{%c~TN+6o71;&f;~mSI2u3&~xl7EH~|=79@(47xA{-Oel}m4((9 zGuVrbwz@Rf1C*kiSR@8kf)PizLq89Fp1VopmiHh(6u3MuJW(gpa^m#0i+ja=nKWKN zeo&xZjZ=wt{1}!htyXY|@UJ|1eGI5I`?H?p{wcr$fDh<++tMl8H<+t{{srWzK9Fas z1F1}Vc2IbD8aM=$4s?!^0ZL?kx+%upEYa~vlgnQ%bsr0Rlh^cOJ&~P$2Zpv{}*}GB=;wG*;R+M zmG$in{E?X3eclzwp2!)tYwbTYyWG0DJb7gP6Rmj~k}A z;E#25B0k3;kw{Mh4hykpu`$m`9gs#=O>*XAuXA)O()OhO&`63L-7#?LGt*rjx0l6~ ze9JgdU}brWbj=FXniCIh$cD9i(_G*TqJ>{W?J4Jnzj#1&eT17^y6=MfoyEOf;;gLozV`DX@FhW8i@y_q@=q10U(~?PQ4%fu z{SizC$ZtM|G8lb1hB-7`nzKLvttl%zb|4^u>|$LSDt!#(>?+u7eIDE_P-{VgJYdu3 zfGSQT>Kth0KcBwVf-rS^=VL?b-g$U~<>-@_2H|oMA}-(10tL~3fe{S$@1(u# z8c!w`gRAa3SZSR)b?v;-Rro;#W`T5mAR3r}= zOJHlEv^cMR*(^jS#|~r;Rt?HzhuSmuUWdqmfv3-*8$KL4HEl+BW#{? zP6ucLyu>dc05I}zfLb7Vq|$5Q1tqTvFl7{k8&Hd`)cJa*{0?^O+dT(d+5!3KmV)jc;>o%?B)h(xWlUI~LBCd%j8bW04-FU)$_3llsp?$inskJNcK2goY4isjkXd zDKeK5`80FZ^_`$;xZqf^nNz$@X`7lZE*i+Z4_gW1(T0dvWVKA=?LGL5PqpJ69?_3^ zuroCLnY z$GNlf9X(H>d#Okt?^G0SJJuuVW;;6Iic9xck)QuRh3dL`%UwKn=p20y={JwbzT)Y3 zh+7BZaur3zmd17_Du`VP<^QenRoc`n1veN1-=Iz#zE9S`8@efFo za^+v3Q`@=gOU2|2)T^}O@Py4>q#M^t&w zlgeAU0bLir{_O-pqrX7*Ly^V`cLqqwdK?N!e4ax7 ziyi8t=jN=#`o_f+7-Fm67!QCdQ;iAKtaFoo)*}|3Mv38!shSQRNuev>L=sV*;XG&l zcShxk597yJH1BzOWET1WrPd|}Ou4LOMV;YxtacuVGf2HtaRZwIeSwZH4WQ` z4!pZMrfXX&4GyQs!@8jbCv`60>8L$%RE~qG#q>L}ZyBELs1=gMj6Ahv_lvxT0ZC_I ze<$%va-XICR992D*~YQY{l9M2J$yAVpG$o5?(lF0c`#LhK?8Y;M4&WmUUF5yBme0K z>j)TGdIY*+eck;BM5)1cS`Su|0&I&l2R+|99~ibye@8lg9IQT{Ed8wDFFXe5^I|UT zNuL|Yg`;Urro0ND=7z<7YZ8FI_As6%|DrY!JQP^}<_Ec@o#3m``3pz_0J5D}0H%Qq zi)Jhl`pJ&BA&g-oRXUy?uL|*$F`w8_H(yJCX?@+z$XnocUGd4=`>4VGa=O1d1|QG5 z`BOE4>QU@dD26`2&h5_;>$6f+^6SFk{DDrsdyb3t97hF4jNA%dD zvlwp3seKNdCw>eZqoDnm6m+;DOQ%o`048v_gNBZ7E^G({Qs`3BS*;yu)9?c4vI377 zXNw@5SqDp&vBgh9(Ljj0`R3KlP z?bR~Gp?(?K-(gJ8%-q~_fu_BNoyuHp#ejXv^!Ex)Ar}8%+`~qxwqd^ zQTH11&fEUC>2Xr!MqTM)S=egK%L2U1+}D((N#SI*^ zto$FkDPx_mo0{$xZ^vJehBWT>cr-ry&KMm*tZxPDD-lShmZHep zvdHiZp!3vq#=91K_js^|zeVm7%d!IiD87AYut8YinLO;#RT8e|oL4E?#)zDAzWDCN zN1!xp|G=sXr?qJmIt;!9A@2zF(x*OS_U-R(aA-u@E}vlUr%@h|p7_JGR1$u*=|5LB zpDU2_$(AsJjvXHDUpb$sHgVmimk*pBx_OE;R2CngbO{LJdiF@+y@mSeyw+`NM2oj_ zRIp12$d|WH`;#v3fgTsUnaiQJ?XcxJnHj{{+%kEJ|IxGSmzXUHRnRGb6Wyd&`qZE3Sl1fsk9w zd2?AE=X~)+wqH%f1D>Q8?>Ui$I~^rZBH%k9oakps6y>?7CdyWv<-lEhFQOH9ztGWU zX!ZgNO|oQG(Ah&xwY=es^It6huzp7@5clxYa$fKzN{rZ}e+?M=ZuG9h?2WXOPB(MX zTy9(1I=wTm%(k}XV8S?piKk=J%);4SuHTYWHI{G!BZ|2FegT|=l zY09(zXF5;BX<#^b^*JR>DrLgI`=*}=e@CISKv>zf(#y+^|nvwrM~ zk`2`k-3SM11Y!PR(MQJe*%iVh_#WwV=i((68};m33l3J=$lX2< z>CeD1qdj!B@XV!u<&Tj&A$Ay`OHF7@Pj$}&b!~_JsL6Na`g^Vd%kA5`aNau!;s2c- z6g=8!lX%L`!>|GN?R?tW7R!?|cdP6}e-(Ed(1@hh3K~oq#K0KO&qOk&_W9|{Or|>y z&Kv!C_&+R2AM*Ceid9pkcPeK(4a52L*;N%?xaP8$025e$ zEC|p0mpi$yHc4F|{R#X-e_ny2CJJW#0_^$bNef*#6-_YRp_`!puWwG)#hbBfU2QoP z8Sg)A%Q33+VUa5*LQ_}I;jBYU4u2E8&i{e?hixJ7zLv4AM>f4IMY|j1;HkqMlJi3! z`mpHtNpuv6ONO3?4Br6~G#!*U;;yoHN&2-f{eKSX`uPjw6n2^N|d))un99oc^2)q!Ut9sR)VI!D6)l}>^%fz?>&QBMP_7gg0dkY zKp+rE$p5?nzx{pw`S__-!~5R%zW1Jc&U4Oro`SmH%~uJPo2U61jAAtYj#r=OP$Nk| zAbjll$wx}F_WL6&_Wx{XevGB~jw$+>Iak5A#hQZP%^Jh~9_ALtTq(Loxqi<(n!)m; zz)$M8f?n;vbvm7254ZI^-sk$QYtsp~s^ZBw&&1ZYHfkU)Ks*}riadfVY((k|8k7ED zk}wVU3Dc5Wru_s_m6cRn0gk^gUXMb1c;Ilm2Cwu*2xH$ezYgU7(E>AhZ>RljNO@VZ*~tgs7QRK7T$(5!$67& zJX#8s0$9w(;9h1N@bwAKn# zq7u%!W0E3NKibSqKU*gmbkc}q){Vo+f*Uv^fchZnzx=|o4RA_X**~Japh9;FfoW}< z;NNda<`?)kZA=K_-)V|i8YLfFSZGb+9V;whWjfNRl;Ny&RGq_BH==BKCa<8VmXu_b z7OqF%C{kV#Jvg+NdH5hh9e9fKpT309jx;dnq|C{XXJSRJU*9MAEmk9hFXE6A?g)W3 z`|5#jK?(KI7T=lB^L(tbtCQ|rLUCv&J0MU_y{$PN*^aBdSpDr-vj*q6Bk{q_JsQ3G zMmDrB3O2aHyz%KA7<6Nj#-3j--UCBGIF_-6#ld;8vS7)mDV^}Bf#%Se>%5!VY>Koc zGYow#kq6BDIAhrC-N8nK-sV9@q<;U==;xe1ZU$7~Uk~uLp0B#fvU6$$)ej7$3E_1d zR2H|K-MaaO@V)Jcmmhi$md2lqD=luwZbahl#-wXNB6B@kzXjT=R-iRW0YdY39A=yB zjQ)LzLrd;8^gaEyMZ#hlwnj;B0m&GqBa{c`Bb&CZ@wxeG7UXtoTJgu}uPpaPjKg0z z$Cy%Rj(nl28lDD^{)R8YOBbuaFMlNZ&NgA>e~u}s_iCBdH(0vZWQ$q5W$5zYyeI#)wrtS-g(08dTnsR;E%83}}wpu4AM z^$iwYT#)G3#n!Ogu>nf8!u4=>Ow8dy?1p;TW*6yHdnm~~K{vaOdS;y`g0a<+)?I1j zRQzsd{#?+TGhv;K8?!cz7F`f{(Iaf^?a$FzKdoQD#7kuZ!gZe$Sq-NTpcRcf zLl(v`W)$AO$`~c)Xul+`&L-B)ur~`Z%%}y=jx^WUM3Uw{IppN7%weT3ouBz*3i~F&v`0_Z;nF_ zV#Zc+%eVt{hz|p(@8UnfMNTC7^FsySLfLvrFJQZF6ECHv@9}QkW|NssQID4t0p#={ z7`62`U8D+O z2F5}hy*MJbG5(|)8efq8+V@~MX|}eMHjHgT*iP^ppQPMApMGAZb{|&$Xa((cy1g2e z9Pk5Y^i$5kfiDS>3kyO+7X$5*A9pe5TuG|m_Lkef@nO=6BABM>nHR0y?MFy>p@oI` zmL!b-)TbTuY#s@-{uWq%kT=>6Mqtc;E!VRBT(nsj%sZ*<$GS9er?5P;YH`Tf1ps-# zW*-T9t$z>a*Xls%bf7w_OyQ50CnE#tn;8WK1#3Ebdf^cDTEol94>ia&v>7b1F|P5j z2aGKW`V_6l>U@lgtgZsL5jy6cV~3N|7MY0e{+mB3Ml5jo1wvdSxakKDabG}7Q^s|1=DX7!E3@P3$^| zmiLC`Wc|iMR9m5N5C=832}bqv22ZEqaLO9^6dBpBbtU7kqlABhJtNJ%-Dr<4n3rD{7d=QpsonOG{OU z3`%=Hc6&{3dt;({_RR}%@1=3hM3foR%B((aqA21A$$|j{f@c_E)n|B{fDkHaNR39o z8DdF=g!XKlpa6<}Na}=qewA>U!vp7Lw2Nhg6r;cX7|~~adFvR*PUXl3V>48}W4myY zBe`q*9W}k$6VN8+l&L)Kz3^SayIwl!f(bS^9coMSI((iugoudPYWoxaXOD zzU!Z-T;#>&9dcU6mh(+{TYZd1;*YFpu<#)cZVh-A=Wm&tn=33mVxR0(=50snkt*S! z%g)UmwmIRQ`$mf~+CZqKJGxl1CCT}?HBib6ZGhvc8WP#=|NgA(F=ELLCd~A*vx+m_ zY$cgLLJIGvz4DB7ZX!fflGENaB)&0!G*E zGyZ6NCRd!ev$ivBe3|-gRBQShUcsa<#1a=M;}Rn&Q+UPN`rRDdBdB9~zm=UbqHc_04N(ZRv3OND<5p>G4O!bsTW zlW;cXtcZalGUGkT85xP;Pk2Kc4sj0fxOtPz@oe2-hnF%aMBnKCo+~Pg+g=Z)YpRFh z<`dj|s)D^n#0yJs$W9L`Xg=8ZXBn0bo(k)6;m_e(3bDYkCH{g_tV2&rJ`#!^?<35TW%hc=3!k2z z?&y|t#EX>Mpb8lA}n1rIHs_tckIuT7UsCtH+C zXXs|Hy+XhmD^d#Tu=x#Kl035ZC;vJVGD|oQe{YVPZwjAoIrMh!Qdtc6BJNx#1;-w? z?Z-0lIn=E72ezCCf!*#OCx25}DWN~R-#njT(=I6)U2gZ0b&?RHkQ}-$1euWtOGKo=qqXtL2oB*3H(} zM#A?LA#D^Anb$OkEC|LIF1{w9uU$0ue&nN7*vi%5j=m|YKnwo+1c=+E+(2%HYIHvF z@V2;vDwTYw@u>`XDZs7m&(k(I%+h?U4~~5i7uFkph>0C~@G%3Xl!e^Y{o~m#D!yw% ze60D-@z~!B>j}7H#48g;uc=G+9IU(81)*Yoe)6RepZsQ&6xQCe*oV0|{kQ7uPe`TH z;@^%*Vr)8SeTl|ZcdtKchLHqyykQ3M9s!X@gP!xoB~T;3mApFZ*|L_4LdQcCllt%EPi3e6~EBU+o)G@LR78XTh9T(36t9t3(>1b%w8O zW~a4|6&I&UbDFJLNlIPjWM*z=4>JQyrG6tzAYNW74JW&(`%(lX*{N8J@9&P15>fJs zTcx&>o_bB`z(WFt89p+-8xvvdBj#g--kGzC0rA~ItUZ~wP7S^t5y4)t&zML{`HHdD;8giQiy*!^h*Cyf6Pmh=2=4469PWs7?R) zcj?VJ9lgZV06)XB2?})z6NQ*-k0ZMS?(f^{I{FHt9Afy>ywRSRCL?EIzd&z>#crg9 zI@D=vM=gD^%^$mL`Ozlz8&2<(Ny*!kvv3h5Tb-R1QgIBUa(_F^=~DfH3a#T|XNCG) zvh4y#UMaBbCLIrT+upJvyBCV^9Z(5dzAm&SXEU|A`IwpYOuWeq{%33MGcHqc97773 zsF4Cg=PbhG*Btz8Lc2h$c8n@(W9un($pS$>R_VEvugBV59PB!tZNA-cu@bNDTqO=U z?>5ht%iB8}6>WlG5Of ze*vWS@{X<8k@YQ1;P3bU?<+hp7rp>p{+bn!Lxc|^c6-ERBefO!F zYO_c(b>WDmz`ubXHm8Hhp*eOrl(|x@>9;_gNLtI4yZY z{Yv*c7J-<1=%g{~m1rI=(9opa&>c;q$%|+-lf(o?Ip;>x`1bksN6BNhXe|mP1SFG5 zV&WBF*7S8zi;9ASwr&rNYpO+Fwj-wErY!SrV2jzi(nO_+mztmR<~+c49SD2&@}u?d zD&nx`OKhVRu+m2~M0U2rQ2g%o9vJIQTN$iulHmMbJ$kqI*=8`B`$C=N9u?*ggV-eO z%-mM-k&2cMnn|(dW~an`+8TqWUu=vZSoZ9d-M6pTaj>zsy!iwt|A7P(|0L%JQ=2Vf z`=zNVUs=vFK|YksNXl|#yNijrI$PM;Om6WvZ>TnolAO$`nEmnlWiAkw4QzPBd;_{q(P_y2U?Nm9q%53{&(hMK1ZMspYH9hLn4wgmS z-Hax2^Wje`E1d2pt2BT9FvPDV)!Q=?=0dv@D7sBdvms?I=!BE%h@bV1jE?Q(u2HiW z&V=6jfn>SuuNUyp_*QaKIkjW>Z6-Q&MT|j5Je){;RkwX345sM7?#U8D#cGMl))4to z>!*4Yd}@lt=!;@h3NI&^O9-AI#!kER(3-I`G!%*_Cr8ld1BS1+e5ze`PnGKdQnw$noeE#4xA`u4y?yamg7ZT`VKY{zcv0$Cl9kHYj=h`PcjJy53PoI z;3@g-JcSHC9HY6t6uUA5kwRATC^nric=5^nO2Nds7U`74_bnjPTUL3Fw+>5m*NA_C zyB3xX4|DH8zd_kV1y$$}6HhKXurpvXoocF*T}`9Pu#CTX;9%F1e9F{-LMz&?KctQr zZ`gGwuCqVb`iCQExOeH0VstF%zwQ`Q;;tDqGwtIG#aj%9jO}Cn``XGz%S(GZX8|zm zip*O8+$dyV#4q7Q<4&)=3|50VwSnEj zO75B0IM&Wvr-j|Q9r!DnPNWKXJj~PlpZlI0T*m9FCJm3Hk)4V}v+&y&ALv5}T$*oL zKRi~r!gE$7$=~_jO>!o;+#BX80_RAy-opOzg2{*{%IOs~;5%PRGBe-tLF{%`cvG%r zGHvi)BeP1stt};#zE=rOD_H0I-wLb`-OvzFAp^m?UNtX zyLTEt*Dss6ZloBY<{Tj0E|T$>$+~tkn@E7sp_HULyAtG9CngKj!g@nFE7u#l!@<-K z_iMC+ty2j2kPzYLq>QyFucqa9>zYmkx+6b@DuQf_YczR`gMtgkIkjmm2ILTU@O7S7 z<4jFfmM^i1?kqt8BWuJ05?$6fnvK|R1=3&NZN&yW<14IBuL>CLq1pD&(1b{>Zz8!` z;}q|<1(}f>?tua#_Hp>m_BU4zl}tj7=;IZn?F=9cePO96&|e2g_2m*8&Ox-^>CU3@ zs@aayqq_6Hi1&zHlQrvnmhu;tEBMGjtIDQm$%)TB5bB5yq-1eW6@p@#2ml8od_J z+Ng^IcR{>?;q z1|_52`_E+i4Wk*c4F2pK2YmnReZzb)EXu#->W6Od`5xIbr#?uu{a~Z{mp+iNUR zt^qTVmsSS3cspuDUhbf@ExQ-9rC%aeZuMYP*nB*x+3LqdN0Rc)ey;a#I)SP+ik=Ae{%$XBDw=c%p0Xn&on#d6Z7$~>O>z!lWhL4s>paZM$mUsXHk>D%>HpFI+g2CBhQ0>gT{^>3nB&hdxD-0a|rkMM2VWmK`qinXw%Sh#?mRAM+4D@6pAcd87CfyTkC2~hd3t)rTY@37$~-AmL8M;i7i4&)u(Y;f zYqtzPY_1FM5wU^s%8__pCN51e)e1_EKO->J>odyJqohEzb1ks~Na54<1vB7R zPR=|_=-GV5;qBsDFG;Lt6Q!_v%@!D%KO-nJ^6rp)L&I9Wiw%9VMe7ONzoxk2c#z+D z6goX}K}ZOd?6$P@{q*-s*U<}$vxp?xEzGFsTU#Zcq7od1gq$&RXiT%Mi~kkVlku#~ zqDo{fomYZX9FPkpb7)>U4U_T!*lcqi06oU@417KgZ_tU}dcU}+;1%U$^mIHQpDg8K zfpBX4!y_vRowrTM-l!PHL-1V0={V9;F|(fKn9N;wOHEAx<5NM4S6Iu+ZmCv&DRg0{ z8m6czn;5H(F+w~S*%4FA3YRg@k-%fbjj!@A$kmpLy6V3n+o$q8>N?BGlPBGv1!X#D zAKParWs8SosBNVx*0f&#HQI=OtHK7~;pHq_x@No3Ux-6y>TeGIY3TWDzRoV+Q-FC6 z=!eDI)O;2zeiZso431Ku*rBO42lb9R8EysT^z8aCTF8 zMWH(pXZMc-|NlRb0!UL1)x5M9NsU zAh}xDR^y}rvsc+l8Nlq9h?<8#r8K$y&CM4UuEC3jwSshKO9~I9vw$iw0ZGUJhyNgO z4Z~WF`RA0pjD&=QQwIe)7j1VF7)aqNBFuvD=EI_md-m)Z=j2dlcH=PP!NNN9+SMRE zfIdyKW3O?6l+qK5f&THOa2$``mG>6gJ1y>kZhZp*D z$E{%s;B}sIYMh-E=|3Av`@MQ`)G6L`uWRP8EkuN@jc5_GNN_$^bDXv$Lg2ef!{<>S zoNJ(~ZY7mH;5^huj@T@tZ8PxjdV%!uTxOE5gQomi4>yLkjL6ueo;bjMDgktDW&rm4 z3{+`@n{>b;%~q#R{0D9BId*Qxq>pKmn%MA!7E zX}MZ2wNLCsQzlwy<#(uY=@*2)Un^ij<%7v-Xiz}1ZsZAG z#uYqmTFM>ROwj~{F1Ds%^N7lIF0rGtUq4+V&h5B%1-o>Y1XWKB-EJZK0zCZ$?5Y|# z$UY|?^A9Pz8&J;-EIfkdJJ?X>gNRvu!me-ynV)Wu!g#zwqVP{SiyT-d;T1{#GqPmB zzXhTHuMPMWA`z93M8oaT*T~C(+$3YOkP-L%l<#@OLK`)#L~=u0Qa1xQyPvQ5O|m9~S<{HJ&^2}0nBPCH zi3SHrFfO^?T4TZUDY8(ubRd1b@mX0R44~+W|suqAO*1z-bCRxF~ct{CU&*$XITmp`P zFDFdm!fn|3)-j6Ik(5bJhW6O#5K>T+X}~q)T1h7!1`Pcx{n&1^R`i!Xt_DGvTqHFQ z`I1O^%(4q_JJqP;b9k=gac24D0AMJDXZb7xP7Fv{>lztFvj;9ciIw;BLPUh>pmIVp zS;3F;aRGW`T5O`t`%J9IDEi}03~1L1a(>WzuQ}3|NqDzQmuxVKOCeK#MVvRZO> z-VQl*^lvaN(5C;((58=8_+D4r-2Cj0DVM~kN1pPKX3A_bochOQH1>p6-cCSOB*J24 zmj)?+WcOT3rm92NYJ!?r{bjiMJmL1!1>mC}qjsRD5l=;=awM!q7 zOU19~qvtlL)7*99Bf)8b=j))8R^Cv|j1(ZWn2y!r@2DrmWG4nv`&G6|EAZjFhtgjg z@7R#+>>QdEEiRS5iSI%VW?6_3YC*@)29!OhP+yYt@df9Md-9eUG_nm17R&r=pP3j1 zHR$J{&ldx|rG&E&e}|CRga3uIT7$c~+gf$=d(+@i;{NgX`GCD@;V(#K1`;VHXxiw( ztr-Z1k8&blA@~P=<<+RV>;Shf_aR@?8j9a40f-o?fOtpNtS>%-Zv=5djY+gNY(t== z@`o1J4j`r{7l#H2gM&*X+)lg;&4x@*1rjx7Nyv;4rlx6f)a8Y639WKmAS7-bh|{0y zC?$$BaVMr24GJFfkEoNe&yVgF;SS_V@9_>bgdp@DzrNS6Ely;kqs%I|fhbrY*9tA_ z-GF5FK4{iZdomRwq00yDl`eV*+J>ruo?r!-?G->RYmRUQ_JN;q=~*iADRJxMb-psv zwlg>jG*C?MgRepM4q%(8BpkP`*gzA8jg!Z9@v$3?CWMpJ%x@~dcbob6sO(0 zl_S;E*He&dc>BJ#cE<-D)i%{a1$sG`%oke^{7Y%R9{-YSOGWc>TYNWqmE7V(0*Pyqdu=C}J0_NsN*=K9HgvCYX=#`{; z`jB$6lC&@kZwzf*qM4+am>2kF!;DY?7 z0X(0Ce0Yw7RHT!watLq29lEbg?=wisM~`gY4qQ!&&Zrq8A*(AGC^=_QP#^DYs|%TDG<$#gAC$hp5oIh=~s2wYxo z=3G}%P&`X**}x_p^`9{c|0MFU{&>D`kN%9QOOlBWZWG69G({kdC1&e@cIe2-EC~TIOpUq#BStFx->-5M)RAC z_PrR@x{0>d3JYgDX{fzZCz@h9*V!QzFj_(>%-qiayht%rD@uN#p|D>g@xsH~4NEm= zx@wiF(Z_KnC48J_5|&O8(~QP0=_0D*F*o=y0R*)Bm5 zl$H!Xv?evz2IkU+JD^@+rQP(n^}XxvgRU^Abvy{y@O!MkbFuM2 zHe~aq*A+?4b+&zx^%MDGc&TJL@~iLg>u5_=G@9nPJtd_w5tXh?3c(Pa@7`coAXvI_ zDLKhF8p>WS)nN)B>oISItShBpEaFS0RsXYh$(WH!8-4`A<~H?NwM{g}uSb7slbt(S ztp1L!Z{H^W@9@}=c2vL4uKq*F!a)B6=UYihgYY!%|8Q#?SNqP9<9Cw7qtUstaEBmH z$DuAtY)C^6g*oUSJYxQJqDD(!+BQ9>wm793~=c7ZWWKL)O!&LO5g=I1CropsiL$nbp`Kg^J*DSmi;b8;l@6M*65 zY>=SpcfsKnF@lgnW(Ege0+8S!#T|TO8|Yn&l|?(lxy*Z31zaZW~0<*?XD%q^;!iJ9;Z^d6Q8XwWu+?LSgUt{&5P0 z+RyX)d31g&vLqz1;L$61(ns>f24dI~+?1FV3Ra|<{Z=Uk+4`#ROHWS^am|?pq#keG zG*Ja}#{O(x4v-)zu?>~AvdhVp9q-s;&Z^RSPpOvpcGV=wSwl1-x$Y}AY(g=Nd;8fp zi!_}*RrPC&I^he7u4W3}4mMMxh4edtr@Y-fuOa|s%9iWi3tu3XE#$;Rt7d2-VX{XJ zAGnD&PykwzoeC+aZZ;m{?@wqxi`5dJYG*JO+yh_9Ri5|x7Gh1Uo7@&^86K{xe&tOt zLF$LQbJ?0j$WgX%IM@&YE}!CG7wyp5IwHW_qJ+_-L5~b!_RIGp?u0wcsTsi5As5hd zL;fq9(ttx>x^rvHf3=Fa)nJrmonQ8CZ{7+s!id;At2bQ8bCQMkkjfWAu=GOeEN&Nx z103C>U;76VuzE%By-?OUJVvPiw={q4qV-?0U9igiQl~d7a96;|j8x5_HMNt;^|Hq^ zGW5qnu2bfcU6Q5RpYCKdmHKtN&zz{ktk5`W6({zOvq`+cz)_iu?}@SPbM6>;7jTG~ zPxpfqfL)qnK{X#zz-fv-1s&V0hu#5@(OUITQx|5E;;LbDG{_OgnuLU-`1$~yL2@Q! zjqm|mtE*YrqPy(}N>_c$ihl)1mrdf~4Ms3J@3!R*py~wBh>c+6w(m$+*g3TlV49(U zcjQbT9Dn!3v=yQLBj)`Dk31!mi6TJJU#b6S6m6@JH`}i1rY%p-ZUEq6Ei*@P`XFsMa1S zd&7)T`mEc>*Ot%W%$$-Npc2BVOQPHx5Zrb zlwJ%;80wRzev4`I-n5)hEyLKak(#0;r@H$92=gp*&1klNX^*NYgD^Szkgl zDWfKP#|GUi0?h>@OQ55B1T=N3$sMw$7~tQUb>-{o2;;e#8h%oIS?r!1x~WULhPsHstEN6s*;k=GH${$PFWp! zCb_Lp;ocK?{dI`9s1-tS#f zIdDX57kE{YwI?5JM6Yw~!|qPJr|O-CX7YRAsVBZEY& z=mVhKg`&O=06I*0VJ)j&zy5(WskVG%OZVJ3k?1Vo4N@tw7w`SCh-GZ|k${Zg5^x84 zJD&Ci_(Yme^g$d{YWrs7pm>lP%Gd}sb89{)+b-p^GMUIY2XD!*QdhudGqs}qJgPE& zYGEEp2@$9OSAB*ecfnm0O-a_yaZgpClQ`)Uf+T32vgm?}rq(2LY=%InLaAtY6Wh*L znUi}M5LVFlyyw<-v8gPu5b$;A{#{~KeTM)wfJvcEN=6$dYuBWmL|9ya=yP+kEkXJc zaE`x!u?DTl2s~;F{3ON|4~!QGAzpmV2l*3qjvOM~%Z1wRF$|YZIF16udA1`8* z`YBUw>oI+b4yC`2MwNYiI7NZ(+MK*g*#|++b zD}^@<(u1XeYI??G5b1rc*Pq5`%PW09vtJ&bRS6B1?TNGha%i>rjggc33V8wDf|psk zwhRWw283?JVgxde*3m~OxIr&G1WSmapM2e56oeoj8QZBHs{P$1hAdP-oCz1BXUPq5ev(E{-k-Aj_phI&7xGHo`iyO1C{QLZcIDj0y92z4#&tt?IHqzQ z@H;>t>zGB_u*8RDWgyOd+H=`SHIPD??6fp$c<}kp7WAvhLMeM+=X(Kz7C71(I`x>Zo{d>Npi+NmyCtvoQ1r-exU4nEZ`f?i)Y36zr z0k(jc+?u|*qV;en5@_g{J4A+F|Z17d|{^$03@_ zL-v_S87DCePOI7Xsu|oR<15y^qaO)e>nnFDuU;N$AM6^?rO*VxCjW1NWfLRS{cTpF z@la@7l`$Y!Hu%?`dcio1_h3yP)Ir>#3l1Z@)sGb!A`+D@Bs14IpmM;m)B@ZQ!)u-( z)R=rPR9+GZUuzq{+b)_pu|<iR0;CL~3^SH1W;9hF_D@W4D)%WW|<=ELr_USAbnk+cnbP7n%C^&H7u1@gdpeuV=u0Hz*CH}ar$o7}t zWceoox5rh^5=PcZ3E`75#jgfB47<{U*|w`K;2_3aw!jz@vlMo(<2dcxskxzI zUHbj|ds(V(nqDgR&V`u9SfL! zREK^3?exFq5o0DA{a@!VO5(;XPc772l$qZC1J$0k$x$XNGkZcPG_(LSP(~?PrR|hW zCWB1HlfB^AHJ`m_r;H$ zg`y4*`~nwJ<%k`k7j~lbprNN|0vswp2x9eK%?Tn8>hZY(myFpPZpl+znBS z!+c}RsvzWhsGyU7as(~>`ESexWir?L%&$9T<4Qyh0+JMmPh;hKVgkzlgX#1WC7+KO zf}$do@+2=6BeNLmUDpP_q;y1w$Ppxf>c2q@yUX3q+vZ8RgOv6IA;%Bk|2v@c8h(@>s^IlzrIzbu#s`XUWTfdX6^eE( z1gy;K?rAh%)X9|R&AQo#?&S@!x0cgN5fT*WzRsK9X|%vTFm~}<*!>z(w9|itE2yli zIevRxRZ`Jzjjz)OT+RCwuHv0!9yo5lDBmidvMNa89a7<}d|=1)A5ka?P(|8VNhsZQ z%?hLK$n@D8X~w_3q~1*Or{EJVOpK}Zrm-YDgUQ_a%vZf~I39FPb5B9) zx3mwdU(K=Fq0>jWi9XJTHGPZH4(E3)nglP4)wpny@4Nt_GzvMl0^!ybbizp+korM% zLw(m5^Fcv%Ll(JkQ0Xn1vd@EiHBpid9nYSGOi#SI{vQz%D(l_jGdYT-+Z^^=d+qzh z1#FWin;FzkbB%$$d>8-VWu!)rh;GS3t@6qB_T%oU%yDLYeGE;aS#zL!T!;tBIS6dG zGZ1R9>(34^qt9Yxyq8k8L5Xew1b+?f?X$5H$d6rNKN3>lUh!Ma>)793ofR31v-gvP zJsoo)Fp>GDknijbO5_Mq#4Hi;q5ni*+r|`MIeSf&a9(0gU~MDu=t*PxLaND#bMzk+ z=j?+oE)k*$oQy1Kh1fUp-~(uE`IVPoQt2|xl2 zNR$zDgZ0F_G-QLYZO|4PxowZ?xu=KLt)+*5PPFD@wKk5Ta0?X4C;!C57v1`<>COL! z*K^!U6QvOSSbc6_aiX%VU3XL6z9YOVzCQh*r_+Vc_0E2JCLJdxDA4~bK>GWtFNIQx zj_V)eb46OaK!tA&dVfuz1g9G~^+ZCOCT2Xw%0Y>9)N9zu0SITIdZZAf){LV*a&^E_ z7c}%{DXWw^?kbR-7AvgXkg0z2+*HMkUzwfN?imWBS2}VZ;HTOU!Yc)CKAz2HbpK)P z_LDM-_Ec@n@9dL3{(#(&wRODZi+`*GrtncvK5_tb8JP0&fwOE=Iz#$Ys4_Is^+EdT zEpVLKLHr~rA|gM9N1i^&B<1s+JykcMW|=j);8aS`sBu&VcrXh<+HVL+ z8VTUe(MXgj?@KzAkd#yaq1+kZgbG}V}?y!nMWp(swuGMLA=@gAE5xM$EraTrPh^tr0WrH0A>`Wt0=BtZ_*?^ zv`ny_lX3lr8MC8O7MVL4q>C^6Z@3yqol`LgZaijbbo3FtJsOn^%xSKmq&f={<-I_4 zY;gPbY$a{x9-=ic9cvpA7ncK^YW7gh0UWI|PRo_we2i%B&~AfBL&$IZ_7vs`mGVi@ z!*%bHSaO8P>c!}DK_a738M#dXh3Mlp192|D9?R)>A-*jd|LsFF@@?kFA?wwT3^S>F zsh9#TC5yU-(!1}U@DP7pYC*@I=tf2Tbi1Elg;4>Zy?B=F4w(itgf!! z1i^YldsFE2>8ny>-f3gr6Gt*KGq;G<`d2`v8sQp7I29fG3leL*h&dpEY5`K1nGu0n z{+eNeST;7cKBzD-F-BTdQQA+A4GN>!w+egKe=arN+tcM_TtiIcEu*_Oi5vmBVpSj%2C}_~sHnF!CxsIywkRs*nq?OAXbc3lWk=gcc9D43WnNxB;YiyoR`sNo#q0Th|KI zggCDk4yv9^Ena2DDKIf09FwhVvQZL2u~@Ucr`I-fP}{O#xbQ>u$BLQjPey_dPV`HC zf9T(oJZp?M7g_KYrL!?Eg`AD^H~*Y1?Dx{YZ&7@|V9?gFsf0M#A|Uv6ACpuH<@pQg zH=p# zp$zdamNxH~?yp*oN$2D#!(FO zh!AvoLm&L>hfjC+%e0n6#2OLol;i)k`@fEI_NGRL?0priuZ9EWrG8=dq#G~RXCFUm zYviK{mrR^u!~{V?n)#9)a;z{1Q1ii{*@N(v)M2CR6>q8IZJ@@s^|@b29={iVp2mfm#TwQpLd%$&KhXCPv)R&20p3lDJ? zFZ%BPxQixj#HgClK$=%c*za?eZ`=#=3?7^38nX(m!g^q&^TMP-hl5WjU@~N^F<x3m?QuXQ$Zdi2g-HlL0seRy?cp@%o0Qi)9pL9VvYWqGl$ESoqRgXjuNUw52$&1d2iJQz6!)D9eN=de=u`xHia@jDx+E1P})Wb z(Kz6~7FvkuD#g}(*^TaKPxbAbV&c9^(0`N&R_RwH&d za@USGj#`}y==x+#L61lqIYc;!>Y+?44R``mT$hWi}L4}sikm|VuyEK}OnE#D1pZjqapF8 z!KAGHmwZy%>h3C&qtUl6@Am2;BQ)@+Zy%Inu}ZGZ_Tw1sO3O~;NzNNe!)uzI*0QhO zRhrs3zT+jM9OBbz(;0LVcrR4ZLydnB;mB6Ug#oz47M)xTh9+yh_ zmB0x{H{c6|K8b2?ZgZQ;iaHN!m@wKudrc{Hgi=gHfDYHs|Tdi7cO|CV%0@T(u^ayT<;8}he>S*)-QKOM{Y zDjz?TgcB0&ZQ&W*_3y{I!1Fzs2i*C=fB)SHBpG>717$kV6xt7}Yx-tp1d<&xF4}3w z_%fT2VoyIV%X2qBo*3q|tKe?y#Vg|N{1gU=UA&v+VZ%i6|1dF>ZDg0mysOjNeYvAS zbdigEZJji&18%#~b0Zpwf*S`xXVo5{e$cSUtrG*!jz`7=;k)idL|KVL25^WQfC2$; zII^9WYDC;$=F6Pyyk=_pQlH}<*FIbx?|QSIp|fAZ9sToDmdH4nAIy(0bH*m5_Y9DR z&Pn@WCR5GWESU4sqkueY$CO)hiLh~$fsZ8w*vM2PGHg%+npKAdk`seN??5b7@7lG; zigyu5Wa-(y1@6N0(Wb+{9I)3*<2pLWCh?P?tH^*qU{(HQrCI|2^PYkHQ+;747Oq8+l!X1lb7wZGkzL@mjO;whpQX%Q=g`I-7YueP@rr|nu!$6Qwh=7!wpJ8Ufi9Z=+YI_rDS>F z;tJh-h|@t1v0d-}0%F3S!27=isWXI!9+G4kpcRG)0k+)J6y2LVS2oUpDA@w(44g0) zQvslH0PIpPav~m!)h%6PIY3tAfZHp*)V2^MGCC>Vn%==7e^gxl^?Z@d^fB47&O)ch zkC3$3&L^wl)nD_th~uiMy>imO{_*tr{<-?s@@uP^3ljYF6rw!Cyhd*{Uh0ddx$fb& zOoy~lE-pan$Z=lY!mCeyu>X>BHF6zl&dW*;o9P@LgJ9`|)**$_{;uqdaT?7Z@<#fg zZ=PQ#cKNbCr-k>O$nM8tAOwE%#=yoDKQe?Zwzq1@@>YIzm(O1lGTGLVX~+Fg)MUSB z;|P@{xWn(tTNg^*JxSLT1uANFgbBt67C@3capvX;S2 zm#ZTJ4ImP<0J`plbz)LdMo{2TpnG@>c<4cmPOJ9Alv|>a0O+#a&Na;Mn(xg;R4r6s z`x@4I5d~S_9jgS@EH3{jWRQY3PT^zq*H$J6<6QiT~R^gJf;d4O+9lK2szX^%s%62YuFIiq%)7i!l)iI z*o`v3L4*S%)&os1L6Xq<^It&WgDLF`0=YBgGwK=R953F1p59Q^!!+RL;s=$;>XmKq zPZpp?w;M9+-^OE+t7X0EIita2kEIP)<*wFB%hb5Oj)-@>Y?5M9e8%+5nDKqT?J&b5 z64RTS4nto)#j7Ge!~9tN@z=|KhfnL_&Q$H1aTBtSwi5(BA?Um@&xjqXpYq2<)`^r5 zUt)Pbq7Gvqz%Y#P!FkH+e6)YZKc-pf2$Az9bT9>MB3Z;B8JC&6bB!ijWV*82yVU8G z{Z$12P;humK4wf+Oj}~hee<|1eOELi}fp$N=cQaAKD!h16VhQ6;@rBITN9-f= zF?!a!Ek$D=4mK+B=vi14ASLh!3%_t{SnE`njWI;9-M}G~4i!0nK=rZ_L=h0q6rE^e98bw9AyBh{!s3C@W=Nq{9`rdl8 z?qazvzu{M3oU`{n`^-1IG_(=-=e4$ePTlTyMEp%xT#5>P_}u)zNjqlkWV4}jGh1-H zpZ~Nj+cO)RR5AOTzG`lE?=Q`Jn-c`z-^U&!-;91g2)cZofz~EMS(-ZQCg2b)ojK+o zz+@#B82S|GDUz&#i+KF_G4w6P0g8|afQ1Wm^WeMx^B}_&CnaF}8#3;e9i^kw(ws?a zcbqf+TKEX*9A^$gD<|2bo>bZyD;ZNA&u>NB6s&aY+kS?as2h8&m3l?;RXX#aw@3S+ zLjms>l`~Sp=QwKX=U$shyd)n;UTVC+muLdWQlr3Y(=Yx$vjE9*3b2ALon#m-xl64 zqvrX~?;qp)^t#}OzHD$s7o1yGV`ygk+96Y2_LIA%WYmJ6T#$yrWWubq{{W_`4LsWqedVB659;<}+Lqn|ot1c@3(65i^b*CN z?bt)v-x@4)_3O`%yYf@r{KDL(Z^^oQS#FuaqAT{iJn*S@lqdIn1%=edvd6^MDUs&r zTd!k8hKhSWUZ$u1-{>))S+0T_5QnkZighn`&(8b@oEwV+w7F5S2 z9i8YWe(>L6tJyCN8MnI!mPtf7HYP?y5t|=fNx^{*!!++gmvRqO*Z`-d+4LbaL$7Sg zVG@w@Tt?U57Xf92v>iYy$f3)|?a_Cn=Z0kr_~jBxzDSuEEsi}B51xp^oH#t(IKpuF zAJbwu%<~LaaC2cWiv9XSnFW8Py$#N3j@+Gk>59 zX=ZODp}ymqTsa(aut7IMv@{uLiuPcN^3N#w;^zM(&^LB!!n-7-=4d}yOE(kFrDutV zk?;qav+l-z-2xoZm0G0|V*G`__nOHRcW_)dO%9O`b!8shGCe5;PZ)8Aw;w*ZR=S@$ z#gD!0%!mN)`g)~2GV)sjMIV)QW5J>1n=y!M9M+CiBxDNoVY7H=G+70kA0&IK!KmDm zklOmfF}S05wm?oB?--nOVY?^*U4kL+^l2)mO1Ok*bO~`DPh(bgmV5tSm+&_YjeRAm z0+{b4LP=3PGQ|%vknz97!$SnuIM*o`_(S62w`UF+SDCHOb8_(oQ@TuN+STaX-yBO; zoSsNa@Ujc28u>Fg{Ha6ow5!_F5;=eLecg_7m#l|TcXHR;MyW@S(QkPac-o>@|4}p3 zFrhowZN&zsHxG?+{bMUtfNn!0p87=B8BVv34&Pr+JepA}AE+m=RgUEOr?NCk^-ouM zIM7o==fZV7Z>kH=*_Gak9a8tcN!ZDx2zJd!u7ksAZD-V(6~^thY#AsBkpjKpNWf~m zLO8y~)Pc}jRM`e02>>8-cs}y-ZrbH06O_sDc2U3jhMInA58% zeWiS@nI-tdU-c)u<`Ea{`RM>Jw&~PACxe_qNeZ|w)NVX@Vg6+yk5O%Nj(Jz1L(TW^ z$t4R}9CA<-HQPx*2`NtE%~&ao5ENx%K6w=I#Z14sKq z@py%b&{ZojDd9P9IX==m`)#k`JCI;SQRl%)XpS5?Gcl&(3D%kkpn0ffZ>#$COK_w( zEbIhM2N_={&hP&mUXyFLxP#v#D4bwj7^9uJdpFtX2i+)`?f*XNDMH!UtJat-(^z=1 zv2YAq%;}~{nvetjZ6#HZTb}MZo*<#ZFm?MAk9LUjkL_zva{szPjVTTL@O6u|KqV>~({WZtp#b zj0%|D`1erltRv#O7+|33?;*Nx8Fem#BJwPg7Pd2O6_u5Z(1&i=CNH@=G9ci=12MRc zzpVEAwnv)VJ_~S($>X4~Fmfo4S(z+|Pn2{E_=9_&5fVO+iOgJMmkG*R<1}^?OB%mT z#8F7mwH$CPybp=MP8swNF&Sv=mG7dYG={PsSp|jkLfpq)h0qxSwHM0=k!6}fYSwM9Yft=8&sTAV0Du3F zfFr40_Q@TL?S&l=w3M!>kK67;jHw_$ts0sQTbc$=A`##+t*nO)tO=X(v9XB|Ya2$O zyyh>K%Br|HT;~Udg^zY^S6JD4&Ehe96JFu@t54K&#-xbmNg+$R$%z?vw&x*w9x#Ug z?k)M5?-#dovJlIlx}VA+MN!)b7q{U!q2MfAMRk^}E{Jk*l44Vm%7$)xAf0S_b4nu1 zVM;4cC%y7px`8HYoC-Zd`CJ#xpg{{6&TC5WL!{96@7IC(VmW>K8U(eSnMQsH2LxBy zhYg*?-^W;KL7pFum%(Q0nPGvS_+XBg`^Oy-~MB8j}xi zNz>f@tArYkhw35}IY&w7S#yiCIfM z`{_eJ3BH~ejw9JvVi$)TY3`!yh`x;X!-xEep01X&)XtT^i^iFl82+&*gX5z35BMz9 z*e~k-uNtJ1CowYDud2qcj0z<-f3i;95am@Rt{rjlVzWFbRB^Z6Hn#7 z(6?2$=HHE`YytFXL_3Wss4Gpnzs$0p?e+d(pgC3;E~xVLGl!&(g(0O4Nm*-Egr_XOG&!$p+QP?j~)9 zclRNTRloglkC@i|?ZG<+*5Z5rLY*VQS2q>4`v$pNit?_Y91$j_BPRcG&KS2^4a$E19dPc1@z&Hwq9rAM z7Sp}o7k#tBrLx#xA-6zSc?jSSv_l#|)(8)h@ldijvW)W(u1pG~yHJ6~^ZD0#qf%ZuP zzr!Shsvyyu2(+r;4y!uL zS9H5msI8!lH5&8Vl7YS)D4h30zssJX5Dt?_y}uNb{KD54k)i7h=%Nz4sLk#8`wXK( zPEe$msw7+YnKdjwTU5C306618Lh|?pk0SEofWEIZnO*d46&`c3wh?3DYr{EE8oOKk0}Vme5^okrCgGLA}=!|O5`)e?<0Y>z_iDocyFu$Hx3qrpM>ap)?z-ay zbsVAYlSm&Is}}K$L=EM?4_CaVJ|k|yixB7GC-aH5H*a?Wrfn~_gi8%uG`d4dxN&K0 zoDi8nzvcQ^nuHL>z06R#&<5LU3aqv)mo7E-S))@gH?ECM)wNol(_KFVghY2?B=zM` zKflpkhUmBG<0-_>tdqZnE4Os^iaT@M-(Y=hJ?gI{y(6qbx3m_67FzDNbP-tJe7jd| zcq5wTC-E6M=aj%n2d+HhvqImUl=#n+-A}|25~etbNOG3^YljA1rzAlw#Zg zpE0SAdQ@@-4ZE3Vg%XXA>=(!AZSXkOh(?>ZsVjpIrA}-^+URmh{|dKSb2t~xPrZY+ zA~$l+&$#$zTV4Vyd)vpf5IVcNXSU;u<&dsE3QzGtn>Qw+B7!&o1#0t9_#puUSGcBJKuJaJRb!a(9lr}@H~sM zUU$+$18lG@Nh;^X&ZD{6&$r?Q!D3P4P3rNCvK>}VFSLWRw%HGKGnfux3PJP1*{+FQ zQqn%kalK1&3^-f=gJY~h9JfWZd7J&sHFF%zgaeGWC4FMHXi7@6d6xtksCl^emr@W3 zefn}i9J5AQY)Bsft|%m7gkC8*4qs-$oOgUXsP&=haDP0mbMoOv$SGR3O96E%ZRpkc`VhWS-)AA>3xclCwwT+tJvNjIc7NVSx0uuHS zw6N7+U6)mpD}^AZ1+BCos9xoaVTO*d4;RK8klG3M>)|$(CX0vP(NrdJ7_T_F&Y!x~ zST9gxxL--?z?J-^GG6z^A<-^ji;~#9=SyaP24p7L^$!VCy~~J*?d|fDZF7`wAnK}| zm|7OI<)6&S4X#kpve=f)!O9Wo1hv_`(9yXPr>L=m3&KJu#!2uKCH)#(0q~wkz;0@T z6bjL+so%a`i!?$vj}Hr5Z`>mw%hYFKDSAmEe?Ne!Z%;G=1q z8`JmJ-5;8a)Y+o%kw2c-4n|_!J~Q>cao}E><~s@W@Wr+Sysuu($nZ#Mps?R~9M0ns z?Ll<#Uo(&jiO%&uIfMtLlZKMgo7kpcPZ35x@UG$aVX~aJyFiZ`OoB>b5~`SPLE}mT zl;2>e16+J*vAOQ1*z$E_<$|lDmnbt11x+=t$$OdCJooy-Hx|8tZ{zw(wz)uGfL+cd z`W8frqqrh070V^w+t>mwwa8w_q!%2OP@$mqY%+;})z9kTz>pDPy&^!@^=dAG%m_6A&Fyjc0G-`ozUpw%CTOB@e~!aVvorJChTGVH^7WlS z+;vyCxSH4TTaG^wFehII`Vr+Yw+MaLvL^Qs^mhgd2_)e(EQ)_E78=O(b*x$4BOj*# z@ypC7s3X@&mFK!jk<2?z?A*}hB5en{tK)^6$NdAIpqbb*4`j3m6|s$@ZH|<_u9e05&Hse z`otc`J`^kX*Xr!pKzc_g4al7HI1le50sg6?n{U?uj`W;WpV_KPXxjL#5!83G-@rW3 zciJxJ4BOY6#~x}pJgQ_^OFY8FV8}&&>EzqP9}AWrM1ATLY+Qy%E*mRgxq zLRN=h$}Z&!_FaWIj!a92e`pr?gO;>cE|2c*(N`Wv=WTlaw+W+B$*w}4l+vwuL;NJD z;g)Yfci$|h*?T}{Wy|intsHoG2CA{_p(z5pnAm2aV{lLqUTky4Pb=3VEm+S*hLV!f zh;u`|TmRJM%N^D4(3-tNep+-)n9dQHWB=GPNJiJYe$a25T*I$Dg(kjD7HRL`ioS_A zltMqsUd- zYasOe#Py|r2NJVYR#&GgucftX4-BtD`2-GKns%-Q-`Y(Wot~I});GmY-#dKY{{%UQ zA>i9Fl#KE^g=LFtr3d_*g-&(qoFu;;^rKmXE0}k4fTVSA*kwESEBMS2t zfF7q-n3hg7Wz5PE>u}g@eCV%-Fq!$pf%b!vjJa3Gl=Mu!_ZEkY7P_mdI@PRR+0WgLpoRzt?eCg!tD`W^7;S%ZLS9c zqh`ck+471#^=h|xw*|vqmEgz;B|fDijW)%igE9ph6MSRbD|AC_1_Rz9M_@M3)A${~c<(9bL1Lkkx(~9E$Mk=1iwO_JJ}HZ< ziuAW|@oT~|XcbMq*q9|M=8Qe*=JH`^m9%cSyWQCgzJNIy^+l)rK*8Tsv5A5ZfqBaZ z;rZSk7E;CP%RE|nEy(@#s)bK69)ds{Z`r_{`4?Nesi*iiU`?oC1>$DCc=48>$l`lu zwIByY4hkkgD{%m>gJPS4o+;YRt%LZw0hE0pLdCxuLqnk1_?c8}P3BZxfkdoWTF^cE z4^>A?d-Xp{#EqbsX?Ky_T?HUO#u6Vd~XytvB~F zqf@85E=@zWtP%Ja7h7pVm{3?xTlRnn%V$t|G%hX9=kLoe&d70j0dg;$F;B^9T5uTBpqvY|!M!s3LUnxsc89iwLK| zec8rMH|EFca7e7Gz_9^Vjkhg}h-67SD6;e=(N}hq2`I`*Ifiu51fJxZHZi0P2pKEH zbmMdjAN?1wmL6BaqzB$0n#QTm-tu)gc%nf32(8g}L%hAa&_s_)e*Acc4}-8eG>P@L zv9YPuBBd$a0zD%LqM(VaA`o3f!<%rzlNSPy%1mTdPfcz<9UjfhyLowdW>>$Q7N6?7 z-EX(m?&wx934h-kBC_l+^`K=qmMU<=uIYtiP}jzt!NEowkyXw7P~I2KrM|TaN69z7 zYj>}~!REg}u8UN#K$^!HML6GpzS!>!G;Q*9)b{M#lkATkp7Xy+aiP#B0- zq0)w3PvWN;|+2r`Zg8k1(kW zd|zeX==hupD+AD!DT`Tnbvk!;JC2ug?j}R;<*X}^pfp3WMvd9}bW)4LMvep`;mFxO43EfPz zv+m}#~W$HDt-#kEycO?+)SG2kIWBC(=Jl-*W)wvoOlR`PyLFqYmiX3ey{ zJ@3N^D|;?q*Tu`~W!x4ww(Z`~qbxr1J5|u-hI&Yr+uCfKknN)L7+vCU7N(HBpmdAk z5ZC=FtV6+sRxGZ9->8@HZ4elUn$Bt@YvHL59cn|YDvW%21R*_s^2DA{w1fwBjgpns z467e*xpQciTm!H?JLJBiiUNvGR-+Q$5%r07F2e7U1;ySD`Y7NUvh1{jrdF2U|B2gq z&i6aG;&yQ`VAE`W_9*8S9cuWoV%&Q{+4@#=&e)-mf7qkM6qFHU060r^{L*!#+lGtL z*IW?Mo^2bkQ4=*B{`I!A&^hzx>*F!+-@j)o@H)hl4w`tj)2Bb$V}J zVLZe^&^uF_*TY4$jJ)IOF|=_)UN=wstijQ2^58Q<(fK0~SK?9P1Q8d@azxUysb&y3 zTe2a^D%2q>$;wt9U(yE(J(S1D7cHlGQps97fPPdIThC&289&7>s)DZX7<=uzoNB%j z0U;SWQao?}@%e(C-FLkry?bJ>#zz0Qu8H$KUGBF}e*LVs8_3ltXZcP zm9zcZ*59Jrd14e7$V!$=UrKgo(qP#cyFdoy4s{S{)&_=#y6ClygIM(#$L*-t*x1VO z^ZH$%Io8L-HXERDDgE=M)r1G=7VR5*1N{w_H_sn(x_KAp}eA;_j{%jHH(bepr&7_9Ae z?FR}5llR_}2;w@qt<3Xpj8kuiW0eOR|?j^28Z^5#C} z+gTm?fIVNb9{i zB4MA{*1zm7Dpa*?Wy;DDLy2`!`Ug@RFYg~3nZ%Ea!E!dL`PD&(pDc;pN-`v#F>AYB zIFz`xYkPJ+-F>IjPeGtpwh_GhJ_4;e3FeN$8jR);DfCz3@N$yXVyvf7AZx z7IcWG)-!lIiuraEA8{ocTF~D}2@E3F9V{T_5G9SD>4DJHh;Ln1h{vaWzzV&md;=ih8%pDc! z_q=nFjhvCvXQM|Dnfgwa?K-7 z>lJVX(8Wy|M3@ooiyb`jr53rXsqy{4f1Bxgtc;MBhy3{NeShKk0F9&_@mck&B1@Yr zl$0Op9^3vFyOsE)V==<1=R(l#JMjChk1Ed;w-|B2MkddTIX837zN;jtIDA-l>hL+t zYEz=94Cx`!BT!H`$P@~{vt908H{wfSGA8@=fKu`vL^XTvm-|xPo+ogN%vbZc0DxP! zwmEl>0tgdh*iAzD&9%fYp@~7EGHS5X%I#83iHDtFx!ydE8UE7UZ5BVlk zQ|^g0QDwpH`;wY^6M8}#m2RE%7Jh`Pxt^tOSUk^ngr+OKfjjQe*0dnszBuM~o|vZc z9nn2kNHvr)E-OD(`Cd?G>I~i1d&&6z?YV?1^X+>*_YnlhPteAQ_QNYzbQ<&IOW|*b zhpXa8Y6wd46{L4PyZd9Gvc&OvUnDyylFxvd$-Ho2DPQ(I&??kk5@%eq>%YAWHc=}7 z88n&N>w0a{L-e1=Nj^mkw4O9U8;ZA&Pv8P}`y9|*dRPA&>AvC8%L>E6<1a63a}W;M zNZ0xO{#hrobsqScnD>q2CWb4HLQrY&<2SoL1J)c9j$V)Et@0RgdC8riZ_stnSk1)M4_V$${dF(!b`6ELl<6Jca4)5Q+ND)nv?wg{cq`FrJ=ubbA$5w zvC;W~6Y_XTmeah_l5wy|`$1+!?pB6LG=7gcC=N>-(q}gpySwJ~OpBMJg*(HyXoOHV?C-IR~gxoT45BMxr*&)8@CO5rzKpG5m_2SsDQq)K-#yv%c9 z2`(F`&unvSB8p7O@6gMce6L61rs_h6Dz!b`C4}+BpXcDX3AJ9vQTNgREq-UK)L9}c zRH!NRS+etT+bZ2n%wp1g=d(GBk&$74)c<0XG>1{AKoctP-qVl0DVzA(WRQ!#|$Ol^<<5BrBWhh_( zQuRw%qm+Q0oPI_h=t-ilsCCfphiBVWI7M3Z?+G%!BKk4&+qLCD#Qki2OhOEk3@2&E zWG!+#LKBsSTn2JXQ)LANDYhYo+cmF#4?H93Q1Y@X7Z{qJ8o0m|7O-A7^bq_n?34W z6uFNVMrrl3TwI`KXqwEr}f5y}jBfwm3oU_4UC&R}LF!!-x>; zsUK!FgF2bS{#zvh&vO=;YFPQV5MQMu^;>QZiR+6ve{b9B)`LF$+Bn};cp9D9Z!YtM z8H*a;Slc5{UjF+hJx$JWXwj{tA3bW4evYctgRgy5q-Np%idF$3c1yD3iT8!E4M7QCaO8HGZ*ewJ`TO_TZC!~QSDl{i#AST;n?bG6G)=E{J6=U88*lP{ZTQE2 ztyIG|#kTJ7D9bU#?%|VwJPDgX*$KJ0wV2+Pdpk1pDJd^6;1lQVR##K9FP`bL2{&e6 zN^*9Koz7$aaYu-J6ZR52$sQF^i&Y|KIla$@s#{ZrE-4)AOm7h6|MrJ!D(d-O>bJ_f z!$^Wtr9u-u6f^|ZL-2rTX=&m+hDeiTYO4$1!#IN`3umUNsiwMB)97!|-y{#SM1{vY z7`E;!vXZ3Pd8J9Gh(B0{w%aJ3F(Aaql7wR>$|zjeE`&k{CVu@k>0FW^Snfux$|m?L zx{KQ^4Njt&K46!ZeW&a1?cvozMOBIp_v|$7u`@Q&m-um_k#b2kMl|5@vUO+deSUgR zZN3-EmlU(f$O}4DT$h${ay`O_NiI(+wlK!O%0TqU6%!rqZ><{!1-{3(Ao@h#YyVzw zd%-o*+|>&6`E&MNUzI0c#q#fr{XSp)pzOFN9G-3=*1Too6wV~oFW!@|~m2J`(ebJMSgIC#Rmz+gH_WF;@jm0zx zqWtcsecTkiU-NwU+i2f`eaa@U1fi>ffic!l;nTo%@|W<;EU+1(&xPrJ7uNG-q>a1W zvQyj%D{WrX4`|36V1)iXV{Fw^X?H6rCJ`4&sXuD-J?Sb3GWaRKToL1ZQ|$7K^iWH+ z!;{*FlTgFS)g&zEn3D1RUK6=GHA*YypNaij`>rMSHIY6wG4#A>Uux=OWjWV(^fyc= zHtC}%7*<684T>>F`*23-twEZNIo#DP5_uK{8L)=>WfX4a<#q85x5R1X^E7Q0c!}GK z|MS=?NFBW!?S_UnQ93I>476aCA6XaiA3S>WyPYBVPSKD46Y=LTkvZ$8nM5n!r{fpo zi?S2GNu-vf2@gGpo(|2q@n5uavi>24JZ73j&pNj*J--f{e2u}^%dNjfq7Nrj&27Lm z|1%lPmVOY{;j&sRpnYfrA9578a!5Cs^fo%kG(e~)f3wVQ;z`3OVsmz z^(xzTOu^v60~TPjfJ5^3_C`Jr5dB1hx}JrDgQNZ;JeDi$wb{kF#2?BJWAiu!rG8di z(_W=7zwxI)r}@%Lkyv;3>Xxcr?mQjkzj(adIFqgh6ub1F)?FLCSH(wdNNfB>wKg@jR%dP=$j3yLT;M z@QvsYkiez1%4dSj-xJZzHCyOouc4h|_O@vv)ymw;Dg)&!;IXFMreo^^Ji}ypESyyB zK{kb;;7z)j^O>4fzW1GfaFBHE48OSl!ktxNlzSgI56molB za7FPs&T|7fAY8kaT&`b&Xftwwv372HrE8c%0szj5KJ)^3C@9bXQ}YFA(((|95z(6< zY3o0mLRG49g`1CH%zvQvZHQ?R#h0sg@AJ>K3j9$skSN(n9dy`Lc2CMiM22kOa1-YD z`GHekz5VvLR6JI$;`0#l-_|Rfd_!IilV3rtAi|qV02pXVymbaSI$)Q}n0PIF3uQlG z*;SO3qUyvpb)a}9yffDl2R-eX7!!VzI)Q<;?=T3S09ndn@=ER%R9Ap>WfVJiKLi~4 z`C&+C+8@MGEY~_KNA`u*J?81Q$Q4x-jyj~VZkG4+ewi>U%dfkC2tAcv?eda6v&s7G zM`()XHHjoKdlU7#)(t=$wzIt*KJfVMdqJ9F2mJ_A0C>$G^k!cGcwiD7(L{wUA+9Dt z-7^e9em2#|Wu#EZc_eoMaGxT8tZExKuDnBsn zP(T$&UORRjhP?n^$X&9g3}$*__G`=5B@qQs#jOh}2$!*N$2EshaE-GsqY_}@t`jJE zQv;YQ$JT$6`wx@y4Wz5^QLZOchqhFz;udN4n56tn#I8lHpWlCQ3w7DGA1>}Magb;t zc#;VIiOXxL2)>3AjhU5q>+pWS&eH>WQuQQ^!7x|-rFkyU#rX`+l~w`GlQLS_V^0m! zgzq?SCiZgjrE2qBK0*Cwgr!wG@J4GPsJ29#ZZ>ow*vzwrg?S!|3eZ^4NLtC&FY(9+xBq6Gz8E$Rv_POT@+2dnH-AV6Bm*7T|4L8{cOHY5iuY1H(++p{t zb>kfI+aG3482p!CPK2d^`s;Yhox=PLd+x7}&(;aB!-5@0=lsKfZgW7WhOtfm?cJ}> zkB|YbwMQ^i6CVT4W&)0f$Q%ms{(C$OWCktx}V;fXYDj@I&>@lKj(|?qg175BNNNzBrQ$NKzH122ty*FY?_D==| z1fbPItHh%S4lr7sL@QN&gL&hl?8aW2#^=XdO)gNhCj?Ci8Jc2aZbMcB2W)-LeB-=w zB4l^J=l|-XKaGmnCFzj})J3^&esOeAd1tbbb0%MiuVJfCv8UKBN(kCiHLR_zLoeKY z+?uY7snxF%A5}@Z3&=DuuuBdCORoAfxE$9Ueb#pNE9@a6| zm8{WUamoOEOT}W|()l?xLozIhw|4G6IP=8<&1GmLuH1rr9eY^?Pt_D_xTN5CjS7jQ z`Y(6iVPdn*&)U5HD2>i%Qu2S~CYD?G(rkTKoz8QbQ>ApDLR9b|9yAH4Y?7 zCLk4NY}0|6Oor3ja0Im}Kva<+PYA4XMAAQ8GVq2Xj8QcZ+IY&+Lf4Blf-C_zdxVs*POGNPol<}UHhOmhx4pFG$7pIHcyYX@Gw zIT5i(Gi<2*5VO$_g2WTcXS??#NxH?3tV`K?AB-oDqva#yl@Fw42z_fri!>n2>OygC zzEHcNnA_)3P|gSL4j>6t{w_Sv?Dl!W!Wo0MJX@%HTjt$G8?we^481n zMvYE%v6_dN=Rg`H`iXeQ*8+>p9$Ei-m0Co!@ZBF3QQ{0^R?>Gb_D)q?J}J^8PLgw< z$hK&FeXB8jC4sT`V9A$Q-7{6Lkl|Od$3LP+L&fAYOo3)+SXElUl`G-Ro4-oJK+RsK zCS<(?J4mj3Ev(cdc0%lhz3IBb$d)Ci?rkj4W=WvWpwV*_3J1gJ+}B~00F4w?RktlH z?iOI*KG5Y zq6d0DbaeI+E1XGY=Fhu%%@GzN?t`MEWle~Az%Fdc8rj=HWd}#(fSnMrL5j&)XCCZs zkAHADarp4ZJxp%(L!m%3wv$5PyS0Mv4RiD!W&u0U5o+HZT6CUwr7F!PKegw|bZ23N zVNaXl{nhjI3jby#81cIehWOv1=iMEGhm)O@D67YV8n&_tL#uGB z;MMmG`%`yEqI$eyq~7!x1GN`d-tggUla|W5m-vX3^n6($?ew0t+1l7-S@wyZJ+Hm` ztOwc`*^Spn@5f19zfLw>iR+|+i+#N@<0X~|<;2~S(3h$i9NT%pi7aMp2S`v7S-Q-M zVh_ajD`oOcei5tdHOpJcb=HZ6c=BG^f2lGi>~1nxV&q`$@iFs!qb479-aWThy=xpI zs#Vly;{)l`L4357BtO8s)p~f1;KE(F>exUSdsH?#H z%5mkzHi9mCB8c7-`Y6cxwIPnLz5TXaHoJ0(hr6!z4;r)tl`3y{|566W(slfz%T_rShJ+crmyK7Oi& zer&6DI*<8?Xis}VTs}X}@&Y+mEu}?Knt1=0o@rZA5S=Y7c3Gm;HdN61BNWl?WXM#P zm6lezefxbmpQff}&?NWmjM5<@RLW|nn-wUPF!<8R|My6b<4)G$#xoGz>J76UI; znmp(IR^mmOWws*PY_*})9ydSqPRZC!Vp-(}497(34OByqyvrbxXob}-u3P6w&9OJJ zpttaAJ9GLpM~iNeOLqArtU9WYZoswO1Wi>-swR&g)XZrPZC@Lt3HhG_+>)T(>qPpq z#thon3!(DBK62({m*~sxl#oFu-ueWj5G9LK!fnO1NFND!3IFC)kJz+zug|Zxiy@a$ zR9LHg>x`9yLk{$rOC275fP|bu2~C3m-Q7BnselAOzfVBXOK#^XH7uk?y5)XVd9EYdn{zs+q-bK+B= ztm}_;5mWoNT?KDbM8Ffm*w+cGe+|&PceT4_%)Jf!$U~qZ&uCSBc(E)Rl0K#96~gMF zpMexo!dMp0K8GQbdP9N z49v(ghJCU#isy1Qewo9R!ykQ_`B!u~4sRw%^Uu@5c-jh{XjH>V?=yE(5t}q(HI1}1 zk?@Cd>-*ZPuVi&Q-wZgv*oTfjIRkkXKBLK}h{j!-MqmfiWt;1W%YZ5m`d{49KS|)$ zC8CFedT{V>;%Mp3vrQLFsk=ITf8+ymGEQaH3 zPr69Jwbq^A&oOm~+Gc#hv>;h=a@QZ|0w#d{k{+q&(!}Fc=9T_Ol^w@NO$T2eP@#M1 zlxvt{q9bhoOfRJ5olGgZOeG(HRGV)l(7Upe-l$se%y5el9186FOCNcjWnK* zbQ`p;k)+j)jXG(Hl_YeHtyH`$w&+Yx-2nF{Hy7BB6GsZeq3C7c6X?KR{}A@YXHzaR z&dt>jxLe2P(?l@ja2cHq<0(0Cu`y#TPRhgIgGVm^x8kS?&P9r?`jW;WBWuAEE*=jA z?9KJ+)WZdiO*a-)HB!ZqL(=!h4v$0Ch9$IkrO}fElRD`6n(Z_@m>KGd?bv(J6|}}G z#z%gGu**DY5f%_+vS=+2n@?P)T1%m`EzIlv`|TFSZ}C}lwQzO^*91 z_s!=^t7TI?Gf$1Ut9vX=H`jM|CQGPsKt76_9oj;l?kaI^kP`wJy^(e#oH;<}#5JdwZ3UT@jKi_4--Iy}_clDs4))6+q9 z?>Gqah)(8EfaxC#ax`)hUg-1*>drnwKgtMADV_{Ig#;DFE3;3_`R?Amn?L)Lp0h;^ zir(W)fp0TOa!^x?+W>L1F+x}(@_G_1_Hw)25Xx!N;{;X@qP1)0VrF;Q=DB&HTJ8_3 z%JXkxs7w(dz~&HwxAo48sf1ouue{7cEa=k_4g34>iP!=zim}M*!^sOswuGC@emS^sQI!6YW)%^6LMJ-6rD24QV7Qh7kAr!|m zwt=a|jeYy}1>u>*Ji3R7E<`-*mF`@sV+ay?`EvG4{O2%O0ex*REB5T#7*y``i#&J|gSb{>0)#p}!YQ$Dsnc`y_t2R9?}(x4uQ`8)kkN1C zW6&4G1CfL4p(`_jf5$5PCx< zqO7dU5otRYJGRek!we$|@A_F=iuTSK2;<24^;#IH$AVW^kj08t)~~U#7?;XA?#4mQ9|rqK-P(ys zrt&DJz%1{?0mO*yC+^1dA1dsPGE7QHr&>*({lvtf!P1+j#D0t`AnjuI49mrjs^xR3 zQ=BZ;_{mK!)dzd~B0HbA(PI)j*hsD?pdti?`5rS68=F-4pJi;zGV4%=`29~zSf#mQ_%aWKL$pR{ zo@;k5vd)VO-1FqDW(h_2+1j|ZE3X`*C@_4x#rj|^cm!AADK_J>6Em|%&r(TuaY`G?8-!-{MSmhPab0eT-9l&+Or2xS>o0w>fA3XOT&U2FEUHT539x+ z?aUqg28mQ%J432K?ykwd`p%)_68RBW%G8-}p90~s?!-Gs1ZDuo`hC$Eg=wClTpt%= z8(hxEbpE0_YLaEBn|ofv#ojh!5!%FU$nSNW%w-7k9@QoXiR2SE@0G&Gb*BG4$Z_e- zE}ECrfj@H`*?!$E+UMk$F2QYiu=SDKldt3>gJ1)|i28?wBtg{%%lY%=L-_zMjDv#Y zl8vE(&(E)4zuu@#x@j;b7_Lw<3}4|>OlsQW|AP^3!|7|&s zF5S};CAe-U#l-ZHF(lw0<@Qu`y!8o@9?2OQ7tV~S^E>CJrdI#D9GLVwtX}B`C_y~u zo*g&C)cQy_PoFD$-SQ;Bp*uSD@MKL%FrV#2GIQ{^^?4mK54UwWyVFe9g=zL^V;e1B zyaN5f!{cW}I?D8xraztb;t$X8uq0pko#$f;7crh~5JK>R!AF`_cI8n1uV2#cvp;B& zl;u+RG4P7t5>VtcX{R`+U>%x5u1seE{mo@=lLt?2dJo8pfaNcfTx%-4Svns z*x2vm&NNBJRHeuZ4QUlU6oR>Qvq19&cLe!3sA)-SZmNn<;h}6{F?~65tmFX3-ak{7 zR6BYkQX(d9T7b=M=7H{C$Dw^G=N&w8)K84#jotK4`Q&7Rvo3Fj#(^qm9o0hr|C`0O zQ~_Znfk8zaoX)i=;o)6bN@K-qOHoLw&sX zp!*`s9ti{i=8ZABg8>g?8?XVW#y@|qlHJGX1#C4=MTPo<%hwbXe9I@dCUSEGA$5v= z!~1A3^N-x1!=2Jszuve%a5T6o?Y{FOBg?z)7y8owO(;G+tHkEbt2la3wcn9TxPgG- z=M6b@o}f^unsTTbu-XP&XLduleCHQ5-be+U64z*NS+bsEQM_Up`9NA)dd8_opQLa*{+hQQ)*X7i2e)uOh-v&1hgZs)>=9$bAH#+5s=4$@9p^RKFg|I8yyl=|M6 zZysM`*3fKOI_k>EL6ONdSufpZaoNlndpAiX?}tG$?cduNYbpIz#F1owMWWQA#ZJ?} zbXS0S>;WNK<&c6x;wyS};Ox=SQ4$ayJ~ivIwdW~YT_craOwlHM+>-wg+kymXpY|$F zL0;ABFU9Bo<=ZBdUK0ELh!%>Eid=nXYD*P-XpUG|sy9a(S*lxyG%1}%*X)^#-pU6( zrvb`!A`Y8o*8?8YL@)$h<&^`BR78)Pi)+#O$jt0eIa+3|$xNiU|FDCc?R2osrPQ`4 ziuN&h5_%g1YM;nYwKhJ~^7n}4cfQ8yL$W>+-B}V)3v?_UoX>@-xz=Pw#U3> z`Ci#oDpz;#3psjx%im|~&6Lqw7Dfa9s+K}(_%X9T@PALwc?U42TwirD zUNIfbjM6D95NK*@b5P6jSqxV(`pW)zV5HAAbn2D=Wx10NuN(LiGmFUk%X4CffDD%p?xJ;wGJXd-TYWnB7!# z2#%#m@5r@`6tWxd&pe2XYn+Mz@qra*v10|ItlcvD_eypj@pLx z>)QVfU-Dp!(#mKAQ?6GLLH^utLzj3z>>0^Vvt*~5Xue+OktwflCipPvCtl<{FZ-0I z1-_?o8(TdOI~B#KOA z_FDcBd#1BebUg9Q!kl~($!6$k)siQzxv=aO8@ha)3JU0GXlYF+8sorpF9MnJA^+Np zjG0uvK)%2YEhy(k3;n{vf^9nBN3y6!7aH7ugobShV#}G6AVD7}yY9s<_+nK5pIgC1wSMk|S9DxVwpJNDk8~KFj?$fo-Q93kC`jX;@#a#2-|=nT z)IqovrUwrmJcL5XP+`Y(uO;1-!@Xpj6&urvEF9 zz&TP_{_j`Z#r1%RvL!T4SoffUa_}PAGhCNzR2PAyf6v;Q8V}y=oWBFsk&L*d@rJSl zs3Y>Ei=BxrS_iJF;*kwakf8mAf?snR&oA;C{kNWGhlcO&|9ov?oIgp^(bicBsaiP& zFk?ppSxdg$Y#1n9ht`7-=RJ!o#V~>Uc|BYupF7D8d^?73+D_v>*op9w)a?(?OwiG^ zkPN~hk(z)wp)r6}1&D+*JvLRGq#8?)7|2o8CsOmFDV%fuMEnPsR(R_kxX}eLu489r zzJUFqzF4FKyaRBUpxXC|)KyoH2Y(4C9kQ%LuuOeth6G-;^7hd%cAi||%+hNn|1XF~ z%iGf25^L@I_J4`_usCE*i02?|`BmV}?ZHG9BSulCj?+tn_6@r7p}Y<4pYB8QdJhH$ zjB@zz@(JHeQReWx#Yw;9~FpZlQV zFfbDKY+Q@oyDkFi2%Lr7-Mf!IIJ6cxT1sBOuIeNL{t>`x5-U1@bWw-E;~9dFno~5m zBg4>yIVnt4N-M&gJ#EQ_7+E8CkdWxMM!$__{&$RFlH*!wySnsE2ocPM0vY#@Xs@34 z_^c^*9$%e&-jnR1 z8c?GmF*8wT*^{q!ge!V%xh^q_bt2#dh zbF*oP2t}WyVI8=uopIbj-CTsFb&Dk4Wo~7w#EI)~0#sC!Z*AUAlF8)PO#hqlaBNcU zf~uX zpOhR{c{(ne>q|sft=P|;845es-NZ&(;|^Tfl?4TRfS25cZUV4}s6Tix9O4H=1I@8x z5kzZn#by9~_qTo7Bl3H>aL&uYZ7_jQz6}ESiRbhd^|0Hwe7avQyYavz7^x!wLWhP7 zi(k0Fs~WHYl_D47T0p7|@|Zy$JOe}sF^z$I$Ja+c`NWe89xU=7t_XO)K5@CR-5Iv8 z=Qag#&VDjtH;EnuHJprmK}g*$nFJ4NC%e%bX&t6_FU@b7^fBMS`3fn9A4#bz@%b0O z!7MAi(rY9VWO>S6N^(=%-56Eb&Rw}42}HuCPO(&79n8Yo%sw*}P`}~pd0V%1U8UTR z7&%Qq6N^Sf2SWNC$tStQt0-SmVzDTH^QJ2FOF&|dxcGRs%a=9b7LmdOmXM-a2k_#9 zry~vm*-ikBx1|v#Py)!t%6gey!&&7K)_rPW40WVHj|+w4=p3-kIESajcK{ZMY@Z+k zchzajvo)%T6w{xbo%N7a=K~9Rd{-{c13DY-Z@UTH86>XppLqJ9JBMEzbXCK_mUw>* z(jq#O7U9-V>{-^&F6$psazb)PGDa;#kl|y1=WQ{zJmE`P;^i1m2UB>Pa z7B5l=-nsVpi5(%16$u_Ixj3>_W11&gHRulkEN1&en*0?b$kY-)f^F~wNElGdj4S*b z>dgz2R)VOb3DQwO$r!$`q~!47!>zzk5q z1W0D=M_nZK%emvZ(;Pax~rh7HXgU-_(U!pCt zxte<^jsAMWcKcj(cg<>`PcQKTPT5qMyW3`G1~X^J+oYGEP$N$q{e6IhMdepjS2x2s zlfY^u(s*Ot-quVq@)ej#L*qXpY(;oj=D{PP2~<2EVQKrHFeVlt zEe%RbNp~11IWol11Jd2i4BvZZ@V9>F5B|_Q_nv$1i8r42c>vb52&uee2wVX~AedOT z!&3y*k-)}_d;NNs?>H)&hgxuEa?4WIfuavx5lu#NX2>LN}j3U4JTwp^NBVFBuJW z-omcbz)9F!i4NA-D|D#7n=fQsP9W88Dz2-kJ`2DK%#aO(>Subyyb7LAGk`+&v+24g z1Odtdv4^7S^dMlX1c;EDEQEfdD`onkKNlnQlW7Xt+!&nVW#?V;mWD&l z2dSC$U+Se?;R|P*m=nlA1Vu)=H|*1r9+s;v?R`YQ07AE;kQQ14+6}uF6*W#knZ23) zkP74CGT{^_j6npO=K56SNiC>L6(@6z<%O{O2>0ZSd2Xna5Xn`xZww& z>Y#oARhvdc*De1SVo%C`^e9e`pD0lMM=zG8E%xIivsd=21X}Ib3<%XJSB~yz(9q%h<%KdZTTSrHfKaNi3f!Lr?i*a@sNxBS3S$*CqEQ!I`(;tmWWF zjgq; zB_pGhX8H#!a1VgFp*~s!)EtO~T}8w6GODO^Te0f2w6tZX4fjd`;i3k5g-NB!D)U&k zJyTMaa8vv4hpI?YKu|Mw2f!<~TFg!Qzd}kzM|pV{)b}aN->`a<(9?1IGx1IWU^{E= zua^{Rv2`^{h2&U1pe9tYJM>~+qW9gq7uB1gtUd}S*|C=&5;S^)_6IOO#tMg{5FMXs z%hg_(lPbpD5JGm37%&4ei)6nYdeR6wg0wk+c)j$K5I~9qpo9~Cml=zlZPtPZI4p|%(fiV~9Fe%wHGge3e2Z^sB9jwG~PtRnC|A$F>mX(o~ zG{I`vae*NP#6qNDf-1|%yi~v$cjl!X;MIV-QugR5@RU*tOWxx>*|OD+3u-XuE6J3# z$#F#Jf9*TEKUkeuzTVC)l%Q)G_Me&uCgRf{z0CEHXwa3p^7YzNjr5OBUb%mLLa%|H zI|DVhdSG7(o^d%1a87WemFXA`16z&qEig=S4eFT@KPXsc0y>*7xzo{<0Gevc5>Q=F zy6aFMq9t4;d&0PDS;@`xxV4pVzNQ8g0Q6hjBmK$zdlz`wyNVa(FzLZi@X7rlrWxM@ zrIX6aW6D>JGW(QKR}{~ou3(3VDaPQG#T>7o2is;1zyS~?BFVyOCajbVaSL!S!-g6n zW#{>Uw(*4f3lj4g`ANdXLL1rmyyVf|13#G*V8lwss%ajSI{Ho+$kyO+Z3$(Hgj-h9{T)!8e%nw zmjI|E6T!D11Fx?I>?0HvK{g>st8tw=rKqeN2pNVJs4udg>QaYZG=ooy^ky!4Li#wS z=)%X&9pCSQl z-IYraa0f)h-jRb?DTvspK?rF(;sR{GYO$Og{?Y54jO6CgG`A*?`lXQ0jE6QyI0FqP z81hO`*=mUWRs{;>YgA-7iP9A0Ty*Ido5sDc+OMk@v?eGNiui0Ph4~Vv&oSQv_1FXIpqKRMel?$J}?j{Wo~{2;Zk!W)Tb(IdMQ0#lH^IT1jZTrzTkDH!y*rEtl#QGB_J|lBx2=78Brr@RNiBHlqj-O3>B)sJkJ8rW(@5=q zQBn_PbMy9?n2+D#B!#1P5$5JNSUX_jzDJ^3y5G<_KA|ae#br|?dyr^g9ydE(>}hBe zLHK#aV{I%mT87t^Ni}?>cp?0wxZP*$(r=WB7^A;S+#?+aqvPCbOI;hTe}YUv<(clB zg+AHC^{YIyNx^242Gl|tK~M~#;kPc-%HsL(6HWhSQ@XOCV0i)2`FF1Ibgi;}Om8FU zC#z4j5WFJ0Z#mCC4jEBfHD+n~$sxN~VNDp0iR=|&vmJdksRrgNk1_Vn_?g$I_;%a5(3_7t++pDXCzoz{@ z{E!@E;IE@dDBa#0taKUY5r!cZgH7>-6d_SYTQxn53#}aSQ zevPM=Bwg&kOif7lMg@X|Che0O@|tfWU+gS=dZOl(orA!;o4mh~3S!RtRwR^(SoTPx zyB%zS=xKxMM%1V=s-P_v>#e*eCGD;JPF!C2Pi z&rCx_y2cKyDL3rzU|752<29b_VEzq!8dGT^dBbM4_kHzKpqftBe(>Bw0+{I!1(3;) zC3@cQ)Mo9XpfRvj|H6mEtf)c^6iks^`*Br7R_xF237U#P><00IvfW@LV2i2;x&u0Q z`>zr2TEJ6ry!bE6!so;K7B2sHwqmazJ0(|S<)1_5osJ4Qf)$_2S6jyCeGcsibgNl< z{cYH?CAs7t$>u>SHPG=R^W*l@*qy=pAZ3F~t{p&C?dQB5;Lg&)(6bLA&#GmBGC znu*xSgp}r7Zhv|r&rpuJQC+PnSLipLo{Nu#hc@F>#YSr+FdMQM9K7~Hre9(O=HZpPuCaz~fu)cvmZE6Qb)i>A>B zk;wIL6?hmy=2+f%mQ42vxjB7%|WY8K~l` zH@s2L7l%+^kQxI5oJ^QR(s&5FA@*(XGF9BtfP;I#ey;~V9Rk0wp7`?QVF5jc6*A! zZ^Q#*C=86*FFiv-9@YW@gDI#xfJdwDo#BVvdK_(PJVZ@jda8LSct8f|Ib}|N&x-5X zt7MU~kfB>t-qY|^y)8IQWyFZ|hL87mh(Cs9qUS*eSI`0RQ`eS*J2>9fKjC^-m8T?k zHPff9RV|3nVg+>_Upl*%X7it-b*OYr0%o4IvUuH-y zwcR)ADJevZY$%$5WJv%wSGpzvG8iAkS(%x~T2OF4>G2Y82-zcY;hv%Kb+ys@Sp3Jd zDcoN>1)_JiTnN3LLbiMwi+{@cYi)&A4 zcFx#FZhjSVy8l%|n_MGvBD!v?-i!Hw17^qJ6bnP*+&@cM~?g{%t~q>)m7 zj>pEvBE7>M42P3Y;0ds6P(z>=6q;ZL26adO-MfK;&|Bs-ynmD9wVsWKq0SD|4X-t_ zd1P(R9mdnYa^w^!Z(E9xN*{@B?W^1>orYh)t`Z)hb6;X6P5EtoeTukQ1#SIez9`*j zvZr}d-|f{rgSZC+<7&3T#yzAf`}S4btU$l9;sEwV`IaDSZYJ06Q0t*_1SSUS8d72j zKkoqR1e9}W-ujajqNgCb&Fks8zFB!35D!Q-DKE7P&}yBwFxM4vX<-)W8{F2nTIk6| zT+%rHoObBm+9Ai4=E#o#ssiKfihATO5++KB*?`o>M)@Q;f5eWaEL2TZJWexbJQ7>zI#!5EL4D zXkccl?tG#M@#Ke`)S+^bhQv);zu$xsG0jIN`2#n$#by1oE|ACnW=GduzP$~c7sS3d zuI;A7t7vH?aF9Kyq|+Baqpjs%cJ`}4wbu%vB5og)N(3iMMWzxCN67JJe0<<)P@TUa zG!^`aySywjQ!!lF9FM|eTp6%2#Dl&hy7t%R^Kp!p{x9k49$fa`;b`3FbloI4 z+Z2#q7|ahu;wknWhf_db)+V*YXxygI4#F5?D1{G}@xDEK`cx~`Y%=y~t(FY>3OF+J z@zWB4syAv46786nbnZG~QOh6Q{%oEuE;1&0^Yks- zJaS-kJh2}7@yy;lz5-(yy?e!DQ<_?z9Mji(yA8|e4I(0lV*4D??LBbVOm-Kmf%NhV zb@eX~9o1fYQpjL*qUIMC z!1=r^^iA}r@7Nym-;ss~TjxziA1*3=!bQ}#Z^QzVGRNMO{mlDfh}zw?jjxBx+TugX zI?_J*D^cB#7&85gJqEMc1W9Ftgap#p+h0Eh2JSQOD!2s`Eyd|D#K3Bb1Y|3Mf|%TK zU6c899dj9U0GWZ1&(7Vug=QU~pNho5;2U3^4Gg|^Lyg|a>hc$%&gW}`uO!+n7qc9$ zA8G7TV9GHwp@!q&dT0j^v|caj%TUU0#di=U>QB`GOw;e4RA~J(E(^AL$lYH4-Do z;BZR42#C3Zrm@88z+MRNRZYHz=NcW2m?E=uYmP~%j-8bmJBtU4YxlvrjMkdp)5@Xu|Bsx^~G(S@; zj~Fso>&;jG^X*}C6c;b8;j0AhB4t2tdW&ub)9>2Vj2M_e0r@5bq@sKv-+(PjJ>A(; zbZKw=Ed`m_w7Q{7xf0!OcQSZwRmqcon~b)$DG4z;Y;s(q3?SuCuYF@_L>f-w9tT~6 zsU5DBxjQ>|joinrKg84-cE-^CEUg~8?r(5ixe+2CiUCdm&u4qPu(OYfa6 z2?MwDT0Noz(@Wm{BeZ+q{S^8Y^Eootwvt}RXlJZADk=FRkp;+^eE@!4R&h%x0(rLU z(7S)HJabwQgR6~>PE26BO0riECp8wu1ppgWZfV(-r1(p>f-8SNMrdgsDwTJ}O>f@w ztTMbE2Wq$HHsoK9-Q{CR*?;7KnXCCN<4}f(@3*JlT2T#T%6D{92S{5ptPavbqU56e zK6oHdTFNaG{&*USd&r#D?)s^5?fFFtDJkkZw6Wwfo^Sli1AHt#O7@Q&Fm7-f?Fmx4 z5m#t-UKW>kcg<$~Oy~IRZ2D$RaGc?KK?{#E`1;V2w&NXS*}8v{i}d*NoSXdW+@!{j zZ`)0auG(srrvLDCFDWE1FE$K4IQ*u}?b8kRW-~a(rN(^?_ixpyFEUX-yU_%L`5W@t zt{x5WB2vJelp4SPx&1eo^hNOlts2amWzEJTW2OgW(N5!B+8X1`19yDJ9p_8|=fDCZyKk8R-PfGL{44qxMi=i`rp9 z%w z9X2U}I!f<P>SFkmBmd_BqU)cO3LGkqFXn~G8b{!Q}>tui}1(M8N`63G+{fOmVJ z_Yz@;S9tA1ll?(~l!xEGbI-MkTXOtEwfpwL;h7E!Q3K`HnC3(E@8TV{N7mmF(w6Bq z=3s27CgS32U9O9UeKb=Gqx$oTp1;OBB~`g5zx+dLn4@qAZA*vMQEgFQgLa+G)+5^& zo5+)cHjNaycRP1v7vHJSl4%tnnf9qF67wXyKNgpC`S99NeetbBM=qxCkIQNpO zT#Q|NNHwAaRcS;0dDh28cb_{z+oD;<-O{)=a@vqd@xRfIX&58zHJ-_+s{>mo$K}}q zIT!yeUsheJzV6!7ygmQ=7#^+jU+DQcd-i5EqPR&clmmDEJIWnX7 zdtFfsL(#o3yGc`}8@9Frj(q+SCDL3C=g#eAX70q#zRsEW6$Sa<><9|jHZww$PFsIl z`^Y5TptIc7`i>%2Bb$n%p^O3cSshM+*(q^hlYIOdOUW~LxA2^S{Gp*sqzhM5oSQg& z4BU#BpKOh?B#d%HU%O#6uv3=Z-(#{#dQr`bAHNZn+f$vToptG9P#gIqbg1AfQ2q5(I8!A z6Kc$?+1%})gXg`7q$$U-*0k^*=iwtDI5K|Tz6R>{g&;wNLhb;HTe3&aQvtVoc}}m+ zGJ&*^fq%Ox>dvI^R0nY@!KEM-u2X#3;{6E^CwFuFx9MUp@V$#{cmC?EG^dd*z*5NF z-!WEMTU0%mCE1_x!C%n+(y{1qG|hjUnt5T~E9S#0o&wx>)3 zOac;Gl!wUZhpQ{JgHNQn-3qh!3yhv3uQeR6GrUY&n}wp1Mg5VB9qwYCOA*D-9PlGi zXI5rTFMcv01y#UoM zdLYMz>_ZWGZ5*ME5lYv4s^Km`76=F_0w{;l)uC`MK0XUOBJzEA-0cp>&l$$!kGYOt znb5_4UMJbW20PYMT1;NbFHcVTZeaZ`strK+9CB}C zAWw*@ft4V!&QqJR5(STmVHGJdlBlhQy>2v-?XSDncHYJ(Jp5^P&a0fwLr-`)6Yb6d^&|zCp5(f66^3WOvBSdWNM&m<3%fJJ{_yCsFu!f!!6V<*@_8_QT z7dKVTnmhJQaDRw~kHPDaj+)= z!hI8;O5`GA6qnJWi3LoGibHXl78U{npwk6(6k!tXMJ@{?v5-a?p+Jhe_dCJYbb*|9 z3o0o6_-P2k<Njr%T#`MDiitmqyHjo|uWMoim zs=!cP0JsiX46A9UTG&dEppbge{n&lZ53`*===$gJ3kK}oe|_<}O^$@nhb`vdq;LrS z4FAY8*Q^f}kb=IdL8i!5`;Uf(hE`C-ONC6kI{37x%xkfV#S$@)NVxJ3-i*8u4_vp( zsA{mtaXKAvCP)gb1Cr3{@x+>GX{E38SS$u*NcYpCTBGJ$Usv%PFO)38LY>c$>gq1# zDrHA>hpznm|Is4sj$`L9zdUk6zMV@vv#~w(8Y9TA8Q5I%Z!T0x+Tr-oQ((?Gdb+tO z+Tyl>gd~#1!0g_uxt%8WG^DxBdrH)ipNe<}Ad00{EMT!ZU-NBlZY~G(QF*nT)*39q z`@sVQLQ66ya%$@SHR+Hf#g`O&7jN)4i41^A4=X^%CF+weARTE z<8?e%^&yDdbUYMJD7_zR<>*cgEqLD!XY~KR1&v9I3iEnI z&VaP*IQ>m&PL?>IEA>MrUtpmd^x$>X%JVc%+PpNYUs-pgTm0I3Kg^wQ^hA!YAj

  • PYZPdI0U6>1|UHqc(S)4kkWGCVSILNg`tPGzYm*a zdc151bG`GB2-k4(sC`RNFl3CAfOW+fY8S81!xyUf%p-eYp)^$e(jL70^bN8WyMQ@~ zY}Y+cX5`}hKwe(%c>dzg*3`~5?$Z^&WH?bDFh*F417;5j!OD$77v$JBZ89%N&OV(y z#Cd2nY_;CkWv!!!>KkG$XGira5`dLq4AI(x?||HFpe&Eh-JVI&f>vQQ^e9arh`2Y~ zu}TY-rOy!%k0%0`0d#>9#Tk3=zb*OHx7CRB5ZUFl;4nuU33`=*eZfX^UMxp~JWqO$ zq-L=I#7J;|x5<+@uN0Oe z7dE4i>?{SL>aXWSeaElf^qX8{lV?sP>U3+yUZVLOzIt){fxp?m`s9^MEF&^2S-U%L z-Y?QA42{ktyHS@!#WL(R&z?MaGJ=qK4UwX`fEGsQ+|IxL5-~hf5HZ^AiQ`$1a-I^X zt%TqnAYGm@u!<#tk_9&(UxO?0JiNTq^}Bi5i+jucJ9Y;)taR@m;%WD&Yg`lFQ@Mo+ zqYTi+<2I`TN{R)gx$2w-*)cDLDb`{<#oUjf0f*VCVlYHE9R%$ZzxlEekVvG!dhR_B2|=IvS6P`Lmqn*ns}dlVq*z4DX+Jkk*z&J?dgo}||F_YE=~ zH>cewz6ACAcq`T38BMg5mJcf`UsBFmSQ^Clc@NoMdR&}iC3ak>_y?7IFNp<4gcVe^ zQ;MgGWFgL~0>BV}7JNV=JP_VWcS!6Rlc{uIQ)>B?QC?n-I3Z9CJ|go%s}{BcZV8E= z5aKa3GB3NgS>a6MKH|dbA7w+jkyAt*x3uQq_wUZ#J5T>6O^IRli&B#=U+d}V2wcQ> z-j7oes55xvlD}Imd`3@7ATKUrOM=kNSAl-J&Oe6^C4+rty0J3rABPBA0E4v#?9vM` zCPoN3%Eu=${JQ3A&pd*OAg~WTe~BW%o$vs-+Rw^5wc!oDi}5&>^Ram1xm0|kg7hY- zbZ=CEzh8!b*8HZ9Za|~>``?tHG1%*;=C+N_8OCKqJ9wt4aPY3bZ??cf4B0L3dJUw8 zeF@);@kGx|@&2?R>79%g@1&0xojQ#z%|e6UYzdAR+Y2hL6M%>8(p+Gq0N5U}(jc4z zaAGLi*knPVJ}5l=LrIC);LuP?PL49{k`QxH0YQfS@IioOAq9X%5E~1);4qN{_=gmL z0ZVvz!6RlkA?;O`uS8yal*Soaw6thxp20X{J34gf|J%jaQ;fL{$C=17E=J)4!-s?Fn&P?FftVm2KIT==anX z^UlSK84n@zX;<8&_W0O5wW!WUW4I4+=b|e%=Q-h zO^Puk<9G6W^baJ-|3TmpzE6Ry_S0BnF=(Z(` z4E|TVf;r7AcHN}$nv6o0B#`%Nu||9y&7GT+I!jHRC*^OrQL5!JR?o7OjC-z52LX)v zRF~_p$rIrdhDkYf0z5!Ewzlvpi~Brj+*t>!6W47d7Ovco3mP zJm$lRD;JPQGZt_p+GR81(%l|O!{h#8lc^Z7cbeS4d%qYJLGypRH-Ne_zI5?KLpoi5 zSI0TalvkqpnWf}GD3qCOk>=v#6`&@hOHitVmcMktAFZU?EH?@ju)VhRLp!_dWt=Qc z+i_5CDklfLQwt#*xn55UmTx)v>q5AMby)T0DD490ZH0|@pqOL~+5-q@Y`K=lR?hCTdxtdC?XY{hxVd97WS zFdFNd-xk$3J&ezm^bSFC=D%&gR>29panT#ob1;x@rO-G4v#Qf3#GzXk^)g-(rt*|w_}BAnvq#}RJ93n;1u?OPiviM+ltRI*zc8F{O| z-WuhS-Ak`I$b6)}lkS44rrgxUyY;@qFn4>#W!q@lSpMmdGHJ~45)GRLH%4dG#h03A z>UD;R$q(KO?DsADA=(L$WYtB4(HFG`UTw2_AeG#7dOA9v#?^k*x5I-S;^_Q|TJJjP z90h;3t`xaxE=`q29f4@ri}GlT;+1Vu0tYNbIRFbm<)x#%ksrkhS%dQyAwj{&t0VZK z_aZnIV?r$sTYO%*=%M{qZ4mwwi_qxo7v1J)-K#N1Kld7DF_7VP_PulpQMMvA*vycibk zuSzQc95Tvfj1$31%6wqO{a9%$JbnJBU(-{a&5EYtwcrr<_@>Q-fpL}O_6FH5lIYbf z?We7GWI^xPt$FTt=X1Ry^*NjFl2KoAsCO4hy~E>}i}z21bFChHLVADkrmBa>STiT0 zMMBapxU(`!fY3%3CJF!mpNy9RQiu}NaNyfj)qQHQNEMO{CVNj_b66ohp35MZOZvk` zQT+XHdvA;1d4(|*yi*6TvhDJ%;b1m;2;_OaryNCd-O1F`1Un4Ac1bTX8$ks{Yqq55 zA1f#m0?N4y?tnGc!Ko=Jy#r%W1pxNQ{RW4&GzyL2ri#gZx?Zf_yhv}}PyAVu{-8wt zsziHZ#5%us+DiC;n*yd+-(nggN7L46aqx%EUcR!5#@EHf?ijVQo-Giy(+=3!WRXTB z(un~N$UlXj!tDR)$zO;dtR&bJuoy^(2U%&6z|eLKl8_j;FAYyGZC->99H`9_)Soga z&2$QRFCsb0(!X--1YEGyDrh`+RxDQLjQ1~$;ntE>1lFTN--2zgQAtgekDW$yq1$79 z5|NNTdaN-0Lsgr?@E>qep%p;e(~UgHwSUT_lLW|qqfIgi7BpYTtH>&Nf?GZG0@h1m zxu>IIw57O-tGiK5xrd{?WvN&he|Z2zk+vF^|KoP6(q2d!x^FtHEzLHX95N~YVHjP~;*}WdZ)CmXCk%Fn&ruEVykH?hUnxAjY3XgqL1;c52Q0@U#(C292R+pv>G7< zgw$yC)m5*p=5KUyG@v*2k}=a#o^zc4dHi*UJ&&f;5v^S%i|^>0KUH==|7}X_p#7tG z+2w;A7x%2(fo2)If^3|;nb_OAR1VpH6u{GIAoYER+vQN}@NTwj_ZK z^R9}*xF2o|%^K@N@<8raZ$PJq{?mRhOhhk4Yzdxp5(vYo$W-{J1Y()^w2}Y|%z5ry zervWYaENu7W^f7%tD-6rh&eQ83i3mxcw&FAd$M{1-+%*H zEx+;OVk*u!I%0xPVbF(EfzgtA*c@^p$0$YOOkWP#?ztzirclox0p zhLS;&h-?K2QW8*w@o_01Wl_VH6qO>tGuXo-1yx-4mII!(wdIDajDP)wYT9D~LM{#{ zo}CN{NJy@CFXZ-~DIAsv$^eX7vlsDXXVjS#sla2G!+z(8#aMl5@Gda)4Jz}{(3m}G zyj~tx_j$;+FG7czsCJ2FNs@UpK%F>N?P;!}dg&uIdDJV1j*j!Z0J{L_coXc{ND?tx zrGuBBW*UM$0AV1YnnxhQkj4Y0D2i&jlUIlLn>O(5QB!qx2;h)MbUY9=FTV{H;ia>x zFk7woPQU=MxfM>nWnFX1o_i&0j(g5PkDous{{K5%2OU;8A!}+7TeVhVO)8M{S7F5LTJc(!hEFrclvq zWp#BFM4VcocuZA45mX)>=EbdgvDaT8j6ES6Y=n=KMkpgF+?oe1w>jX(DjyuL)wPA1 z2vZ14x{wwLoJeq@d4K%VsZt3n*bL^n8a}M6U({FgUB?X|=JfRCPWu06KlQ$?X0aYl zkbx{6FR2uJM$`5e7C>B}YodXg56Xf4Gj?P@i)p@aVa`D_K zKiJydi1K}hs36h?G-;ENg8g*adin;5bV5aUTY5>qrTNQpn6%9xHH+%vz>#fOw}h2~ z86LKvX^Vz&;>^#yN}Lq!Gpafs;;6RQlYIC;WCr#^^=(=`X)bQRA^E_U^kR+-r!I80 zgV`7ik_wtHY|`T@N1t9tqf2dAx>eVeFpDaW(H|FZQSbd; znG9_h77RP(J*2n|y}KZp;KKqyF34Rg#rJY2zw6TMPA?zSore4m3NS!1g9(JnbSP?% zEH?PK?H{@|uh6u8@QJ8#6nig!^*QxUThH?~>i9H2d_!Y&)mHGHc*hfwD8DdmBPtZ+ zJV1Pt-UGMz0*C-1%`12t=dV6xLdjYi-cWUjl#Nkz6^cfeRUg0&+w|4(Rm*V%x}x&d zCP&um`_X}%6K+_X|IONUQ-E=+7(PgjsDc=tKNJ?fY@#bw1_ zz(RcV8x(*UL--jfof_1=jRmk`w!^CUZRb@re_+x=nlPv!X>NIW`8s<1`P?NT=?}NXbeo%>Z)|)GuNfVtBGQw<$kt>T1AsT=?~W< zW1*&wTbOE+Pap`!9zf{>iYoyTq!S^Z2b#TszhoZ=x!Ab*>58@ZAl6_~_x4OjscSwV z3r@$1hk@RZR%p`&cbVJaNG*ObyEUmGXNYA!LO~H59aWSNLfy`OeTag4Vf)(ZZ09Gt zjvlsf)>Bs7J%#_&__~ol?FX#FEdvh45hM)MgL~YUwIOOD4{@$cKuF@a$f`Z0{JGgN zoqjMmfQJ|0TUtC?mps&D{xoUl?Sx_G+tHB3DHR@-S4>u_Jx zkA(?0!Y(~RWZac4e!MvI>g{36E!edQ;HZ1IgQ$EXlvXTcN0a2BILhI}N@te7Y<+~t zZN#EFo>8u&f3A0q5GaYOu5N@n!Zeg^=<#?3PfYSI2~b+PWhfB#1UOkt01jh1+MwJy zZdsW5n0yA*rojULjgtja!TruvdfAPa#35bOuZvgE331Wo7c%C$X7^^}@kBlEcmJB2 zI)iK8;6aWpRWh~dlv`{{>kk~*sxrvk+lyRUKBE4 z7t;o!tR#*X<mKi(x%6LDMfF#1n(&aXZaq-h$*2-0G_=bJM3 zcJGJ5%7MJJQU_mn&A(!x&ns;O&GPk|V`ES9sKm?_t8kq4(gM=32sk4^FYM1Wozfy1 zX|Mp_`6w&kS*6l5x1kBX&i zm5Qzt;Q3zy1O9{x@1UxO&Qx7LCEepTdkq$Jq%9e!z!%_ikA|71-!d>T$Q7m042}mv z4-G`?3B{xL7D%voDmW5FG2eWGHS7ffXj^3J`RsBe%8odi!g03MusitK@g$*6rU;K4 zO4H+UZ^@9rpRE7nynC#Wb=BV0g8Ql!1BT zt23PKs7N=6TMfk{_XFTHUtb-`jUw*dq@0}QHYE8}A#x{JS;=nAFZ$mjJ?xX@xrP4D zkV)KbpTP9+6Qt#3iMJua+DV?NqDHRn5cFL%+iUPU4m#%MP6sF3kt5MEvYQHF_8)WR z1&;eEs+cJY>Y6|fRF^~+#j&#j0FYX7$^EK@%Z_ih~guMHIpxop3IQ#J7X|> z*y-IKVc z=veoSny9r!sm+hMJt|{HVXXaVQ~n$Tyw^Eb;iBd6cdn4P21-gFfcqFy82_? zlo9w(rH<4)8Ob@8I+%L?jzhv$9XtPNqGaN@5`Jg4z`xRKq}KXFgci{zhMYtyadcoQddii%$G}LinR_Mf`8;=KAsTm;L*~uinNi{TWgl zZ#`>nkDF=8GYnM6XGc#9QX`cq=wvwtPCw*vP?&Tr=mlnI zM4o^+T-^Ql!0YvJ&3?KTnI7UyKJ5LriQe{zrmzYGjJM*5)W3b92XjScW7wc*90m^^oW^?sMHg|bHAD_i@02p{A!CCT7_yAZsBl;b>=5FEY6PhF!$OceHRt z{N#{5t|Ql`iho)+QbEg3tx^@P*A!xOq|tLa;xZCj2=Oi38qUN4$aS(#fjGx;LU6-F zT*(xj^!SswLi6#T(*>M^uCsw2i!))VZ9lY~$s`={B>x4Y;YTRriQ2*3D)}^F0wG{y z;j#3$o7FV@oSiS&s|RLzS7$=k6Jull9oDh+jDMY><*wVa7*X2PgICUjS$;a95VPw+ zUEpIK9?bW8O1wyvg-@hMG}OxS3!w0gas;C1tZN3OyE3NC%=+c2lk z?q1ktbzc@gl9ut=xH@d7Y-jo1VHipw_%NvHHGgoSSs@e=PQK#fX?kiNCi1c8RfQ+K z{AGFg@4PI`E-?#WJ}Cs1T3fvI$=#0op}&SPOju1GUxs}B@ell%eBpCLKeV;Yw{~|u zQE%>~c5Ibw#MgCXtBrSYgIdOYxnA$j!aB0okG z!>YtBY&RJ8mD^O`ZDX17dr5LXz0j{!S7$taLuYPUy7tLgXGX2t99}2e^w(D0NcB>N zJP-H_AwG^@vMRU%C8D&#ip(+0r{I^ z?dz+H*}{Ao(UrnN!omac-==SI_dg0}s~(E#xeUt=`|&%94P5+7bB7B}!J6j1Lj~(< zW+{Jym;ENb*s}uLW1l8!yJYYx5eMv+T)43>3bCve_rcb=IK<7 zfhl}iRUHGbn2l#^IaeK31sG1xO8?kjC?WuD7@ zM;-Fl=wbY|TGK(d-W-z62;Xh`Uz;zMh(9ChJT6onv3-Zc`giZa^_c>~k!;PhRm<)b zt5)+VPReW8!peZX-*@np|8%LqDDQ$n>(J6!5wZB?O&qWD19`*2)zzk|L2g4fKLT5^ z>;GOMb9cRYwe6-suPxC{eooTzMk_C8_j7i`!#Qvi3~Xo|!jZlV7TPstQRl@M^fDDo z1v8}T;IY~`g`eAIVqD=~S(Ssl7J%vTVw%MBf)nyxY}mVw+D=u$fA( z?vSck`d50cPhbhR9+iL8yuO9CR5!1T+j2dF#g>3ye2R{+_mQ-E@WaHWQcmaIu&mH} zbNzXzN3|wpBFj(dCIXj&6VUXcG(AyeZOl!7m1T}-m+Nzr`RuYDD(QQT%`NIgZ}x~v zy5jx{3c-rHy399hmT|&FdD@BYA4!zBa**_fl)YVKqRJ~|_-TT>{ zNZ=+|Zy^NmN4?crP?OfxC5f?~^XypJsJ3NNj?!IeTjS9wi`9dzKrbg7t?L;(;pSqF zVtLrmqO1FZ)5lYU$_c42o`!98x5B|BJR&aE~5i$2|q@%z~+7|2YjkKdZ>1!chrop1miX)X+gsKyjxpav+dz${SE@F*$azm zIOq1h`P!hZZ3p}CZJujkY8h|!C$_-a<8%#?5mn4mVIh_yTxvUDy)24Z1L9@IPDTeK zv9Y_FT&@ONsWbp1dmMVaS1TMXYK!VMxrW6IiRvQjZ@X*u!?Z*V`>>7Fu0KCjnrhZ_ z@SOc+Q-(0f__>Xji`}%SDC2*hJh#lF>PvfdEm=T>6tI}>`PYUkM?VEUh66N;QMtRBj(w%3)z>++k* z8sbYijgRQYF>8`W=a;L?Y%k2EXArfFJ?=YN_IQ#rvcA23A)?naKz-7uRZhx+5vriC zm<-sFNY`mcB7HD5tQ#}p|FLD$V0Idr+`LKh8t|5sWpGkIYphdRBF|mBfXJD5i_G^H zI&aP|Cr31PcZMuSddi|LqQa=3G8yw0me|F^{edics@z5|+x!653!k+ZZd!j%kli-X zhr1bO2Bqx`bzEtctZp44ukP2_nY(2{VJ~HNeynbn zyisO{uP`hpRSo#i`!`AW+0}6p&3A>L`Izfa737$aiB_Z8?S3nSaBlmz%hP_Y{k{JO zNo~v3bJ87fYH*zs%e)Z6qovB-|8#xbX6sbL?$Miyt=3FW5-y&h(~N#~$6mMn=KZb- z>B(FHR`n)z%3;JzIgIWs8_jvEog8Q73?LZLIGu8vka8Samh_ZQd;QrlG7Rmq|C>Ok zzgOXsB#NEo=OQI#)?8{A5A{1lN=OKZc9`g=-XW?a?S?b1;|>Ofaiy|2ph0DDjt9e7 zG@s#lO1EI6N8=C}TM@Q8&Nno|Hd>;&`DWoExW`XXI?*6w~`^9PWIJa-^Nk6L&Jl6K)GP z(e_@lZ|UaFDoo6n+c>G~pr~WJkZx>Zb_&^Sl=kfV%IM+{TWPW!qd$AG99y(P$wEwy zpo%9$AB>o}1iAkyttQ%-AJXc;UORzKA#-`c$8DY$S2OP0on})-S7vJ}yu1+14I$mvMwBuAXx>zl z<@{~K8b6Yu@z@w9Xic^NN1nd#p}jlveofGS^QK?BY+e(lMndQj^W32fZ8NmHx1~52p!oi-5C1S>S(pRf6N4ibLee)G z{JEzzq9iw4Gv-D*>VpIlURzcdE2t|XPnFVk1sv~rYo-yTwW=U(xm;lYMN=sv0Uf6G zl0^yGim)W~;wY!uYx!|DS&y~Yfv9MeaN_jq2OBvL8Xi_#d^;hq%-QMttvlDwy=Sh4 z1>fGJDe^w8@JuxM@nZqUnu165TTjw^D=5f*lB_;g$8<7U{GML+cI|@(7Z21;eGi=F zRnJaN#BaRZeE>vxuxS)S=05Hn+exCwZG5gpZ#KQoo02(}LD7%$aDY31BUq&7ZiKU= zvprPO+$|QloTz0!ep`4{WU9MbCAx!rhzU!la{E475(321)kc|l#xxu1U|CZKD_Lb( zMVBn^?<1nWJ|o&)_`rQiqbOFjN{wh0_dht}^^AnPha@*$1w7&0dF>niCDYF950qSU zHMMH274iD-}2N@Eb%Dj@SRX4Kb~S(%gjzR}a4gDGFe31TD!Z&UHR{N7K!YkEw}n!-Q2qCLCzE&jO9m+Sli7WM+ZKa<-c;zN;tOv zblVJ;qPP^-nW?v$o#7uZuXHG(uebv9*QGoI%tHN|mEiv@D!S(83p1fTQ*+`@{_vl} z(YhX1X|EY|tTbI*)^{TJN2`pkQ_%L_QzFjtPG|f7k@eqUO=au*I2?viUPa{0aRe2C@ra-xMGz2aI*x;M z5$V;TNmq~(0t9u085=?<(t-u)9RVRE!2%dslwK2*5+FbzA%sB6Z|xxZ`Cjk(1HCSB z?X}l>>U}@^S*R=-XKR7cOBNWt*2m^0^T3%LVjU{sGY**4 z6WdNqw|HjlHZkC)P-J1}LSa2DTW(Orb;~aIoCdf9FpNiPie}P}U=HWJ4ojJPXB~CD zKcB;+R1ikG(T+N@n^@s$C?s?IrmxL=i;Kc0G_Wqyh)VMs1v~psJmthP>Pg6L9`JRB zY;x=4?n3}N8cCMq;6q%7@<}*e)1<%lfFo}_5M*RbF{7EzyA+9lZ7-->II~;Q8_L2I zQ6o;({4wKNkZ?p)0TitDf0DpB?=bLm*scYLtMcIX_=P^|BFyEQg`ceqkVQ}Bi`Y@p z5(aJ2ND!LQ>wT7TLCkxn?AwmIi`Y&>Y3Y$Lu-74@N2!WLRq_N2m?@7Wf&IJ{wVFSL zQ%XLDABkc|tQ_kP3D;NAValS0iN{A10~K z5hsgyb)#|_nnh)h{Sb@;M>3V7?QpL!(c3{uNa(=Z0{|mB+ zTYBdgmde6})}QM8yI$t4iJf(-r-l*bGQ{i zh@9ap`kg=^vC^qq=N7pz;K>-N&X~+k>zXuftY4i@b=!bL?s0Bzu_Bvs|0sphCmgOg z1cDpE`17Cq-5q&Y5Rdgf{I_2+4mCB>q9h8TP2rwh?_I#}Jp1QWeJU|q4<9XWx%^p_ z*2xqvEl*vEpA08%=He}XtnJ;^M%b7OP}9Hy!eZ@Adg-_`gdSBM-EskYUsdq6P9MX_ zSZkpa>>GnZyRkDo$AhwZf%vACb^Z2VxATXjLg*+Ac{O=>)r^MUG8z%;VfA@cMUk3y zfs_-I)zsA$xchXz2}4QCeq!f#zN2(Ly?3`dcbTHgg5Mze%mng68+JjTsq&Qdg*g@u136h&ZkTwZvK;* zH2I1zZzf@2%FFGI7KAUq>w=zkZ|iA=2%*Rs9Ki~i(lnV)Kr5ureW1M#aIq_6PqNTS z@$vCLO!?3LLDEeNAUTeRRc%bMQTPIqDpWNX}HX zB+HCbQKIB@fL5i!ZsIB7OS4zriUxIvuH~Xu$_9XUb3c7k;4-DP z#BT^iChkMUxIVenS;f))J8E--0kWMG2$usoG={XWFuYOlJJ@r0iO#E`@ryI%6HIWx@%L7mRSdh}GRhPX{ z&|$s4O{}$4Ap?KK+b_i+N)946X+8iz$8E$P)hNQgy8JzM+kw7mn|vfTX$_k$wn%yO zSFb`{enSb*n%% zXwYa5&O-hX(kUyx=%eCx`gN}M{o2!-GnFm{1MT)zxRT2Nk99Y?CfMEv9KYL>o9tH; zh-wf2;_DJhyzj`UQK;ST_iZlN%TEMZv%N9npJGTewZ?8V@aORefZ;$GvH(B$Q%bZM zJoDr0Yw+r2k$%c3h!kr9=4y)$yne|$?6qV7I8MQMX%^}f((02u7^^zWTJ`*zeV*6M zD>H5Wb*0f~F>ObUf-TyuDcU0_>PFbxKf#nYwycX8%grH}1YBBuKnzp6OXf_lNo%dv z{vXr!$tcLF8mhv{FQ!ywj4ikYc^;Iv>{1KSf>#gy1KTOCVb{IQ0!p%1z7kzfiJXbY z0PL599P%E?Z%dE924tK7a)#HoL9^{-{_^9}ks%kI$-EeEiGc0s!sCz84^tntj{yvg z%@9FpyP-L6;UIHJBhVlOR*v9Wb2elJVfoSjF$vHfc$Y9Y9+e{gE2KDk(r3P?fK9jz z(s<@f#Mw$S@z?^}g$ba~TY z)1~#GkV)j#j$1-+-T(_iPpVlX9>JIq5IDH$tB2s#y7g!op}V2*Fh29!yTM(U!zVEE z*5M}x?*%q)p!dUB+QH?u9Ni+U4#X2>^Z|Yf;^3h1@+qWqxyb12Dt}WFlbHp~qrS&d z%FTwU7zJ;B1FB;i>Vct4pC8eg@Dk3&@Y|=xdXvS{%uPXNUN*q7VU-?-IFJ{1CVYYMKiOJh)YCR(t9cbV*Hiw&eJjT_~H5`Nf2oXMlwV=5Kz`;W^7wXP6MveF-^yZ)wzVxq8f&FKG(CN_PYc&%xNSm5_0AQ+#svgjStVglIp!t<>>QtuUy2cast(P|E?8`x6d zkPA(J6o3}T;6lx@O7HXtrx4vAFVYN- z5P5B;N?j3aT2oDkLmIDYRS}j;s$&2{JYc2*1468u51w|XUY?Tcf`qUcXP8U?l7Sud zSLFkCVk+D2aPq-@quAtGY!4Adw*=xP z-K&bv9;1_|>0r{UWc>8!Y}Nx2f3L%5fq^1ID{>^{~vrEDj+iT8xugGg82+RSUf;Bk-_zqH*1lfCtVByVU% zFVdXddDFVXCt1z`fYht~(K-vI#!T`R2qu8WuRUiC;GYe}qnF;Xju~!dumslOnIBUc^8QE#*#Ie zq!C1qLCtrP6m}o%9Hj7=dD7Hqutij0cG{|lQ75tVaa}v3r14PCxKky_64VL>sfaE* zS+v=_j9`p(P)SsHQqG09 z905R8VfMwg6)X}I1o$+%n=i(ny=)-icAw`sPV^Q8d_eQ1m|!V%2X zXs2xqN$pLsD~wm$lAbd6cJeXFBMQfVJQ=dg@#`3tiaJCulEQ?(7cLQ4Y!iXITZq)! zzkcW1{1U+*pLLiyv*DmecqN)XtszNvf#U#vLPPQl;M83R3COPq#;-OJLhHBvJ60!l zp{p2q(bO_C0RV zwT`Oa~lF;IsNJ*$ zMHd4dv(=tw?d4xgjRLZE+A%>-@e&P4T*8Sr`j0xSyPAt0I--WHBx6}-`rc+eM z>ggPYLD)ruhSdH3_U{a1G|~Kl4EIT63>Kz8p&eJ z8J>~b?9RCQW;?`C^Bg(5(_j*igNXMxF_fb|i*9gUlbhbtUV~6C+u#KiC><~C5Xj5x zD6Q14QSN$PQA2>dCEbpURd(7aR_4nSj?r{asSY76zH4yv6aSLsufbqTAxl-E6E(=8 zmWYF(Z+X7EiNa?}_~K_fY?yF@xoX#4dB(O6F8PBe^Ze902|iM>Wnm`ujNJuETEw z*MDx;R&sv8qfzuEtlq-Rg7<`qzc59bW|H3N`h?t5lie42`RM z-x3Z|qZY~<7#y#owBNnFdKK6kHpJWAg-%$3!Q)6sJ%DZn??!bQl{8|Jg(!h zrW(9JrOlF))t87h{Gmh1N5ivhp;8vXP%9ldoBT+#;)6b0r5WHo>Erdsg0b>*Pp#!qhw-dE&{?UOoEG3c?hofkr$JFij@lXh^&DLE zG*)LCWjEDfH*Tl%vZ3mT?AaLncNi@0+MrgE^8heyniRlPs_MBHI5L#9Zxw(h50G1W zws%Vm=BTE1xAq3)dvPXieK`?BjZa`i7&d9-=wnkgz%GcR>)iH^hB?0V-r5LQb7j_< zk^mCdF0D&ya__j8A1Uf9I+aqt%A}MSBAfpUjNAfD;CU_-_{0qY8o&Ri<;xHYZgAsm zS#78wve+CN7d^e5UxgpX=z$qM>gAmpJG>v?r0IK|cZK((iDZ?PA!`Y!@s)8Aq?@(uB`YF2fgz~rdaj^nzL;_kW@8ybUP5I zo#c@ORB+Q-_S@V&(RE?Jvkd~Q0iT>!Ms`;60C|NVLEd^_dvj%i52oDkAf0!8J}1umyn*Qz z0?sRg70Z|b)f^)rI$_p%{67dd?5M3%TeDB&KspV?FX;YU_CD~TF#o-!g!j0&X)`#e zzO4xj57YDWXaVElK17S zf>lo|Hyi_j1C_E6)j6PSz4IcFttI>Fayn;qSD4eOSge|6 zuvA$?^;u5Qx)n&sUz&HDU(odb9ZD?)qq*?&KvIA+@DNIdD@eWprFp6oX&ipG&{?(T z^OfM(miQ&-#_JBTv`=ua-C#E@2}Sb2l4X;W3EFOU-fY%vy#gZJ-Y}uy7ATgfov|G8 zvHg)t7WSM4{QoF@s3KVvoiY}Co_kVea3tlmW`D;UPWkSRaUjKUpePbVAB^QNLXQ*G z>vWx58(u+&7Xwl}xe~2#iiadAgApA0CZzRET7Gs^v&9b!{_@Y!Jaru|mcSxsbn5D5 zEPM?(fpV0pZmPl4Ipe0oSH{9O;o1YPJnrlR@sAD(oyy;#yaQn)3h7-4P(K9s7~^SV0x)arQx1l2^j=179&E8f#5QSAL3oNX98VRiz?$2cFTbMYurc&RdoEvXAl(7%) zbE@g}#2@`83lqKz;Q{QZ;nRfrtxEY zKM#k_{B6RhH>lPka;K&nf?HYzfU=t)8Mz8fB@|dY;T=>dAZlIH#hNM972)xQ9RvLc z>iqu+j$xx9?9yS>5Izh~s{?vVWwB5{pYkq3I=5aAk!Zs3*G16R7(tz&j8O0Z0a$w3 z28j%LJBrd2AL!8GVF@Q>PxSs<@Y>tjvJtWA=XDtG?hQp)g3(;4eeF+rno=^i`#6dM z!pH0WLG2}pq*^*h+H_zVQLpD%3HEu}U$D=9wkj49+)CHhxm*)8!wzIK85RM(X(Swn zdoN<3{kpH;$I!JLo9|4dn*6O!W8OpwDC;)0*z{C?-dZD~pJh_}wcae(o;I8V*mA*M zE@y333#t7+9%{vXIF5EPyi4|FZV<{3d|D3+F#)QGIT80tVH3 z9u#3?aIw~9)8zR0DY3RiG*sr-@YnX%3~65b6I7xDqu=X*6HUz0uHAU>1%zZKz@9<& z<=j`uC1383f5n_p=r$fX+kWd>7A|b^eS`N(dpiTFAQ8`PK<-5wzWNS7x_9~)RR)aI z6h({6M2xv=fC@aZRBsUJ_yqb`f^q@nF%YM>YC*|JoS)Xo5^X%|1VB(zR2pAyB!>ff z9mlQnP~Og+VAD1ZFj92`n2dFYOXTVWcmI8#Z5O$8-jzQrvhg{-KNu{_XpL(cPNr^>PBi zXKzvZ%}!mEzQyt0gg{3?D?b{?rc!(?g9Ol}VB;pVPun@bmQIrIDy%=SW_3N-JJQgz z089{kg;L&4j;5`xGMSPPvFU-@;STcV&2gj+M9WB}+hqk`H+dY3pl9P1M;`zj2Ujw{ z`HZprUL+1Y#%V2i^FZM&kV?*uWM+kQEA1s1b&ueCqJhjWX|gDcbX7ra+$t}KMc3vW zbF=vydHAn3!)pXc4qcZ&=M}y3)TsNyp~@C(BB9Djh`tkyq4+c*S0TVbddBiUHPp@+ zuJm36cupfk@VGAs3W)=95wU3j&bBeUSNx=fTkZ`80lo3%%J5#KYc8mqbDMtHyLae> zk-+E+=G>E?wj#U<($WjwpvJqk_OuO}MzvIFjPZriEHy0wMOsI6F)Y$HycwPW0#F=a zyEmn@DKB)3k+-Ws^&tmOHvA3Lj0rwB5KPKROIy3mM_=#@KhK8dZYRqJ=Fh{WbrmKHQmJiPF@W$@Bz8X? zN;8b@=KIjP->;tRz^ovBOyxCDF~Yz9{@boU?tJ`jxX{J_{G6_6|HoMI#5=lQ{|N7O znQ57_ZQ1|c^#AYE?iMj2w;elvb~yH*0obm;&)NUJ<|U8vl-D5A#9hk{s9!@I2!0JqF2XG(#iXC`{=wlhUbikX zl}68Ap<{o7#oa#xMSgu#WmkYbfEoXB{_470mTvMWK51;@QQphiH#m*Qrhb0+scjMi zL9?AS$udPuY`WE>9r-^5WJ8@~v)II`d(MWugx%A*U8sjqENWZh0u^w8S5{P<|lSsLpvT=Xjt(IDNC;8j-u%g0M@53ZPwmNTCB^QS-RUF-Pp%XF|J^4(xCL0Ys!_BX&7zwL$rOZP+%ZmLf6 zX<@}sBTyF%u134LdR`pO=P>v&c`sxta&(?Q6Lh_Wo}_x=7vW~)<#`ho1R{hNOBmxv zUDJqG)VdbwQO=#U(g|Ceszzk5$wth?8>LA+1x9bDxNtMDsnyH%Ei63>ddh}&37iDY zJUQ>G;xwKXt=JYlonPuqwhGUExpp|$0rT+qR?l+qv}UbebzmG3sX=+WToh;Cx`ic^ z_oucv0ba0>B^xtaS&fMP+Qy{Q z`Rof0^*2L@^}}U`pH}2Hy7}$-PP)eUaysXkI4Xj`@h=%f{$~Vpr)zrfb;L|tgrPOm zeE7g&=ty9Mjp>%PQ7@zd-*y=Lz>d-}*i}*3HoBIZQbL4>wVoC~vDM%jT6o9l=}+@( z_>~9!i-sRhix-)CTwqU%Xsg=W{@)4n2madZ(yJPZ4fsOGNEDP{u7Yc>YUF493zpJX z-X{q556lMazE|cOOLgCH=7ws_@!`t+D6U9GW@hHYKo!0|Dgo`1ex-;L0g4pd)zqP& z^jBTjnEI(9Q=vc`Jg5 zx?q*y$Gro(%5WkPbrWG*z|RlspVPf0jis#LpSQcZjsuwa9<80g1-e%%`K?E!b5RE)BV!R=&2`(atg7>*d_ibji5{N()Iybb(a-WLpI;- z-_JY~J@V!uxR2v|>yC5x4jn?>?Y=|;Y)~m#0dx4W8To})tAepQ+{_xcF1eZF!e66} zC4qf*a{nI?hoO0aZhj)RAB4q@vQRN(*Jz2T)uEn&=oyOmbos>+#d*fsFh*jl9|L%q zXYTvFq2<}Z^udzeUCkGD+08CBIFC@?N-^B4AJ4wy#3i#`k-#kUTN3py-};13br#J7{Nu6>#V+E6l2D2@ycbzZ(A0pSXg4Y zH`0l1Fbb(a1rvvEkrfv?**?ixhSJy1s!HOiHi${0L3-e zGRn&C1-&o5AF6);2KSty|Lh{{1|lrvi5$GkH5H4ht}c7|Ob#3+u%SS4Z69iKV`@k0L4!m=`jWj`35^#*HL@$fvBB@BBD7#{yQK?>p%fGLwW!cR^AomFOiR z>A+C$7g+MWf*1P~XwQ9TXO-D1G5DY?YB{4;XQo8k2MA0xqOVVm9NES@=;&tWzHJiX zVtYPy2u&PgDLkN+T1X_z<(|Ff{W$wn`NBpb=SGmlW}+@*YWI8a1=BJGGPBL+25~Qj zVo~BJ>SUelM@bopoMm*WBk&K2Ge^SMgY{T-BQsULu*COWY=4qQ8g#xDO>amdD7%@W z8;{PZU3bijZya%^+lf#*6lhN2iMqM=sVwka!PU|6?Y zmL*HnDA7)FL2ewe4tcNOin12Zyz;%1M_jB{Ub+H|UnFIa%bEClidtc|g#X`()cYNp zANvOerc}iY*mGa2TLj2kJ`N9A2b%%h3zlYZgIZCUWoy?Z`GuU*dz1_$ zRegsW&G+}q8UzNMH~zLRSe?d&1j*6h=}E$f4=M?De^K`mWJ!*M)y~b%t6)J`+ zySupCAGY?9iqL`S{dJ|9k10moD^pB0VYdjIhAd69(gc>O%XOb17!XWfDLw2<{)#Zr zXoKB2pP4W~0a8z?YqLum_qYee3hOUNcz{5MT^-(-#$xbdm&f|sT%X!0|(v3}{<%*?qRf=fc7RSxa#?^iI2em#Vi8vJ!M_=#>1 z?O$MUr^SWHm`HOR3v+L7VO|C5*s=hcib5Jvk4wM%${d)_9?Ka66jj#2)+&+KL~YLI zKjvO>aXW$Lz_WK^XVrR=uk7ZvcvF>83hyMet z=iO{*PY!%+#B`hyii{4cUQUi>PbA-;7tcIKRdGpOfgF{OIr@l zGpk;GK2=6OVbJ@VR?P3F@{bQ>zM{5EO}RASUQYZ0_I6SYwx{_)z{u+pq7o-Rf`%`s zfq{Y7_4NfsMJGTLJ0j@InTcH+QMwSnXO8w1#yLMYGgaUtp$)z>=$gDwZILi}b%nQ7 zAU-p{nOjmwe2YmWC?t|go?YEq3-}uOL#6u8IQ|5$19hFi&^{PgzBz=wlWQyOBfBG?(DG`);RQcu!)(x$2LizwdZMB-f}`H zqf6UvjEY7q5p+o_kE1ENWI_avk+T5$=IxOCdBV#n+NX-^*eW@iDCqz^cf$ia5Je2h zcxZ&!U%376_f37;YL&{0I=EG*63$;s(?OmO2| zekWRA7j*vcC2b7UON>axl^st_u6xz8mK}YmiW`}9PidsbMG+tS^`GZ0_qGv$1OK#k z6*jfy540mH?;T;*vR9>ClPtNbx2xwVDy}HgAf!5E+ytg<(-U@J!tyYZv(mulZEouR z+3y_r<(>{}EYw=jMh)I~x2~=(JDN^tn7AVvGT`82<0S^;{o#Y?8Q&aNL!4d=YgwDT zm{vAwZ^iA*G5Qtq9D?B=zU z?k3?_`qi*?0PwuJ(yc?uc8;2RW#b|eCnq%kJji?!;o;={MS^T?L_oLY61?t(Oj~F6 zuBPQ*#;}!6=i&;YMap&E^ChIUdHQWZ4 zX`t-{T2$rDZ=sa#u40>#p5fsPn-be;&_kx1P07s#?LKd1=|ij0V|0SsV+#IRhXr)C z{v;BYK+DeNa3u|3&u`$-tmwzw`K|_D(kn048Bf-!j8o5FHUCikzN%c)R{RT26fnkJ ze}8$jzdv|M#cQtd(T_z51%ZbDI?O)nUT|&SWQ>M)=SOf?UhZfRM%gDfCVY*I^aJ5cIJTx?$u2kadvt0{P&Q#a|^sdcAd4&-@OgW%FKoCJv_A z1;gI>LAKJxNW7%5t(}>*8;a0IwZWO~FDxn|JUplo(r0DFj7TZlXhU+^PCC9WY(qQ- zy+^@bDO4cFsjjxfK|GHMsU2fvaE)`f3S6{29h$p2*70cfx!_d9Ps>!k4*Wg-7!9xt zeJ`dS@zHyvYyz~B<;3-B8rT9(3lnYCHgx|y%9|Z_d=$_N%zNEv7p~`UlVsRm+ILKk5XvaUloB5SsG=B)1_>u4?B>L!&_PyzP+n~n~RJz zY<(YSI2Z)&nI34B3ZKdF37Jl{o6*Q+n>{w`YL1HrX~60ySaPfKRc~^AZM|k@bTv#I&lzJ?|fEXUhW*rp4KNZ29eysq7o&Vh&-|!hcl4nUMC9s zrn`hYG-5EK4&v^gGFc1&{Bky~y}aM?PD|N;-2P_bOV%N`t*cJJZp580A5?%z!In%l zP$Xn3f`=$>J%+%5VPBbfu+R+$L}5AC`u;k zvz$S@=ltIXe+E^uq{|L5FNG#>^jQWqq}z*S+vl+s^isq3s;Xi1b`a-oij{^fslmq5 zTWbTj+}`xb8Fq&#^o_`?ZHYE^Ip=UwUX}6%#bRVM z+zCpz+&4i4?hb>lmP0hff}S`wUgLpGF3?r$)G(o)_pY39aQkABs=Md}e1hNGo&nCd zrEKTS(iMQ3N{y!Qqsiwp^zw_EJ-lKC2UHToZoK!HRpo&V0u)XagTW z8|Y0)J_eskGKy-V40$A$wU2MS- z@R_PXaT3SJa;NhxQV4P4e_kR0)+hVGjZvNAg zO?i)UTpAWv=y*$`?gQ!KGMdVd#KLyuZy(z;ASVihR9Ta9gZlN80oUe-@|(OX=m~KY z)xfUak`Y1XJ}Ls8VCPsvDA?O(A(5+L+~FD@RwS2%pq0&Uz=Qz|J9hILo5_4c7)3tW z>^Y~;QLKS!;p3PM}A2FFSV%B^Y0W8%ELp_2j6LGbGqvsqHz`wyL*t3&U= zcTvjG=>v~)cE|(Zi{}LnHLd~l5{_!ZfuFWvTs!Q%jlQck3`C<+pci)2i3W(f9})P7RTf+*&3P&KNYM$pDZ*8N;Ygcp5QwY`GOA2)W1 zxe1RnmeR%0nV?}pZmbngM8qR2VJhy#%OBuCv#jQ68(V&7_Fo~D<^WuTzgLPVE^GrI z-*(@xYu91`JY(@TB*#-A!Xbiw^HEJcz{C{!#T%pKnUPp5Rv$FCEAazcF_~1-QBfw9 zxkuX7S;Do)!_+DC-5@f(!p&`1rNYg?i`+NJrU2AQFwWULL_0cg<8AJJn3x8L=IgIA z^#*k>;^e>^;+wARRg2RDk>qHTPeG32=>D>Qc&Z8t&Cl!rtxe>)JYoss`OAX+-@Ra5dLPJnV*}VsX$Y5ilXk=xz<^eX`vbRPA#NK?tr=GB*Iz7C zk$B+L3(JrI|D3?-pAYmko<%v~(a~^L`-YiL=~KO?JfJGn8GZ1d>!sCBXhh6s`D_=} zH9uqJ2g^Nr*wUqavO-|60rGmMy{<*b9a9~}oR_I!O~aN!r{(&7 z>gXtJ8QhKVG&qLpWaH-Z<=s71HWl=VCqB|9*)y5L24!yio`Qspm{VsoZT7N$Lf|W<}B3 zFs?@*I=7R=z$dkucOY!)SLg0!)C=?2O-Bub*9ytbR@@g9yI>ao5p1-&*04?JfS%wG zz}46bD^b?g*11#HgMyY;HtIswYNtEWDIn-xs%K&_nBEb;h;y!;vE zBh$sm3YPtrmK>Sl%!0uIxuTLnBWtZ!wPBl4^6KmV&$?E35T#%ncPL`#!fFT1384sX zC~3V}1Yu)0(s%Y5FPiiVT3aJ4`EF~!clZ5~>iP7#^pLJQb%$%MPtr%_=I?yfFc zS-HY6cM&f|m^_SBM1q>S97509&$p=#h>Nghj{82kP=`blE&kW2c+bu;I(cq#|9B$4dKCwnOymZF zu6ThsJ8*N8U6a>d{*;{IGmy@YIn-;9>h;m`*vR)!_Q>L5ka!r+Ij}5L zR%oa0x7`|8oSmIT9o8LzErSb+b3orz%sjO-Q&S1F5MP$Slg7rfJs#`i&r@q+pj$zE zM@AZ3DmG(IeJs7~`whTB^FU0Yx=Zy7tE<@S$d=poE2Ix@BOvapiT3?%Xz$gt1LUW$KwsdX{q;h1L8 za4bpu;3Z;~=AtxvOd5Xze}3}g;n2=&Ejxai71kZ`7K8l?Sb%1jz_c>cH;!0nmVyiQ z+NhA~%mz4HJ8(-3dG8WLu68w12D~mhv88+u>xDi1;`U9x;uc$;+#z{H)6*nzyuPGd zvo#%^gW5-nsBCvhSDcmk1we%T0-qg5ldZ-x_Xker%7Cbu+v2bcr0(e{kEkY+opAH0 zqmPr0(9WDkz@(2e#0aO50<*qPX+*I&SM9IsKQQ^ip-+l3o*^A}$-%N|(Z1}qLybQb8vS4k^~veX`?1*b(ip>?lvbp zCLOI9g8$)AD|HqV@>M$slr7jvKx}2Pz?Y~8jlGen2p)M|G=HHP_%SmhBcnvt0gzc~ zOlQNQ2XY8FWClpoauX!sv5T$In=|*k2DSV8r}}#lv427=1vEY-6vKa7mM|fhyP3#v zy=2RE)HJpFrkx68pXj%0rrYqBlf!ft4VOBhnCnW>)f;EQ_c>@ND)0nd&4H7i>v?6< zwH&g6&(4MklV%=!GOYjy5!CAcTHi=(TycLw!}vvp+zE9PsoY2po@~!R;E`WDupr)Zh|+9bIV88Gi|d`dIyj1!;n0 ztK4ApX$LLUxpH@HV&f6x_myAOtM8R8A+*xDu{SU3lR&czc7^z1Kpltu;6$GNM^h6} zWoz6y^3s3v0}e-T00@X z4eP*Kbk`V!cVzhziM8>}GSiKqGNGVoQ?D(Sc)!lI+??H)z@hbj`5DN-Oq}rE*_91& zor_aHlhU0tI?3d+$oOKa@M_kY4S`5B;dx!5FTO`9k!*6H?EJ7z4){*Y_H|&pFtN0# zu;4o_Gbb2v#Ro=`v%}%ly-J%wU1BAh(6d3k(Vnu3fWu!KYNZ63eE&5l;2$1< zErYjC2PtuJDHhyeFoxuF^+_JE0|%a!b`3GW^qEy1_`w)QbO>_n;} z_0-Kjrga}~=QfwUCRrxkoWKwcUat4Cab~M+1a{2^6s`Qz2N=zX@wTgd9-tOzYr}zV z9dL&b>DJcPGS^^#{|kHZaJVgfNeP8_c*>capF$-bOW@~vdcLL21pwMV zZ*WNyaF4*uzyfH3`2W$PM>=2sISR5$Z9Ll?P>ov&El4!i&SdYYywJGF@tmFna@%)w zGaP$KCH-!`Z5`(Lx6OuepXJLJm6jEFkz60cO$VC+F2ORkXOam4 zcs34_&)oD^MsY3`LD$u}LpYbv|1_+8e#LIDki6PA*|oWte1yp>+VO1_YQLR64XVwu zvgx@5pTVXZXP1qFEO}pbv9#I^!W55h+=$tosB>W3B>j6dK5cw51r(zYU742w+zL?@ z&km4GL=MDR=)9u1%z*1uve*oYWaCT|oI#(sE4~&<1Rb}XXER~kpirYNgY!^SqhdWm< zBz2Wb7wRp^fqUfxMEJi4rBodvz6bW*-_j2H#+Jy*CYg8!QVF4WJ)0 zA~fCOT^FdLCfl3V93D6{OP@z$71%Tsim7zJOXHGQaKJ|jNl!@<$B3&&a5_|F2^uA% zqEJ~_Dxiwg&SCjn8hEyN?DE}{4%K;2YS935gK%?zCgE7viYK+OI;AY_tH?()y9lld z@;+nB@87CHNdpCU|7-{y)1^;cLdOrJ~Kt&lbEn>G|#- zz##@LsZ7^1(j}h))m8+xN$zn`EDSjZT+SB2j6xs~yd@g1{7EfuEtszbqW`gZCP3I` z#%Zw;NBo5XK>LdruY}>{B$yHYtr*kM zjIY^dFm|S2+rI}O6&{1fsCE*ldk_6jAYo^WgAkqnb^_%QU?Z1-@~~%(48f5=1W9=l zz5V_GdnFN>-JyahZ9^EWRV8}Oerk^`{HfAq{^at{6T;;5><}yZ7bg_)q`50A(YRy% z>qd4JoaUT>?kKW5)+9tB^Y3(&JZu#1P@f&G$nfLI=f;bXU%}5LrY}vNWc+E)C^60U3@m!;;Y|qe+8XW&>fVW-mrT9% z9n*hB-IF7HMm$o*gimjnpGY+k0E_KUPs7$V@SEebYT%|^`#W>Vj3xiTz(6*Sg(p)_ z0;cU2xVGRkwb3vPYWAH&i}q2$EL4|~YQh&sn%G^z-M$4mX~^{i1)_<;wWB7(=tYoDxs^`IhNJAG#x%OAR4QHE`U+3qofx zCUD}#i0PW(5#3&eJr%!$fM`}4m}lh7iw7$0;Oez2*NNalkQs1m`a;+^q;K~{KszPq z*dgNty;DZ-D7EEY^*NfNuTxQcXZf zX3zlJxZg))s5~s~6l~1h{ubg!het;!Kw7;QWnFV25_y_AT@a&0nBeYVKmUf11`C8J|TG3xAbyv?V)l(CIk&#$FZ zsRh4E1XgD1hndAPR$kKQ8L>{bP_$O7-K>;#z8OJG zd+Z6gX5J<&2i(0)f#B+t6V}Czdz-`G!j|{WiQ*&QyZ}*0!wRZ`uu>DQ_`T#2ru%v@ z`YgOxI~nlX%!U~cVie))S}2zYgyn2!hCG1p*`2{lzUN_Z!TB9V<5e+bnpeFvps;gPkqPz^_SgF;4# zJv-*CBdVod5*&q;VN-QP^gzU|>9jW6U!h1S3QClI(}-G~bw(`KHh|0fG_Jk-`}Zh| zr)o#iokNTP)9>cBI{W$F>d!+*ZV7||_Qr4=lvV_cjJa4P?mGITMrHZGj;#s_xlRs= z7wdsSJ`9w(ax>9M4AjtkN`xHL65hJtoFBM(^I0tYytQmFyuqW34RNLktEZW8WDJ#+cuI zjilfCqko#mbzk?Md(QJb&$;JL129(tUMkFc)b^olOn&Zy^y#WYReP&s;}8Z;sl|0# zeBP|v2fo|?P3hgcm9r)0F0X4}-~ze3bZ&6(P#X*Wnjyj!Z9LviW;N$$d!*-N2qXiRc zzrZpZBVQ{OWn5{CR-Jt??6n(qjSdO`V6c(NnY~rZfMEOvG7TQ|8YD=!WLi;DGu0F* zqxXA&P1_yzXV6nY2{C0e@CGl_N6orwD1%>bm@`1kwFcbyN2^EZ9{J71Qq*vsfqeMv z>^?2PYWs=-gbVX^;e-vG-oU`UMAY#PAQhn>raF?IXBywZ+LO5xCmnd?#ea=tdn2_Bgb59^&h;m?M@lQb7}3>d2M{g6-WkPnd7>(J4Js75 zDIy%bpWN?RcIrco8M&^od5mQ7F#rq0QdGSYv8D{K3NKeUl46D%SkJ>{JN|im-Hk`) z643|$bghA4s_zz(z2WJ@W7>5WGUMaX5D7Z2Hul1@xr0vaEZlg`n-2Fu16JGWiuLjP zkOv2ZxK`cz@Tf3w5}J1}-MrObv*d96t_H73p|W6?fgb!}u`bkhoFS>#I=UMsG31_M zUy3^=^%Uu)ft%mA%#h6QFGCXULi)Nj;Z@z%7EPax3d?3t-w*gRtYM*}h4ONCpR45# zA#prB=A!g2X*Efwn+Z7i=uMpY;sKY$*cTrw3eU%us#|r!%W>s{ASnIpx>dqk$i>xl z7VfF-`T|td3<$-cZQA^oONN6NE2CsX?3+HQ&_^i3{TV8dejC%DhMy=)93lX8JnEU+_CqUxZ zp}#-Ld$n?G6etYXqNH3Zq(qAbsv4Jtw(pR@o^`xVwrrnn@caadK0z&Q3a{9?FqH_p z5Pqt{6X}TYR))%K2Ei*aK#$MfUslTXx$lZUUSQ}-4Ra!viBuZu^sw-N3fydO(n+c; zZTpIiuX&SPPVRc)#Y+5@?}4@_LiZ1pU`}u~aHZVKb+Z^)qY=mEeAchw1f@TM6)UWP zDlyN3dd>98+HghilJsj)g5f<%4?YjkLyiMYJtBu#hkmL|Y_|K;|)n>%%V1P_;z zy1(G=?C~9xWRFQ<&`&^dQdB<)Gb$H9w>kTYQ7{|ekpYUZLqA%eU8zOW;h=gEXLrDb z6<83#-m4cU7aG*~c2e3fy0$U6-K<<+Z4gN$5ni4vGSx9U4^{4GDUA66!eRtZ25l6) zpt^#=8fY)C-J$IotSlDc?7h=3!Cd0enwe2tSIri*=j`_W`NG9*Z!La_4aH+}%GR@j zhw)f7o(kM|y=Mde?IUtbP6~|xYkCYa@+M7;rBG8fbX^Bc9l@mokOOgDC#wR}@u|2j zf8hma#k(b`p}6(oc_g^`^S~!0qa|zeAl6sPNok6WNe$lN&nT zl^tOreF@y&)(ho5U&(fYTrfZYB9j9hF8--PhuJHWR~PN1GSw4`(>@D4GuG79Jb%}H z-#loz%@B~@_1&bc@B&bFh+n9p zi$#EyQuE-4VV62NHjCav3}>{opw02S_ClUZ--yCcF;g-q!2kx+``2aa$E?EScYmsf zemuLaYbtGTM$28C#I8ClhOwT_racksN~T0y_35hSE~CEfD|n=Te>v&S;+oy)h&X@w z8O5ooeOfHADl-roz+g8$;V?ND7ndKL!rn8e2f0)B-zw3c0DCuPOnsy*@8e#3x@0h( z#ZrU(dgriLN&f6Q-w~YlsZJ5DR)Kb3q|O}+v-u|@JEK`jn*c8jv|_2^e-Iycr$|M!u$UV{pZ1n`m?9&H5!(v)Nih>{?}b9iLI8_v*_}ch1J$F zESY(b4J7|NBHomv4A#YDBXA_*eFjET#&7As9i8|I%CwXpXP|hZ};Lt|w z;+Q@0pB&HIo7`v4n6G!&8c~Wai39t0>L8ODh`tHpC?z9LOC@4U`|P9&s}`@Dp%>^c zPe{g1O50o8eU<#Z#<164^1q!Kh&L;vE@hJu|FE%h|9+q{>1C?|LHab;|z*^1Gku(+~8DF zQgYQleZJsIHPWzDtUtTe9XM3s;XTkKJJ##YWK~L2%XiJcE?#*vHWc34e+*s$r<&f= zIBv|rD@&^SFLQgMr(WWc{Vsru4c#R&njB}&42_r9Au493X9MEpX?qEPm`ytXphl{O z6wN{jgIb~D+9q(H4S6tGdM{hZ3eS*CEmMq-WC|mBr&k0?-manQ2JCRX!?S~mr`6=GW2VF^5pjj=Z=?JfqaM% z^`Cz<_VE4H6~EE6o;j4G8vePo!@#h#m80P(wQ^$??YxPa4d{$Todv6OElHFyuD#FI z4|aAH2bc!sZD%6mK_4P-j5Sul?t1=}pXdLy4uI_qN;vMkg5tA1k=yUJOFAt*{f77K z^fQaie9>re#|OPU*&FRM3)9IndjSm5QDZEF+=Yr6m+4O%oYRG}ckP?vK_gi#^!mV- z90=u9RWf?4UG0++;Zur4D&@Sb(A{I_kRFgBBz?X`*3)`4uqCUac#z7fWZ;B>)=F<5 zlNs1EZBv8I!1CaF>=#GFau398V7-Nyk1W7pTQYrtWUX2@QOOs)+SoqJ?8(PNofv$Q zZYI&Gzkp9^ZjQ*YbWrWX*(-if0Ye^UGGh$cB0BMj#HXUI(eb=L_q{mrQE5S%V+@#WETte|AtXCZ+!q`yBI(!t;2bj#D(x}NU|h^JIlx?Wh$Y~zO3pnE$TYbifN8omQop$Sv4i3|Pg!b;lw$}L z+aI^K35;W~;DD>j;(D+i~d@m)`h{rvop zA#rRNS_*Z{bMGoRtfY;(J`Uq@8bkZDwzNN~0%nxzpPF?tPH4K_{~*DoU)y%Ue7m3m z#@9EHVp%Bx)5_8js4ms+<@(v&z+`0c=nBPw|QKm7|}itlnHhCVr|UdfO2A@sA| z=DtaM<>&Xv;Zsmd`gF)G`<^zg00Rd#(5}nZ#d3RNM4n}36u}ix-*TmAb*07{JP4wB z?b~g&L8C}X^uy}s6f5aVDw>#Atmi%x($n{e=ExBF_GmkFM?&Xkq=9jMNP7k!retGI z4XkG>FGR!|C^=z7ku6*yZ`rbCo;=vGn* zKmQNR%!)Cyh28U?$t9+jLzIC-5hU@Y%<$4zC!Zab*p94yAAWqOQO}QzGCjOpZpi%p z02>?sEHQG*=h-fRw}rp_nUfVl8{h z81(OfT}t5px5VtY?e~?nx4oMuoyQxTs{d;__iDeWo1U@vh~`Tb;L?z_cEY9NLZzDKnx}Ply%e649nMCviodOF`ZX-BTX{3E%R<_#Te`GzfkIf-I z$F*w4Jh=&HfF=TYh^en&Bc>sE@m54x|a)Uj9EkL-{#}w%1 zPyZV8jhP76Izk04)<}lG)geHNx5VHB*o7?-3DlI8!+W4jRX?1WZWtC_Q$Va3sTx2A zID9{o84T7yd||~#Kze&wIVj?Ul$5Gbb3T$nrui2QYSUP>{9Cc;$9nqgkagM;--q@q zuS!}D`m*5Pf~RfOb?3oHoc3A!7}zwT2wE zcp^^ZLG0w;W6k)@{$5nGAm?#caTCQrq4+$HQHjh$KB)UIW1^<` zNN4Z!FOh;^QA@r*8t{5R^ZFKPC?qHMOSV^D|3;_3~Zq(aEAP? zA<}De9d4(4WlP10T8=h;GDlR-{b~9QH}R%^D2EC$p4Z0h|lz zNMo04b(>d+_79+PZ@%vbQx4DWq^NFCo!Ph|Bi*FXzXq4mbil7_Wh+sbtOX~eqNb6{ z?EAK^zSmHwvL%6LK^AMW`_s9YC%zwROtA791O8Ex!~TLyEn$9o`RO^z~Jn6hOSNa&Q7S&jRpM z-G2)UeOe-oa!I z-#1ebl{393+VEjul7m62E#F<~VN`>JnYK$>aVCwN&`kIJsfk%%kItSIq>OADqvP?8v$aQ=Gh{ z19|NKU^+I8$qJ+8*;)tUg}=e1qY;vht?_N6%iHBhu!0>&(d8&kO|Rai4w@1ZCcw zLCjTY`H+Dn+8OEQOLjux#&5BD^u(}wO-f}N<5@@zYCKaxMzFQY#}#t0v5BTvoLBG} zEn8jl3T}+Z8=n{>y*M{@1XwDwvkXI7Htnu}seQ}2ChljRb9~F(ex&iMynju~5Z>Oj zcZc=#RpXxAUZHL#_z7;F`5-k$+FzFHp<7q2oYLAH;oQt;cLX5H?J=LAMoWeDl$+$P zYDVoV1W;9)E=w6{c$A(IT*NIesCjyO<^rh1^P{E2V!5F-Li>}4QN1x-F8##i;bbLE za1!=zEwBemRi3urqvK)8>dzk#+t{;9mRgE!Y`n7KFzEh`?i7b7JEmM`G^Tc})qN#+ zgR?C4g2m!N-=gX9pk{&>1bEGgp@8>Y*^+&uk0J4}b8S?IYuYs?rW*Iw5!TvThaOD5 z90DM*%{A4U4A$t#os$q=GTG}_o3kd?C9DP@-BouLyDL9OW1Z#7ZM-1he*nc?1NW)+za zJz<+cT1E4Z0!2I6n234z7K#zRMMI!w$SqL>Ly#F*WOGMAj-OCX*LG{Gv*c;c@iGhU`-CEeBL%y-K zs&Sjqe#y?j&U}@_S=(h%3rE+X)!&kLyPGkJN@(>J>LpeYozVM7RBFarWzL?k%Y%o{ z|Cr2l9sn^&vO_-vrA7J}@r21O8gm1#?O8|SjRKT4{kaQxuULbZ5Wa(b_1<=spJ~~+ zwc-Wh*rA_H{53(mS4B-cehfEpPF=+fB^oG%LT`qB3u1hG(ofTCV{3)#n^mM%SIY`{ z+m_--pBgtaBey4cO{vLCv$}^EG>gkgBCgm62psD`4Y6w2IRs{JR(>OmuxK>IId_nz zEXXSf5J7NUYij`@+GK3192RGgb1%?Tu1qqRRur391g8qqO})nRcesRi|DIf(EJpk~ zmy_t`ZG&P$v!VN+b-Xg}Ep^ZvB|J5+&c=4XhCcAyE5?)`jz#)q5Kp!l5ADx)Wv=o# zaNsDZ9B#zTu{rqVUY-?VG)|l~!4_D&-?DcZf2AhO0mRnbd6&_gCO_l$_OMj3v1vPY zCqQkjzG*h=0211_Z{72Z&r+mc3dVTd0gYT&U>}A%VlMh@{^&L09J>_922mgaNB6z@ z)8!Dx#)j@Zn8fRfQVEQCU2&lFiqqs{rIk- z+fp?m+cZ*;gie{}!d|tz9+*z)2T6l1dHujt-(o`51U8U3s_F2GlO(nwLkp?vayttg zY1LzM@Ksgc3tcsK}<613H1e*&7tBR=iajV=sDr?k$QI$rtf4wTBQn{ zDn|JKW^5o^*_#yZ=NdBHnl1%vvF-1QFPY`C%SZ&I!fmeKqr(QDiP_4E_uJxeJ1int+MPHL#miF{`Ml?TfPDW#{o_%d+}2UJ-BQsv|KvuKa1ubIYtN{{j5R86W+7qKgx4m@Wk>tYq> zQuXn#H8-x`*gcDromnCl{8mD8;PYe8m>b(`Qzf*le~ufbs+5EH*IhA`bC$m(TOrvZLr54W* zqZ6}gF)w~k7FLyzo95xzTNOOkKDxkSQebv#l%U#WAB3cn65K79yZ#FTTeeTZ1Jt2^ zZ|jeq^BJ(?I~I5Hw!p^;-G`2b6{qpEkCA`bU*G-$+rAvp*DhCoSlzqYJ%C)SaQ=}W z*+fCX3oe+TCr&y~To!~NrkOTF&xXfa7Ir@-b^C?U6^x_yEj1+rZiEoS1s(R^;)ah* zmdUYiuxsCQ0=)V8qIYt2GL|(&kz(5%C#n;;+O*s_WDt_64TvOP`Fbdrev`;gf)zj1 zsFooH9Ir(6DzGP)C(4p%J}qd9CZ|b0{BuOiP?xb!tmPC&mfK8I>v_BS*#Pkde+jp( zElw^Tim$8wC0;k$utpH%4c>fe4tecqHRdWvG5X_^h};WNY;ztW=3UMcR6PidP~fF9 zU9L~8TBL0p8FAv)7hF@@r=R1!m_h0)!3H7_Ws(40$$a%^ljl@uRIUdk#X>?Dr9L9Z z*--nENx?ZN23R@EWCm^L9hRz0aXypf9>3cpmK5zh_m(#p*raBv($ioxux(kwd7v$? z9T=Y9BG%I-B9RbB>+-9_og4a4z{c-=)=&rEm0#n2JM6&;7erryxdmi`rfnn?L1!_T zn_+8VyH7=h$74@DKfu^5^ft~01`#}6M!eTQ?Gd&6nyLgG(3bd~om5ed^LDOYE$7Sf zRJAEGJ_(!(Ttwyz%zdUS>;E)CvyP53hCOX_fR&{{UPK=5E<#zQsLn}W)xyHh-TuR$ zohnJ*n?!t~5LE$!06;rT!!HmKzj|e%)2woa$qf4Ztjr{ucmMd8iQBt)O!6d-$&}r6QCsl?tIb+$M&ZdI2oU&zGMy$`OT()yh$5z!#O~ zqUQCTY%}V&N;81rWH52!$%T??FZ*TY2=BHo#35%b1|X$rs#Nt3(+wMBE@SMmF+^q>2QAJfnT zoa%2me&zWMrEhPiDZtK7eRYiP>V;Ae{E{lB^lJ<(dW^{o>`h8mu%9VL63RiS=jNrr zTQ+<97hYlEk%D92FgQ#THi0DkCusMT&zSL@E|SHDj8B0?MAVhEBn3QeC1JC>xEad{ zygC$%RL$SHq|!&nvYEc+$eE7uzHecDHcf9Y#IE#rhSbtp9b4jV8yK_C$yyQJ$M$;h zL(gGt$pKssKPYXhIIYR**7#{};)jy==M8GX?PX|Nk6&W00-G-kc=`o0MfnM8xbXrA z9;7d7rtF)qYPjrN!;~RTK8p3K&Id!(SVhu5xno`tp6p|QLV zY-1c05R1qi4XC7zIPF`$%!cs3pn3OsF|}S3GQm?vc1-Y#>Mu@#?#%{yL=KiSv+FL^ z@d~8{{M>Sh5}UL7EC43aWh-A%v1kRzcHLnZcK7Z@d!@174VlFADsjs*emUY~g#K$+ zkRl^WcHLFA({+H{)|OQ97zikFFDCo#pKFXllIr**<)c3y#`JmAHTgRw6p17kNLu6O zW`t{HH>aL<_jF*P?&TL4S}6C);}k{(_z#q@e>Y`hE$`y@s%xSQx`el!vI?N(Uami$ zMA3RffvwY3X170Eh{>BzhcJB?STy`&6`q)nQiBLM(rD5Q^y}CDjKiXcQr!$JGCJ9I zMF^v{r{_n{Ne)xm&834!K|avs+F$m)>h;B=XH>KsqQKcwo$iZEW))6*UwAb*E}oW$ z#4D^DL0|fjfivfS5F+L(JZ!6n_t@a{{CH{B`f(d2hNMO14A6!|0cjss{#XT~TYoRi zYp(dg+rH|-evlf}Ootr#Oa+-n%L-#$miR+(Z0|6X#C@C)J-7J|udKI*C-l3LET%|& z26Ei-#^`8qfD-)G2cA3v7-bAxi* zG>r+uRj>cmo`m#c$rVxQ5X<4*t~`MYF9DJ1kRseiV2enc0_2qjXUE$=o%dlP_R~mP z+$TE)?i^=joSfT)6;->*n?NuPbn0Jw^2BZVJV*juGhwa*2Z*(t(-fBAaIgdO^=$r z>B5ypC-^b5g{u=o61OiMJ0i&hJH^Otym)y@7=~RK@vAJ8F`xc4?Ap+i+1QKhH!xr~ z-$?!2Og~J)NrIe&@)gaSVU(W^HZJbB0n`;jlOMMA>cz@ffD~8R+{*w`EJ`jOinQ-< zou8$M)!p-{uh?Ec}hXfY66cl}IA*=MvXys{4*SacS z*+toLpxCvn^hs@Vx>|FI%jQgP(n3{3GZYNHj@Z&cCj%R}X$N@i<6_l%@PX{hbl&~R zMG$ZNTMpPYhn+E@2l-JH-U_Ew@_#_7#%OKaM)DU`7tF~j7^o1hiB=%-;x?dJ{%b~P z{!J0PYd%3lL?_VotFAeVaDWAsR zfqUgW8O;C%Z@IbmD1;4sZqHz7|7S~MXm!Pj_`4iK?NYqQEMjbr{GlRYD*v?|;e)-B%m85{D4!|iz?o~Ny-?jiI}^3epK^hSTP9p zw?t%!dkNQqoHK!u4h(P z>xV77{DHPG9I>h>UMo=})oOSgc|Ncqf*d^+Rok!acniD|;M))7x2ooKCSk>e4c-+#a)PE+gIlk$tlp0nhF{Vybd9z(zJl{pGBLB=CKE7hZ{vS+yJ& zP%-js^oQ7q?vu<_&?20xgxSN&N}*%`dFBqYsIw*`4U1Twn^x>N!Egktd8evt=x8y*HXXZtKp#w=4f(z8s=s zAH6C4@iv~H35Q~?o?mHL*f$R_+Ic8Tl4Cj3#aKg8g*Fh{{V16l?UklTe0>HdPl-{*(h<6_R83_dm+k0|XKq+o5!Y?N;ub&IX`byC{zm}s_ z=E{RuTXDpJqkNmA{x2<*OW}&3unI~7SN(8b9QCG19JKKakCrfW1DO`_hk93}Ea^2u z+k@&{KT)SrMqcqt9ME5PXf0eqcVEtaAac%eeehL@nA_4)oq?mt8;GbZWjN#?-5VMe z)Y`7I5)EpAQ(I}tGU8Ni;fdNY+&XNNv3w?LPHf`A7iU^P19#hv@pWm$uRtTtqRYg8 zfVX^gVi#=w26Giq?4U7hi?fm6TQ~RIizDVe>n-Cm!lMoD-@Z;jDU;vAZZ-W0gj@tL zmct!&bQblptfxf{GbR|I{~9QMmA9iN`w0@+ayELWIdzXIT?tgf+x#bZEMTF(6#J^9 z!W~e_M^<8wznqbf)V#1g?7Q5bK|(WQ_n{=*sfiu-_ zpgP?hE}y8wzR;kZGNs4t^ZAjL_jHQ7i&ay6A9qyQ#E<`a*pji~|#Pv;BagJ;XxOW`^$(>^r^qyr zwme+;2lifkfM!&{T*a%{--}G%f6mU%(GR2|{)Otdnm8%)c`{dVp3t(TZiTfKvn}2f z3u~o7qO4|=*y4ChX34B}0wEHjuYON+Ve*LF&CiQj8=S*pAoe0V0Gz?&?uLY*Zp2nW zozAYsL%tNa{0E(z9Z3g3DyRl-N_O9Pve4Va32N|a1X*JktoiQ|+a4s3wsu#DVwg)b zxCn2jzBzIsq-V8u%ebg=?SL}SI%E|9eddjCZ4LGOe9t&QO9q!eR5oNX}cDH zi#6y~b5CX3pEVt%SmlZT8i}#4TdCI$`o-A$s&xn#CIS1u|ebe6q^Kos@`0RH# zyx8TTIJ*BMkU?(!UuP$QcW!-?R#IDeut0yIzlaySi5)u^mA}0TFpL?!gACcO5~h^= z>in+hY?!HMV;HD}^Eo0Y#krdaHq7v$gN@)>ytpXkGOyd!;m>r7ICHX0bA=*5HA^RN z@>1yiY0euJM<9^!TUOy(I05tN>1hgcl_FHZgBbXHDt%v%xTANOycX@NgY&mg*9re! zFuhYuW+1vZjodYlMW6oQ^JHC!uluq(0okt&>I)Mm?VvQ$Z*hORKI)fO$<=mMoB)jY z=f_P0M~03dS^|0}rv(RRE1s_Y2;uPuDM5%ydzZ^F;;Xp_e5VZCDaU`!nnuq>5st+E z&CI#80pn!!7*(A!CroqeEN3&kOIyL9xlpNdz|{KF07pn_4`n33D|Z6K|I znhj>tpXn-fXQ7x*Xr>PkWJ||(<(l)q`f)j#x2Op9m z1{N=y0?sEZAT^CQPK!^kuBBqDBIc{lk)31|tovY)MILd5qV&m2dgw&}U&UrFv0`5n zk5ow#AUX?YE8L&VFe+#+1~87F#n`ByQ^lE~7}iLisbwNj_tG&^Mv;89U}6>s=b;nx zM+vJOAK7b$<;}hU&`bV9rIaR5slzQhi`hUB5<_k_RgSp|M2S)&{{W(hud6R=W&pN| zaecB}8(ZPywBgmVYaXhpO+LS>d}(_}s~j82yXW_3njCeW!?%y*7;aj&6!&pL1NA`L z_jK=o3k5b)WLl{QvJh?ScFk5Y7F#SnT1>`;BtNhbx{?Ejj#2ZXsPDt_Sb#UOfw zJ4P2mL3VTKHRswUH+_L4q{e^60Wy_(hnUP@uy#XF%?j#zuOttHBQR;Z*sN``mSkF|J!={d z*6NxSblOjqr#LpFKvV!qLVW6RO+|oGqWjdfiGobf4n&6C67iYK_h2e#Bjm!9~Edav>O(9&0G2_V|wj2wKiooQ(Hn>1DfW2q$y`f=At8L4- zjYm5Fq`=Mo7ZlG9&WOWk@L0!aj-iRy_)_sN8hRbb0H z*NmWo(FUyOSBI(D0N~8UiQ2Yl+R#goTXHIK43sKULzhpe1 z#WeU{(nCXWlmLnu2U2L9yJ6E?+jFl}dPwl4s=bG#X^S(j-*G8f%@j6UkWO5kUT$=; zDzm2-?l6=vm(;WX=`k-hq}HvlG4S%C6!61%TJL39hyxOEVxVJRvCl|kb;!Vpwt{n} zEpcIIfQbTQPV!T-gE4C(q=k)@geK0qIoZ>}1jLOU4g)3=2m;^8j57cYo3FWoL_c?q zD2Z<`o~8+GA)hr*d?8=y45)P;!Nc4;QomF{k%JoZ<%@2(WePmwHcwXUxS@&)^# zss$C+2u3TZpn#@kdT-*;L=Zu|A43XGu|OkGMo-rJ-in6HwPIOvKb%0mk1;istKLdXi6mNK@Yvg#AmQ1&lh)T6SYu2l* zfu~KBWeNR-kZc73P)Yw+?p@@2Os!RA`3fJKY=SoadB5AV!jYk&4pzT(ZeBWJpo5op zW3DFJ^e{6_0L5GdgAI4&fSBhkr;TUe<02uuR#!ME+k{-|Z&`T~hHv4@_KU(qB}xuY9U# z9ZdQw%-!$g6$gzn$}rl+sxQafVtRZ6svm#n%`ixsrl@KM?5ouU?AZSAKTa@F?5DV(5Qc8oHg@$L~oa|4KN(yncXk?sVHcA_Wv( z-8c^l4>>yZpBr&b9g+J8$_*W%!z`dVw(h5F+8E_L%gUfG(i=AMZ6FW|H1L^NG2+y8 z?R4&mWevc^G;AXNAge%~piH*x)s$%pD1&sdIAKTfyKeysLTBlDDDYT9m+NK~Q8!eh z!Loh-KfBL9{h>H_*k9n(sqg!`yKqw&<2W}XrI>eSiHSG)m;U2X zJN@yWP&KT^8tuz^hq0R3EE#k)6wk)XAg|4m(HP?45JZbS1qsJ1MDA(L6bA6=8r|#` z$l=d=Y{Zz4rErH&yLihO+k)p%g4PJU#MtJO#_Wh`Ne@dQPyCl?h4&@Z*4vr|E1!Oc z;`fTb-O~demq34kV~Y)cDId$;XlO3kNKifpkWMNZx;HtV@EmnimME7N$0IRIE!tEN z>?+jv-poL>G_($Q-CIczORxUJhQjo945H%Jn}?SRMzG&L$a&clLNW5LtyjA6 z`f)jF<>F%-!(Ze+Khl2%oSJRaE;ASmm$DpfKBhXSb1Ucpip1A=Q9;(R`gNR`9pQ@P zsw;R?c1y>EtV^b%U@A)X)Oy>|(*x@t*PY?#pd7Fp4{In z+xO>o`1o;)6U?r29$dcEk7*V!Ij+)6`R|4UDErP$;%+JUyJ#ZZe%@!Rsk>)cO&(mbc#L#e$*fPEX`IkYOfW3HfLSY-CI1-ex*@|0w<*$a z#x>r z0sZlgHI|YGdXL5q50Bp|-=>D)-V?s%`d+qo78gbh`c8XAo6R+uQ z0n!-83$#4%6xTH{80^>C9@n=b%lR=SVea#;;_RzWdW$zmdrOnQ*9~;p+qbd^RS0We zHZ?R6h54QUO@Cm%mkk&0<&dAf;BRL3&5ozqzbA|HOCTr?4{q($%>8)jieh>UdX4w= zh#Lz`$E!|fx!yCL3=0cxctHLi$jfA^2vxR2QH>)2Te{+ zHq0fsXX(`b_eS&FPDn6L!jBOLO@a5*6NN}A8RPK*lhS@Qdz+&C%XRD8rg7K@Bf{wY4=3kVLgT*hI zNi%Ph28U78qF_I0%vIO7@tniQzjsWt-ZAB9Ynrn<-u_aY^N(N)^_?uN4$}$2uF@0kBk86kYxo&~~*O9e{j!FpF@shQG8srLE-Q{Z~d+P*?k0){H#@N(kC?AT` z^bW}RZi%l#*2Bk?)^1qe*i4Co`im>axE|i`df05_MMQZpDCL;1Ka zuGoc!wQ4f6(+eve6uRkpDY!47W$3m1`$x*=#yL5qKK$#H|0fBVstnA8x+06z@DCe{ z{Z`&&DQ&BITSMPnzh5m99-qF+Q(3r3eij>+=M!g-(ea44)iW?K*!-2t;!;yyQ%L6# zN8T8~GzEt4)Ia@%fdiBoQf6!Y>vC0{&)TTb{rNl(u(w|sd;17|zNa{Skxa5a>*_kP zoc0hNohJ>)JXWh2Q)T4}7p`#3_MW;-O?f|1sk^-fX0WtJO!Ie{eWjca0q|zOOD2dstPVWv=Yq2r>(NPVL$z98OJH)p6*(eZK&nY?8wqM zOIBHSchUZqwQfOO#M=|wf8e;^iHpZ!j!x=#FW-!mdo2g2KM$%xp}iWh0bG4?8UwP? zv^L8+KL6z;LoK3H>GahS8Q#*x_f7Y8dj6Rk4bJi&Z>J(>SWJKAxxubgLRV#dIr_-Y z%*Rl&Nx(BWDjKTJy4zaSj8XauYq&zU|7=xNr*ttDQQ>7oNpLa@lS8X7KEt1-mP^Pi z2&$pcl)0ocrA{58*f{jP%>{oJa-!@pz3_$V+yW2V8k`0f{KK#tu$3=~I=f)ZIM>#5 za32d7BE}%0Ef<~JF`av&GruOID*a{Q^Oqq$@sj{GBkSi69mCGjyjY6W_+t0Pn=Wm<2nFT7OPY|oWX>hDXpa(&*4A>w zL#2!(H3l-uv?T0DaD{PR-;O*N3r>)E|8d9lNTfR7oFn#hzLE3MoFmFs&6Ltoe|GBo zZ1!{ojYI(N`wTM72P|2Q?o4kG`(maay8{P*4``^5_t?MOw2@dBf^MsR9P+!CMP8kx zB>3@fVY;Wt&J4Q0q{XHq=U|d<)vudk#L|bz2Jp{kv9z_mPXnJzAjgdcJ?+2~Kk3WS zmJ`n+uvj;ZcIo0W1&L|dqNY|=%%a)d%V;;-#m+oy@RDW~9>g%eu`t#~FH_w=9xImt;S=Cz>+!^5)AL0KF6ZpT9YH7bl3MR%8YVo^ z-@Gq!k%Cv%Y77~0)p;K%5!*{CEtm=?Fp$G;SWRvpfift-t{ zN5o;w7U$VJOEA8%S8~%H*Iw4XB>WyyWHU&S-#v0t7xGZg9j-8!u}D70k2TOrIZ>2f zuqw4j3;V<9#txkD8GcPUzZ}$A0(#NbCpoE)(hILrSj~>8ABUL~yD09}1b&*CsS4c9 zsL3={KL!{Ri#e&YPITAyE4gu65{_RQT%U^v_gZ;Fzx*xhZyc=8<+Y}nKg}9$s8o~8 zOf!G^6fyRynN##*_aFt}QOKpGGTzN%swu;=%fhWwhJQMp2jYP6p&pQ2N{ zsjG@eS>U?`?yCKkA0gZe?}vxUp{Fkk)0;j!*Yl+CXK&~&ws86PS9(4aqf6C@jYob7 z0+-&`i*Imp4CI{3z&i;+*w~ewY76)!+iy7b`cP_sm4+-XPKZ{8a*W1mo5~mI)Q&%V zwpft2a$$#uyav}bh?=I3TGk4N)n%(~8A=SiqdPos;56tj0BjCN%f@xW`q0T^1JR&! zgZm+20yQ`~fs4mDvT&uvUp#noQFE=&#%r{=pFaX(=_n9zJpR7~I(i{+6d;rJr(Ov@ z3Rr4Q*$qxFM?z?8d?BKcQzHK(IE%l9rbqs0Ni2Fo?;CtrKREi)L30F^?OwK+r)LQe z$Kr&pTPxgX)2xQGHPf!qOBg3*5Ql!`Moi}70+G%7+bxX6k*}aDXF+`yfLLOpFURtO z=Uwy{*67j}ceA`(ANE)nI$iv8jF(a!tl4FW6*+M{PZ~K{?6K-Z^i8+uZX;(ELodYU z$_KBGPW`np8fXC849>?l2w z2bW#{0-l4)n()HzwH3{grFVow-48W<765Et_aW%VEetQZ0$9GA>)kF`dJ|*#m1@^| z50;~?(P*u9kyLlBATO65P_ZxthOY+bXooj9%djp#%_*9*NCq7-Gt%By2))$gH54Ev zt42iuvT|$j$FmbKS3yTiHN!7X*#wen{q;ErD;xIWa(=7W|>{eSB`JFQUkyw1JqP)QE-mH5tfBDaU3h3|X%R;5kVv`bm|jo$@W;C@TUw3^njN zUt?lGhRZi2%WC}HG`wK3b)bL#d+x?y7cnKXJP)$=<=?IVRE1e;Dpw=)Hng_NiE_$) zf~-BB6&@SbT6&Hm{K-4kMGg8rt!`EwBOwEYpj>5m?1B%kao7oTyE?|AO$(R#Z> z*I@1N;6`IBPs?6Ys>7_{yv#N5%C^W;03vxaP3}#5Hx`a8r8;ZFi-dS9hBu$M=_iQV zcE9r;3A`_3_EK~N5G}vu9reVECydDCKZ9vGg*mvj%KJe6$joL!1qzXHzu-M|KIEYX z{jOm;I+wpP51w(8{tzc5F&kUyanVk)fTN*!b1t~4-pffBnA&Z**wx*?Yfw|Zr^v8$4=Nvhc?0 zxtLZr@=k5=_$XKH_Q0^Ez}nI9^yeR)AIrqsc7q2Gt<}Crt)0JuA~%C@^|yFx0f3Hj1rL*f zRrc37DO>iqwmF2|@X&794@1b~EwME6sQIi^KoL~SmpL`-czs~&4Qiz}G&#jT{RiT# z-xB_z6yTM1M?-s4F=xv?m>2XqUBRvha1r#~*j5yJu6P1jKe}8aHsGx+HZ$(BzQm+{ z*GVAGdANlHVfo*3?ZSyz945K^@&yItEww^k@k@NMCpvIBi_J}q52PZ%9pHCk-C!AY zrg{mX{7wRqIdsB7`sOQe7KG+#ZRO9!lC_V&u_393?_9F-{R%=+df>q-^eqcTv`G$m z^#-RwU#axW$#{r-7?*+2lx=_R%P`GMU}yktNa9`n{RR;b!-ar$Bh@v7gQNAhM1i{s{PEns zW8}1qv11L#dw#ynF7vs&(p{MJmnjba;Cz$P`XoPs`0U0??A5Eh@;(5Fc&I-hCxcd? z3>JnRT)u?1@EadGU|7FUdq4fDvGQ z{N<$ilgQcoRLdL4J(y&=MRV;+94*nS9WuAfyI`K7y8t+Q&(R!ZS>KNy z=8*cV7q0ZJ4=pb4Az53B3LdgjbhAKu?I`e-Bqk@=XfGK?@(WbPOWB$kRY&j*Gf)gfP!V;eSLJ2Wecmn)d9}vI2RwW zhj^E(oy77%RWazh<#RN=3@(g z1<~No+!Yb<{FY+69$oLn&yS4)u$;PfR1*Ew571Ic05X0cs~b9aFvHf9x7=s!-4^Y; zau3$l%3CzFWLoFv=*5n+?cC&%SY&fw5<5b}(WYU55Oi?|UBZ&=>?fo9z;mm_s~7J- z_G%r@({I*%=2CUY;-UhEsw;>D%BBu#>vR~exfYB@%ha@l#2IOY_zXf=TUNMO7Tl;$ zl}-e1jP6|f>B>($gdl#4Z@a{y*^=p&6@W;!Br_*UWV=5|@ro7vSktZau^T}C;wFHw zRsm`dbuH7z7=#ONZ6MoAk)wGlPy#%ji@iAL_?bM z*U5WFz--YsDsME%R5L7CZF}5gV{H#4^KwT ze_)pC8k1MmYz6#~;rlo&y!b4zOOc>L>YWS2j9dp~Tcx)4DDBf?An@6Cl_p^L6%c0L zCwAQyuo(KD9J*8d@k7wlf@wavKpw+lSU~*Q_8jDNpWKJgu0O;^=n|*SuE=|-QePxAkDb%xzVH3RYgRn-9LOgM zB_`NFF+llmj#RD?@$syxg~_ zkB;58zEc)(s0wJ zhfTyvztW$3We?ctzsF3bv|(%3!jUM5I>Z*=PrYOL8h;WR9tYd4e!RMd-O&!EUM0kK zZ=V=;@qF0&w5+U?q@~Zr`QQC-mX{`Y@2O!{BcyC(tYia!^*O9OzUPw3DBUYDkJ8Cq zF`l<(E8Pz(sVF1JU-tq~lNeq(^$!KYxus*=+B>WVgFr9{*=y_t#$8l4r%0nRSWtdC zHFqM;N}(OvZT>wpvef2pW)2(8=$FuZgO)@?e-=%?JF?4E-?sCs_+Sx%1v(feuQ9C= zMgJbnw;RSmRusN;<+X5I0MWfbqf)^zTRCm{+p~60Z$XsD{~qzY56^O?FFD({RN&IM zI1+MJWf__{_LYZtTVmwwn`FbZlOIYKII2FMX4H#R zTF+ILi)(5OKf8M|E>5;RTjcd0_<(k#D{11)8*!sW-{M`ST>vLhNhxwi#cDCUAkBY5 zkVHV6*t2C;jp8DhIiB3FJ*ia=(lF7vA2XHe@z0tNTFw4OVq6AI9v&PE%YD_w^s#6l zrmVJg{!0J=#wgD8f|JHtOb1tDJk-uCB@8kp-xwFk9`0g|t@iApnpChjIpHP@IMHzY zKXi(`L2Fz3t~>nsn{;J~LSD&I%lbrndK#o?_h0jyj4ds`R`ymjRP$w}G#ojsEP7K+ z6hBOsruTSUuH2og2uZ?!jq7q?(u@wapXFY%mX*NB8nkl~mYCC&AkqS%StaWo5FMXw zhAfn_xRJ5Cd0~dD*pdt$mV7H0k2_5@PF60Mo#myPmAmVQ)jKx|LDOM~6+VHUZ~1*$ zF$TB~afLG4J%wTh225%D02y+k*4LxDvHs-OwstL-vXLV}uBCk*qpbl05r34ID%2ee zqbJze>OS1V`{qX+0}-y;@eSKw?>+IfJSiY$p8BOl6%C*dO3OwDHK@s#!QF{MM*uEr zJ35)VTily0RXj7>XkXCu&L5KJroVsrou%^$TO@rC_IeJx5|#!ho{<-GVvct2k1MNvj_Jl-J6{Qk?(eb44pWYS&`c3P zDSA^#U>_6>Nau#Pm-$+t^5;b}>MO|+6Xjr{<6>-fBFU5MjSct7j9be?Q-cqL_IBB+ zYzSn$b_uaWN{B{*dL`tK1O~RLk4D}B%4n2cU5yjEmURfRoOw|c>sb5gnfxxZu9YSS zaTk)6k~uB%z3(p&s7>{-pQj7@P@dfVGP%XFD_X#4`WkG;^agSn1D}u67h~>(~?6jo77r6`y0ot&lE`jn|qhiTbgLh{@9lo0Jdv`v`@m z^<29N;UwAN+;e~qbMR4t39Glu7*?HO@e}mJ18_`NV%s8Kg+FDuu2WVL0{O}WURha@ zeHpmIio{39cxB^Klhe~{kA1B?P;;#S)su}`Ypck7>~^K_w>aCCC+Y*aK+Wjs+^V{2 z!9ulD&wr%LAj_5UiLtfVfw2K1X+~d0Z>FZ($HVaZ^NQ4bo8DwpO;Dkq8h}g7F26gX zuL~L)(x~6(lITq*#H{b~-(9-5P^eARUq47f7N5knA=IR_<*=8=4)~rAaSOi7Ikmq@ z`tt-&bxeDPLDWXnAV-WAkwy=|)=Z!eyB*va<5PH!L#R2&v$))etg;| zrfQ>yj7{J|Pdz$2OmMV-aXb?I!ozX9 zdFB!|Jx^m4EuK%)O`Mi+a)Pkq4}2X@U=c|hCS7yK;0Yh%B2H)W$gXxCw{Msdq91f0 z8g|GsnSF?!85FI}mG6**g!oW@v-KsXs18Z;xOW_1u%O2u$L{>Y#z@Z18X9TOs>)`7 z9RhbW!qB5C9pTGrPgERQ2p>V=_!r1w(b5Jt0g{(J|*aBZDY?sQ5JoYY)UdF>n|)4S-Rtjw~~ePiMs>Z$}cuJa`} zHI3h;UOSK}fTMP3uI`8kqTOAc_*=W_O$RoEf}7T_>wr$YT(>U3mn zizQsQ7ZJC|>IjF(He|;c)KVt*hQuiqNKDT&2ADwuh1Ky_^?S;{h`Z{}NsbyQ_J8AL znuvn4-a2q6nQFqt--ye)w*I!J>ef{=?eG2HOy(4VwB1j*5OF38MK80KAG8(}1PUt$ zHv0xS)dqR-lV6s!>4MrHsDL)vo~#Z(SOG8Fx~XEsED_4fEk9YO!Dx=1!A z7;w))b5w^k4nvy9P$4)rp8Ax#&!hLrAIbtSy+QeT@f|$--VG0KaMHwS>$~Vd{w~u~ z`uWE&^`0f*8kEVQM>JkCsbEYAb8Eq6Mdj zC{sh;)Mrx^Uhm*VmCwv=LcS>$yHXbTQM~j0*+Jv<_S8Sut;hFYcI+ANfmT{e(a+>r zh4M1m+UkR9TSFmuc<|BMGR&Mnsmj`5Gi@81GRnzDHtn*;4;lD3yuRp9Ya7InASC_z z8iawIqogu5D#0S7x?;zRwG%oozI@DwX`PImRE1h*^ z<{lV{V6-QEyb5Uwxi7OJO#zsI7S4D*w4RC92M)xkcL|fET_65vPz4vaYjd!A6&AQA z(lbdq#aVrodf7%S#u(UQVhyaySdkGKl(|P7z($g5y<_Xmurlcy=wg)D!|X`+>DOORjb0~HG z39f)?(DaKHda7*YJ$a40AHComWtgAWD8OY2vGA)D0iNir{=D9W7QH$A{LnFu_di?< zuU)~}H1iB1Z&ldxUUsPzSoKxkj8iSbd`L!*5ow|EB~0f}$ynWp?5GZUQ%g}-bL{NB z3z4uSbp!oNfPPo7IuQmNikj{8vTbZQZ zeq8<#9M1o+2gvr|Vz|>gHeb|bCJZ9ZT=drJA~~Vp@Ltu{4ub$}N#AsBtEG~HnfBu+ z(CPH;nx}fOttB^mn93SgjYgt--=YVq8)&ru?9H3_0Yk^3)fIfd8E2ITXT(%ZY<__3 zbYwB-u#X$Fw)+Z`QIQ~eE{2|mxYT;2lZaVX z&;4qNI>D<&`SaVDkoeUz;P%U1we0G8#@;jM$fIK;X1)|%fOmdn@+@%S&PoUybd zbyHFtAe7}wDxrCMTSLCYzVfX*d7v9W!C*(#8PAFWR2G(>pqrfB2S=o49(oGT{hr@H zME=}wb^uGe&c#ZtQas|5dWxFLq^{N+5gkWuQrG#wfnc4^{St(p_7H+hNf87Gt?9Nh%RIfy^l)Bzc-MSyy9?#n*E6p_q-X!&nVH|d1}OG8m}NqCbE`a{{nGGl}x3skO*e&B;9? z?eP2a=>Vxh&Qw-W^q6QwT?K+WjVJl@EpBvlNYW2aoW+Y*OSgEPUaO6d44JIjog!wu5UJ{d4;UKg$X7-KvrQ6f<|};8zrlSKGo3}@ zO2atg!YXQdI+ zsTvL5{P_a-G?7nxkfQiCc^-+=N+(2%x-ZR1QB^E>T-YV;a?zk;;JT9WP%`MIkMhFE z$bjHwT3ToJE(~aQckQ-B^6o%9u?{_$N3~BFcG>(qODb#Ubgg&jnp(7%MB)#$qk=Qq zAt^E4<2w{ALM@~?^F=g$xuW!AZ;%_t1Cnk6yqODQu z8$SIVZZ~4KYtGmO*kf@xO?v@YZmdKJ_4VO z8=p?l|Ga?KtU0#+;df-^<9CdK0XZ4YhIRHKulJ#7p1T5$$6d;Et?>XnLIN?Pg$y_v zNk1MA0AhcSJD2;v5v6TtZJV20TL&k-C&LB6d#+%Cke>YNDv3_GX>bZ3t8qaXiLV6r zAb70ZmT>Z=O)JE?u6}cNq*> z7!>e~@Mgz~9XWDD&pqe)^J9gi5;rxm-an)5Yk1arOl9yiG8?$J{sDQPPCPmg$l2+p z#=miey2h{xfZ^y5jg6CIa@n2=P|45q?^gYBrxjxTS5R20VZdzUZa3FyQ+n9G`q;up z=8~s$Yp+`m^#-Zwy2DOQmt1B(D=6RjdBzD64;r}AUB$fJi4VV=F(aLkL63`W zZ(xwG1(MJz>xk7LCH^LKJdcA&%biw8QFsb%erQIxWET|oihc9ya-Xh$HPqwyRka;j z3p!LVX$MEr&q$AVcC4K`k(P;+R|8L21;yfIt?=#?0fvjl_l++7(3?jUzi50wY?ms@ zZWD*IU@YNg9&{sbXh|dJ}_XPQi@3) z;Es-cc0;jd52ZwuS>N`zfF9bJ5{NvZ(UOHx4}5T_%iP51n-rn>bq@DTgp)1^bSzq_s72s7qr^F@RK+-=09QPYw?q!s=PfqMy}AiQ3HOvk2W9U?t37@E0Enmvys( zUP$dWrOTNF?9w2#GcrocABv3jm}_?-9EpKc z*Q%3jbpa&ZYj=n}o!JBQ>76M}DnDpDqU{63ZHs>&X0km251uA+(u|FbQX5tMW_+u-ao{p%)YW*o#Kp> z+)EHty?;ol{)aK}!oCWm`L-(cHnWg(BD82oHgJ+5c|uBWR-KC&`QT(L+UQ8Ta2KL+ z9Cg&aVudlpu4vDd1wD_Ur}BGo>Yj^V!=$N8bO{%p)Lhjz2%%+=vQ5FqxDoRsL~RUn zGw+RASdi+}NqW%&%Zr~cJCss#Xwkqp>&p5R!oHl&qY!mPL>HjP4{g|7PYi7}G=KuX zfo`BHYYtbZSbzIvbupWDyviEc_`tK~v|Y%R$Dm%Y6VL)u zT|uGhfKi;F@r9MK^p)h`!Umb8iHY}L)%4tp6B3RatuD4I=hKgfGstF1uouj%d~t~K zK08#KPLT9gVbyaL`SIczy*>9KEe$*e13iKYJxB^*lhPar+%aR+SsU3 z;{kmST~?O}rOjs8nFRJ%Sy@@ZOJ4STu2>Hgs*6uqd32Md~{QEX`83gX#S7qp1!`D?NV`JD}Q=VHxw+PsB44;dbf3J8Oct4VssnmVN{nA zlwBTG&z)b)ZZ+&YPT3|vDB?(6APWZ!7Pu(8P56WBJ>+I1d9>Vn-swjcAHpl*u7Ae9 z^QDs=iC_ic0lBMywHg`tbTUs&57l>$2|-(6%Yd%s8toGMlyqp?UG6g1Zss;%{q5B< z@iCM5?0D&TMlZoiHlv_PPvV4Toa!!_iC8z4>Y5m}UFD-fq44-^9R@n_3h9Zfrr3Lhq?;?*Wi_0&8p>|XOM_8W5!sXgrE z>K#@7)y07ELo3T)jbs()p}67iG1lA27$~}&JJcopPCB3Hp=h*>-LVgnrp>mUmfP74 zMvJM{Xf|29d3FV50m4E9#?amXIXE`npxWv1wK!n7r@oM!&LCsZTA1kcewfilR)#sc zC_aty&l`}km(G=*YPTqGP-UArj0?lu>i7-!K{=?nFwodjd?5_q>`aN}3euAaE$Tm+ z9RqDZIk%M|9Pe+GKlB+_IO250fMk?uqF6EegjKX<78~w2#}F`3!dFP{BN>_Frlq2(h`ywi0Gi+l}*AU3JDc#SS#~2OT$byME{U zv{k;O%XfB*LeG9m(6eVRi;Hunq4|U=0z?(D>bPR(0qwh;iap;hGDy#87?8YiH&?%3 zBzhJJ#1)&$Yjv-llP9fI*CaSpu#PPeepG`X-&_*$ivG(XwCdTeL#Wm_|dJHNOevn$uH^QZDzJb)i3l2@A97@J4 z)7nr$%3;@$=T4KogH41?Q(xqCP{(7>@5_FE{3!zsUve#^Qdgpsi(Q;FQe?Vt47#3LI7_a-O4wiOWd5YOg{}9tsRwVvfXRh{2y)HzT?_6Xz?iSLD({N@q z^|IE}BUdpOD{bIw&Vo1HxEl2qtRWhhey)P-;EphhbxG`VJx*Jumt*OIo7LKd7IM%?L#cDGggD+&AZ@X0;-0EY z_o8g|$I0C0=O+;)wibHo2JS;1?tHqk1u=Y)&7lOb0-@TW zv$wX1A*sMR(kv`2E+2*`CnqBW%Mac~e0n`-<&NJaAdNrwh$3hIpzJ}OeDf&3)=|K~ z*1GVf+|B-CRoV=O{gQ@4nL~CieJibsGb-ppEhgO_OLM|610L^3O2{=Q9R@?RTb5({ z{U!OwTT)Q)}$=m=9^5hRxun9(DKbB=gCi#@P^UGd!s^PZV}k*lrXy!m;QzL4E)FWgty20*r>iD6Q*aBy-nj{kOn}#g=f(mnXPPWGHyb2rjj2*y`<7!5O}PO(`?8!o5vv zIOTdCbD%CZHYX=X<+ep_Z&u+MOl8yiY$g`2b%x`7pySO!ZxkcttS~7I@`sFF0G)3F z9bUDs=o2!G733G&@*T`7W-}K5%v@SF(v3XhWqJ<=(w73lmeem+~d~)3`OhEiNuLCbs8T>D|J|8sxI&SapgF#fE+5 z`tb-v!%QJvWu-qLNKZE8?TV6rz#+td{5ctmGISwb{4MpVL&3hyCIL#di~W%WW1Z2UAD7KU>7-~5B<>@^hfV+R`~dgqi!?6 zf~;Gr6|-nJ>om%S9}08d+4eoFg%IxNe?X5BAkx1;`#;avR)!&XU>NPZByUBAs64%M@MQ`;>&|AB!w zEe?EergGdruSXEMpd#{~iq@{etRFvBEFR>ud6T!2YU7c@PcejbGqvKSDP09!>p=;` zPZLiyY1i{j8RIORc* z?XFAAK@r|e+BUY@b`XQ-+=o6u7a*6K6-My#>A5^+#eh zO#9xg!_oS#^7iKj@NVGJi2ai)GAKR~%y3?v7Bf zQQxt&SL%5A>?l1Fza|Gn@WqsDY-}o|(SU|lx}kyQGQ zEU>?d-_Ty{&~lyV5--!!1yEdVT{xNZ)}V0CwA-aluxg;zXvO}L=TGZI zk8e+`=S^!#tH-I9hJlw*(fkv_y%Sx=3jmj*1a}8CKp;h~K5k4b9ZxH?N4+0+BiIS+ zl7%67QIq}#0W}vquZmz>7D*iCOF=xpLb4pbxo2VrVjkVo(?k94En64Jp*-e_|ME&X z>rQj>%-med?2qDpC=37Kvln3?DzU99Wl;RWG_aKe>C_G@&)_-;~E$>%W5zA^- z(QY&-KLAZSY60D#9JsQw;)ubR!K`)iY;T}%VLGWb0J_P-Ut;X_t=09UE5z%<;vk+Q zp!?ZGhrWt5BdA$JAe0yMZno43<J!hP09#$A~uZp6N!$T-Z9s@BR-TY&TKlle(DwX4RVG$Rxg|~_#NxRtM7^=9AsmiYwr!~WVr`0`Q|tnPGmEA_9s>EEK?-U-~(f#d{cKKjeT2w+)!8U zo4zm-;FAs?e%$h*8tJxThfiwzsw2ugy3w#%8%D)wY}6@trwm~_43i!M5?`@}qHm{V z;~X8q*1Sv4(?t+QFpnF4jZ{Q>T9W5df*M#VnmR3j?x*v&@IetHzfxL}wD=tL<#_y5 z^P&Af7|t+%z*!rHoMJsu6}#-om5_h~LMDlF$}Ucu^w&2xvrMF@13KZW`RV$G?;~R= zseBPx+&YUx1AV2c{$i;G({8HhlbO-O()DpD1=ZMe+o6O3cYgB@S4N6t6)blWRTp!b zlb8{&11G?Itq(b4)fD?}wt?CEr-z~#z31$5KNfXMmo+sqmniASz1wR3q!T6(@i{c_!>n@RknS=hpTn7t_bDM+Ah z$kq>+eWqdv3+93zpx(K+EZ*V+k7CCiSwOe%wBWbTw*FRHRD9xUb{sq4Eu;oQDC?_7 zyecJ0L2q1k*{%vb$bppKJDa)6yy!SysbOKcqahL&9K408>Zb}I6_jc)I~;p0jQTYR zLPtKNok;xl&AiblrQ8!+_~koX)JUB zB&xJ$lsgF%C=eGS<*FbkO@o}>vb1_(4>dujSlu}4-~*fx1G6SPN^$F>i1`)Ghq@y4 zS656N-{%4L+rzne^BhzKPQ$TUK&o0SHogu0!WI^Bs29tdk7QUeo&vja=-g%k4n<;A z&SWRGMXFnI=ddAiw3{WXQD0Lc=s2D?=ho^RD)eW!Y??JOwwFdCsDD4 z(%a_>$7DjAIa!x5lix4tNpixK2~~jN*D%}q4x-%-FK-Hmr=tnEuKc_s9O`Rt{mPUY zfQT?Pb>jRTL4eI;TlT9(v`}<3TxLZ=ei!gmOtKIAh z(Z_@ki~2eHFK*uW$Gro}J}J$)!Y+1ZC-5ICtEY-lYu;%7Lup}Z+x+3HhBl41EW_T z{3YpIRSahiBO#=S!k#S41rz+YPfI{c_+#~)%pSr+y;?RCLQdS#Sv%KrRnB7(qLEyi zcf96#R!YG#Czy9WrOo8E9|}G|gu{ZlCFABqc0`$Za+br%H zdt=bW3~t^>Ac0EyiXRA>9R1d{+=)P_#Q`UlJAFypk?V)IPEMB-v01SrS7>v|E~`x~ zBS_O0HUv6pb>^=m1=^Gdv=`){@r^tGwgD}tY36l~%j0HA>K7jRjzcW}!e+4vmRD$< zZ;;KFX?L~}EQbC!5KdcX9k@j8bnMPDe8)_Be>${PQ`_?6^7j$_=~H#`|M^3>4-Ir?;3c z4Yf(lzz0cJFt^O(Wq>SKwoZO*BF%bL24J+;5W0f(5nm*c1YD19mbuIpR!r&GStd_A zJ4%bh@7h91?QEKFy&p_W^3b;xscijpcxDX0dzKj(PmXEJQq$iECCdt()o^D=kgKSr zUmx*Bz+^=>>Qf&7VFk$?2z4PSP;Zr62P02zs)TpXmq1t5k*z95G)Cx-Bxan;b82=b z9~UJP`Zn*>ZP5S* z?G-K5F&EsBWYCB1ik9uj#V?=1S=}(=(>gi=r%RtY9tnQCa6wR*y;yp|*I}=_w8agu zyX1!i<-IzFDjvvnxFcxe596r?w>XA9WyE`9a0RS^-YYibrp23gNUjrQ(_c%~I}%SY zdkBk9d@>=P^nJsCs7P!kj0&4CUgrA=+;lX6@m1BBCQk-`0s-!WtALpeRx3noG z>qHesosi_lts8E7` zViZZE%`xn3DiQV6DK3d&Emz2Lh^3DBnUikY}Pcd zwG^~x&CtM~A?KD)LQ!LMWb;bpKyG&+W19^Ok_-nu|AzK7_)wiEv4y0dW_BY@TR{31 zIB7!S{Wl9(ylzZ)a~uj#?neCEC&DU7PhrBm4DxS#cE<_qC}eslmMlFVi13D!;g5RT zkeUQEQnF!`{izA2`^3VOHiML+{ioYF9c_+UElw+|irF2A%H7ROrjZIZR+a!<>baao zYlJrpelII9CiF@upRCYdN{58oZk^!dBrf<3?t972vB|cXUonmcG+E(W9Z}sIrhp(S z7tgEE>_G1B+wwZ!hO}E4Xw3?TC>y`ubhD+m9+Kp^dA96S#lCbaXHfWxTQ-X?G}ZDy z|Gh|1d_lUN2q8rjy=)k-n`_iLlzW;c_#q&;*+2EtRgH=$8eSauLx9UW_UU_!Na1lL z{->?Zgo-%`mSU;hxAsy2m!aMPfcu_{SF$8&5zZ}MDYsHplSxnJz!QiJt{le&QMlC8 z)J3`=QnY%uP!a-dn{AYrt9e}DVf(Io!}FLE%v7CBunaBPP}>poY}q)D4&mIw+U9@G z%?*r%(6PaN5nCybAm8aX6CKjCf8V@|2onEbv&n!sKmBH!z+Dsve%%DfftGxm{R#Ms z?xW2+2_E{tHq#wJ%#ZzFJfX5xV-m6deeCq|y;8GCA}O))NVhU;$cam0Cx7S7uoo+= zs;Nvo#b9?pN8xk%O*?;c)8n~SH!6G_ZCfTU*A~3duu^>euS*xcF4xzQ0+z)sBJ$HB zEN-POG|afK3<}2KXBUc=%nS<(3<>LpCr5wVzu^c7<>CMRU-TIEO2PLK#dE)1`Ja6M zzu(yuIsG3{_`ekUFU3$BD|2N!X@8j$1o8tB}w9-0j)p1tDx@*2Tt~K3A zw!nE(cMs#UpQ1#pd|teGL0Xm)6%{=sYOTMAkw$|R$BJbB)`L9VL*C(K`BW4!xnD$c zlyzW_Tzw84&9^~f0tMUiQZb18)Ty@*A0yQw+piGj7iY(-T2l2= z+;$_GM{^74{@U&z|GT2L8Ob8ZFX#RTe>ss3Px9(MkHup5@89oE8g?3Qd9wG2#Fg@M zCqDQvoxItZV?|hUfl`wMIN5AIy${KL_SXuK_M*ilF+B^SqGCOd@DlkxvYB0*TiGQU~+#~T0o z$9K%Gvdw>bdi1}4S*OVVX==EjJ61-VfD?CL^dQ_#mH-I?$u|xmcTR5LmQ5moct!Fh z<-sWMUSG)Czg9T^KjZcPi9G!GI~(Z#Khhxoe^P8sTOn-*R-HL~J#M7p`T72Ugm>>w zi`euWesW0ICs8%35>gu&y9+S^uCrrTDdEV|P!(EK;r_e2Lgbn+gJWI&0@5w`*gUCI zccFmF7;>{RK+|2Ow7k*eLhH5;N;sOM$?tY;H@r>lE+ZFJ6KPJA`yY|K3AxT0=AU0& zE4piUO7}gt%*uQ}H#hgAKmPb*esMfKK`ln&^Sc}6@Qw5DEn4{{FvP>fZWMp{z2YZ! z>^&Sl!eCI%>NTdVuYZ``W9AY_i{#YG5~(WrYRb*ovE~fOrML#kUTD!Dx;!XV@-HeX zGH;CkZD4p<0j$jn<0}7*)s-a$LWxH|)Ux?OUEmc8d(ycLrsg#Zn63WFT!KHOs|bSX z{iQaP&-ZGI*7+MZZdi8Z3Btz-ib0&8!34E|l)g|7VsSn-%AM>D!%uY9~Tf{!TSY^BF)1I0Wv-=(?b!!c7M2?3Qr#%ELFVBG|- zmw7=gB;(DtcQ;UqDMe>Gk|AE0sSXw|eixrX!P!dxBdky!6~{YSm*6kKi=`A2&Qplp zCnr@9-d5P=mGqINp(vY5lsMbBZy%I6etY|MpoIsd7_s1GSKaHP#f4DDMEM}3>ubKl zaQNvPzoW%ymy*~S)+ zgcK->WLLqW`(xdRJYRb(nY{*KtsMrt%Fy+NOJb~5!cQNAtQBpJVFp%_Q;@Nu$zi4d zW*vF0hMLx^0~u9p=muP^5q;^d9mJ{H2do;vzC5B3f)zmqrx%9fs#sxz83;tZXI!(` zfg7)qfYLqS$Wfzx=Vvkfq-ait%NUE^oqn#5Tp*%6w1_vmYm^GxV8J>>7$A2ak1HwgL}$| zZ$Rmw+k0HW-;Yl(=gI=gDRXU^rpoY}#DXgBzd@25SsF4}KSM%4ufVDn2P#9&YYYf4iJRIkV?Sj(KtF8=4p+LlrcS{|R!0LBIQiM}2`r04{pd_2y zM26Tfls(H4*Y^&D*s0Q8L>@rd^P!l@F#$k+dW#F-- zyyVsN!^m|}GAfU~-t26W&J!04G2hDWO$EhKQI&KsM#2eIp%*|mxPSjZHw8(I;%xA* zyOY_iUt%>OkrU+=v`#llP{(uDqU98*j=u5qQvW@y zBA>{EwZ^?4A548#U=JCm{R2(#f`VS5XHk0j_|u^v2ep4}r+?wOx{?73#=h9P>GdT$ zQZYrVUgMYz63EHLm847ZgqkYj@83RzVAG0dE|%bexT-)s))bZgc7Mm`QqR?qo?seMs}KbDf-2WaQf1A6Alz6xLCrMXFtSi5ic=qf)xpg%bt09g5N*NhkU za1ZMX^*EU+*o4F`NFL11Tb}Fe4>$H#bQ@w{ov#uj6-|GUsVIRNq8yDbGym3(_`W;F zG}plP$m{GXLsMe=J~68MF{+6j+bccOXbubMaAt} zhkK9c4z<_*-h-S_R^0v#+>Xk93WxV8u(_BVw)?bi&5QuXuXP{l$hPSJK*#QfR+aWZ zLDQMyTjT+p9c0IcTFhMm9XW}nIF1lXJ?r9ROS{rjYqq@uD#c#e{tYd8y5M*4(klwX z5s9<#AniA1HLQOzB(;yZ^kSg^45*rAF^h51+I{HkYZX$y6`@2LiqB&1LgsMaR26%` zcKQQUg0ATS&`}6-!WW|4avUtOSobdbT0S1iZZ;_~HjkOl<~>C&5qLf@w~$fHVF(qV z!Aty*#ygK+rQ*-T(aQ~T+t7${adFLopqYacQ$!`#z9ObHYn*Dk{3~rJj(-Jq>?B0Xet7gGwWg3)Feh~q#0y{ANibSP^fegsRdnq@c=lFUP|v^)?(kwXpM&(VqOthPG6Ukf?Q_P#S3X9 zP_LSYfqGLQo?!)Cup21pQFEA&r#tE}x~mLT0VqO2buuu7FJwxJMT*+62^7yk!tjC~-_DZ!vJ<;ZBQ z)8||pf_Zm=Q%H9Pc)thFnrlGbr^H|h7~Db?hSwJrdXOgmlUi>d85X-%K;C0Xu88fo zvV&50ZB=5W@|#+$0u0_4qHXy2 z!+kpK`BSLc#Rchg!~Zqy&^GdLsu7ie%t{s%!Bnz;vFXaQLrv{quGJ*8<{G5aLteWA zy2POQw|0>0{0Tq=qY-w&)P26!ThL*sE^p?GazCg${#HiYl>5L?vG8gEv?%HtWVWIv z;Bsy0zI|x=H!6ygC2us7Dnaad2f?O2mEwxF{XHbq^Z2h2J2-?Qgcnf$#Y0(Mp_B%E z{P=Mffy)MZXh8yV?kBPhkjoepEsw9^RmHyo2}ko$PzM?EDmp7xAonO`Lkz)Ay@u+5 zSHYgg0qr6uo}rSn-2>I*-m=tVgRvHA`J5e4OYz(d#a?Sow(H9AL0wE4F%m&_5SwPn*f%l(pMML*WgH@ z1<=uMD8ekUD+|^WF79ya0SY||a~onLla`l@;E#6!b)9q!03c>SgiP7XS-pgnNx};# z?9quGvH2UN2TtCjV|xUd_s^SV;a0RYYy-q@=({oqgh7r*pfPCPk(^FzU$6ur1wEib z4+`B2$&Sa*|!c0Bd~U;$r1 z)Ni|>OrZ6Z$IT@uGBoUUgGr#4_`Uh(Uk76$6+QoV4B+$*W4Kvi3R0~zKV|b96ny&h zm@!N0GvV*>&WTnqn|O zS2jME*Ce9J)0M-({~d#W(DOe^FIi0flnt~!U;c0pI;X#*F(*3ta=U(sb0;gl8JBjQ zd4#6tyV06nMA4Bw51f5oDWexC`j#q+P*kkQI;58YLvF(Qs6GhyO%e-iKTG28cKRjw)tD?mnZUTPfNQ=QP zj-rfX=JKL6=&!)n#WYZ=6;KqfNz7ka98Ul#*NNnISOX}^C~V#q3lbMR4sY-Uf@+P$ zzzq!n$K)Tr>cF3LkB)j}o_Eq;Z7%3C?k|LUKtg!uR`6WPszosA$@Wqc+ zH0@J1V1#fef(zwZRQTH`!p#y^mkCqtW^o|}Sb(4vkMuQY ztXdqDL`e#KH8s$U=5?{jA!Oe^ztipGKr`iFJIivX89Tv@z z2Ib&RpJ5TF)MoeOFP^y5I}rlsS7bg1>R5yZ7eOnYkY2VL*)*z@-sUU?++ixxPJ27b@?`xDTQsCTVNybXT!1v9XFC6iFA3S@=H z-f{%Q_Id%kJZ@A4RS8P^h4X#B31AyQyDa_K1=v#6d>O})##5@7?bev@FB;G@^Q+|d zpjf?lwTzZQC7)QYj?^fjZv|MF=zi1V+_}~?10fknCKuXwOV^5BozQB#rdiM;sEtBr z;}vOz3*@j{o^1`wg9t)WH~{oeF5Za0qrPWQ1A`Vn+T-JYyPtVhwPH<2@; zD?ri9X&8XTN+fm4^Cc*e)E-?%n%K_l@v@-;v{A2_y;UE1-h1znGZNtEe19_4UsZ)7 z00VY$dlNLwkdOt&w*KmsEBl9|9n>rdCB>g+QRM(~ohfw{hXOdj>i*X-w73kP;q7eLSc0|!D2df-(fAio_BQ0=|n zms!9cMeit{&C3%zBz$K-pYHod5E{7v6MO;E9U|reZv9t00c>X)Uj zF{^-oVUPb>-J?>EHZ1539tw&_pG8GQeO_2odpw$npHL5P%+=7)5Oq`gr_lvEbz0?C zK+%S7U&rmFm;U_ES0FFKgyR8HzliqSH7;5hinS2dZ%TQR|u2AaN4hM^;poa>coy zF||wi753g9Hi&!B6&6!M$wK2^I~ds3qEg^L$)NX2iOA>J5ZF8yYK{6HvRXeX-z#~_ zb!KEA>Qqd$WhDGQ?HN@Bw=WN9qLH(*q&RG(vpP7O$&L>*qm4qvY1)d{ECm2SCPpqb zmHZ^&f+-Y}v&0D4AkIeMbUuR1H-1H3#~?0swR{SM@B+Zjo#`)x`PHvka8TfnEzlyU z_fWT4%NU~8gJ=LlqgSl>9TfZ(-9o79(|<)keKre_H=fo)=gCFS)nbSTh`|mRqh2lC zjG{f#0|osR`NOfS(1g-Yc4aDnNn)IJP3BQI{3tDmnsR;*lwP6ODWsth4cL8osaPXD zI`k8=W^O=(eU-_;g4+C?X|_{xX66z0(C=sU6g~o`Y%h0Vq{l z`cREl5~IPJ*C1Y%LI5EmM=7PN9^j27eae<+kVeBpQG<^!!&bU?QWvKCq1^8YAn_^` zCr;`EPSj7)PFKtCfw0e`N7qW+UC@A>9b7!5JtkUN3VbDKQvDP~qA1X3l2AqsJ9+Rb z1p>IjpMgf2X`GWkjY?(sAs+KfE1690^Oqz(>gqC)?lgqm2?Vd6 z%g}8y`!3v)wAvfRF2sRuO?{*=PbSFX zewT;sB~XP1;^N|hH$Ods@R4XAR2C-NE{KA^+jI^s)I){uQ?@UE0k*n(!LX6KR=bQm!=I>S71}X(ep?8Q0=90hr!{ z8t%3NCyScd3r`N2n)+8hVNKFk7v(|#VRm;y#Gvn0n4waB5|o*v?z7eiL}j#TnlKQ8NF2Mu>~BU`JrH~kTwLONUz&n=O$R_*xhYs#+pw; zP@8G8GdBQChyvUQgCeL5?DFC@xby&)D6+N#3xi?C;2mecjUZ=YRtLk3D!+ZWkNyP> zQ~C`<

    *BL*uD4KF_Yd4=^vkQ!y9_l$j0+-aI!m(JlmTA|oIjKX78J%;G!__#WW% zY0omNLa*SNqeK7Dq$g!?AAG zZ^m=Go%LE|%nc0zVB7+Ws-R&$`w&;Hgn&AmB!;NsG91jK*@tQ{0I9)~4CK`{b6(Q5X3jau zLtIGq0~OjfY4ipkEVZ9q0dRhe2kKuOhEN_;iF(ifYVSI{qPo8Bvn0l!3W|wX5J*In zqD0XMB48rYi&$xj5k?%4qS8VeQU#@n6bnKG6bmIZ6_t`m6AMugbfgJl8v#*afC1*) zXBg1$m+v3=*2=7v6+)PKZ|=MI+?TNTe#1={#9OWAiJ_V(BG*kf{1P;8s1n_9XnjqRN{V3k1sz{nh$JKhO8yJ zJ+z9bfT^S>6a9t=vYqYp?Af#OzV0@M&W3_}z%Y3NkSlY$iUe-@;6{TTx!Dc|1@<){ z)_q@|i6@S4PU8>Y#VLvTJi{j6xWFB3T{r5MFWC`pWDJX5uZe@{KF)|=`{yYwpWUno zPkv1M%^S??CdauYoh&?gB8TG!%xs$xowZw!7|4c_u2fY>Xx9ZT#z+`Alj;5_XW@VT z^B>WckhNnzf$4O+f*eyPU8H>7$O|iIub%Mf)Jk7{qOLJ_!VcWkOskc2w@1(<4oB5u ziw@23b5-uDufeVnU$qaAwjAHbxbZTk$T5w5yKbLYd9i`=QOBy(>Ha`c>(LTJ#nT-d zdMonj!-Q(uiy$ayg2=LeCWFP!LJBF%;o0>Dfc>s(I{sBjm^%zYpn$jV^SxXQox zHSKJkSgm%H(mE=4brmjiC@)3NFXi@5tg2G<;Ft+UZn0N2(8kNKELp^%tU8I;MY(h>eOL?B`92K0S? z%4ZkYE+xJzbUcbqd2$0Pp-A>F(EuV(MEV2qBn4Enb>d=mplNsN43LanUx`mc(T+n) zK&F8Qxpkcn)Dl50oL&tfM-PXTq}iSb{z?(#dX;D52h6t?*mhH<6Yoy7CqMP%OvZ8U z+76%YGU*B=ys_TRT~N9D;yL~C%Exh^(`Vc}XPI&go$0tzZ$P}at}5;~DztK1O7oj{F3fFmPQqaOD0|DwtL0*B_pB^P$G(!w;1j}u>HY6w(`XkaT>?jiUMG8Zx zvFMg>4$^}Jc-V&lEw?n759SgvXydEPdU5&~pBhAK*?7DCpizp4I^1vdEU|fDMtFmI zE^@UA{uSI6ZK?=IL`!o635j5uDIfnH;f`%mNdfNoUF71UYw;m=`%Rhdk1u6ZH8b0> zc_UBLZkNT}jfyaxaIP@u-O1)spc7u6AQO@D3No3Cp0fZSF1I5FA^{_D`Ala&B1;=k zn_4}xZ~5bQb%le3n2hb_AsHkI=+?|F5ItM2^)_>adl0Rvw4v`VsXvatF1SAw5fMUC z2IS;zH-{*5b8EbMrXd&1?DA6pLyUYs5pBysIvvdOCpAg=)M?e{@ho%3+kN@8-@UJ5 z-8lU9%VaixJ4oPV`&vttlMuGwY$vP@8CbhL5vU=aXG)wWEnEY+z`T(lpK-bAM0=<* z0sH8mB~~wPAHe_HocRthXMb$FPcy!h{TcOCEe;|!Yc)P}bo==oVl_KS^$IYo@~JNy z`w`a<0eEeD35R-0SiktmX=}E z8iI!BUFz))m{IC{xMs5i;*=2(Z_NHc@O|y8Y5i{lysqgyf5BZiqz@#tF%vRCk?C_$ z)>kA>++RV#O1Hh7S=)n@y#loSHWpvazGzLmpLNsTPlG>$s(W&y!d z`*{*KY_e%6oF36{Q|Cw(6cn6^3s|-H;dD~zWwrfc`f2P`iFyvzbw}u|h2abxFD=8wM}_f@5%{Xb_W0WWa>{cPZhqJ^u0#NuRs0rnQ{9e z=}digl$#qXwBW?<8FBfSSZ>Ze>PS9E;Ig} zASFrQ%Ifr=eWj~9a6)8-S9kUGrguSw$8H_2Z!bB}l$Nm3MGZZ?BAr3SaQ#>;)~T*M zcjoP;NLg)X?V}xxhbzCH)%B3(eKYyIC2*+S5ZNY_c<8fI?JR_1mzu%n)vH|`8mHm? zkj+&52B7mb^-!rD*w_k^wM}=pO_%o7(>I69aU596iIpz15TVQjQg!GRvOSIYBXEL; zC()~e?{tL+lC`N%j4!ZcO(N1he+eaKZ!`185?3;{6@qDf6_6G{a=NuqzL07~gw+d?}@hVjUo3r2@a1Dwk(zLeysi;$b%JE`U2_i5u~hDd_yYk00B zjpGU|{M|6$5Oc%MZBy%apZ0haQ=5v7fz5llL+*Si`awy(p2z51xNt$)b;#qVoxRi6 z2F+dWXqe$tRaKRcYCr5Y-&D0dZnOfLpb;#Z0#Ef41)tyz%rnbtw+_K%5iN++=+DMN#V*ZosSwJ6B#07{S$zPR&fzM4B;vNK$I* zw2)dp*Xo!TJh(ET?@eCM<>nx*i$gBgikJFV6oF+Jq>^xtW2En<=iW8;-;Hj~)-Scu zt2wU+%t`7{xhgZLtu?LX#ruW>)n%VZ+il?83PBUtNJNtr&pC-)JPJpwB{mOn;zCVe z?=;5f4|k@|AGjkF%{WrEYhcM)-R#oLJk3JjP;;dQhSofs_%R=EGx0wQgnKX`DG(J?gvQ@^-$JL$AW<+8|s{~^DK4LQl@kBQuuYwWutBwK$&T>kVRu?B8 zTY_tIx{z8%0+g$D9LMUe?cag1P{8^K*aJ+P4HYEM>C>sRJ*<2%hx*T7V%{LXaRA`A zepv`mO<0YqzHs3}ud6kp;h~m49ut?sW0%)M7shU=&OLy@l?{-Z=cH(QEb3k&BO{<$ zQ-OuE3lxs!)~#{9c1A`*ag}m}Q_=ZZ zF9=SYB^|2peO%~?03erp+jR$vaUCh8w(hVbO`X5`{U4o|Xz@dSX>F4e`f}Ct1G{)0 z54_#M;yP4Defhud+FYmqsZH^59Ms_Bl=qy#!=)g|v1E`@=gtgvNILZ?mNoiZC4gGU zFN%8z>5!mlp7R6c(>Eo;11FR;3p(66Cokz>?jSKc_pVUWJIgea79DFM$mbp_u21fPlwKEl65E+YY&l&7oo@x+2<&b9ZZe%-> zJU3BTLcd6+WX4rw1t}1{lz3Q*`)bTqu~O@aKmloOZcW}AJ2a7+^YW9D?h5k>mG)%0 zB0U!0;zX|R`Rimg8oYpd^LwQcb zJAzPsIim*=;_W6RWyG%-`#%HLFc&;`-u}9&P>XO%o)ea;grJ)J(H$!*D<1-fo2spj z0OLeGxLicns#$FmG$nGi)X${@2lyk6rE6*`P_9kjBf@ zqf#eczo7wR0b|iDwkk&aB*K(jJ?!ehXX;5t0!axMhmjy7U#x0-Nfl97>gCG7f%jM7 zLvzvQ$7TgAw8`7EPp|Mb!j2bs`m~_~`vBGFOu0k7*@;cbbD~Dh$oubn-{{^9=n_Z)MCP1(H$c%UNK2)u z_?*zIdXs2f)3C3BMSx~d84(C&Wo2`^vLU6Tmr~IT@)l$`!4n~eyzDSC3E6%2f=}f+ z6a|XV4*rbx0ep5T6kv&K2Cl;5nKMNGK`d6!SG6zy5a1~>QJm|DPEq5`POJz`8hpBl zT^$o2Ujc%mt(r4@;8Z8cHAJ?U2*RsFLbN)s+*qYEPGc9wWBA;;b0HQ%Z;$5x#(@Mi z4`h?3^Iyd?ux}PULXJiK`(a1p#Z3g4w9;-gF(paNn1|LX4*_$6>$Fdx8Uc@3;r$)^)KOVLIui zIa77(7SEH9JiV3LZDl-Z4heDR2p$`JJ{*n>g^`#0f#~F)b@&COLkcDe%6MdF&G~V75@czB6e^rgCWy^jx60ms4hO9=`X$cCU1V)4_M|Da zE^`Mn90kDSPg5rRNdsnOSsK!6A_YX&M?8sjMc|m4MFbSN+6;C7ezDG8z^x~mZ}ro6 z2dfZ#El4cFo?VKBqb5-cglZd_`-LJ5DnNyaecOPYPUJhn4VHm{+TtRlzs8z@j&%F_ zwB580hp9NR@^=IoGUZ}%bw=Hl1glJEHc%!*g&BBI4&ZIbIJIursFWPHXezFUUqw24 zG7)PpaK28OLh&7rlKzmc>>6f&7N~)4Z~^UpVLuZWLi*g1Yxw#NTD8KYmw@&Oey`5o zgUqaf`%b|spsW^mwy zF&y;VhOM;?n3zaYxto2$gQ9J3!Mo<~$1@rcD=~IN?<~*{3jwC9_Y3NO+nycJ|Mo^_ zJ$PeSLE_v4#z*b*o-2Y-5wfHjVn}v(43pM0{60;WwPtW07F*O*!KW=RHUL7wv#gV< zdr`6i-(fDkll#_@WvnAW7vaz0ax)KjuGM_L=QZH>F2qNJ!3o;{Ib^INzxipkkDFpOepETWj;ZEa__W~?hGUgbY=tnErA7> zKnemon;DtnSM^zPL??@s)D?UFmcJ<41y*{!s_nbX5nKj-7YOx=p#;(Nc>&FQYv*NJ z-MUnh>i8|VHV0C7;WA;h4^tCB_*)Zt-2WIKeCks|`N3_Q2w9!dTGffrMxMMn!6Wg8 zIt+}oB5vvSxvLsIH|^3U)Y}v89cXxo?s?H0RbZhCg9W%%h-4S{|Tayj3-wQ~?FFh~yXA zVX}*8Om8A$?RNlbgW42XIxr2EI?zmWh~@ur!X(8y{yK!(;kh7?N%5hLoy4*7&iTlQ zVEWS?Mxv#DVg)-o+rLJXGhC+RE@v-vvu-Fxr3movutipX-$;J1zW!>CEEPx5ujeFA zXC%VKgXK64YnNDY!ltcglz*70G?GDIz*UEGB*#>PLcgBm)KmqEqC|3IIh7$RgznKW zwB^i5dK2u3Jw^!%*KG30L&B{LW9dTJhk1a_AkLpXiG3L4QP{@XVPr`;bdI`QBd#Si!7y`+PIHU_STzj0tWd zAE(H%NYI%;voW@K-*bzN1EhNpBHa2q+ zaU&5|$`JNjA8fM^N7`3Gv?FM9%Pm{JAU7dIruAgJ{$-|l2v#sDb>w~92mQMY*;X>{ zqF}fq6&rxe5Q33377D#w_w6FEF!jGHvnv<$?EgpM zm+&8@;j;fI4PWz*((oVtQ5ydCAEn_>(Zvjt^2|?;+CgTl2}TzO0Nzx%zW38 zz5w*8m7x%pDu(#Y_6{9rw(It}wDh7imTmz&+vY=*g}m?1$;qKa?f~jgMXxBAu~n+z z29(qNAS)=p+y;jOv|%SQ^-XSIBe$#iy$fksE3l7=?^h#ll&>FK%!UosLA|+Fu;7K~ zQ?&?CLed+(f|abQm=_PT+rE{{%FK+QGh+6^RU%_5ZkqgbtntlS*%zn-#&%WP=K{*I zKvpe<>@Sy_{9MBGDPAIrpP9Irk3>*L_*PB0(ZLmx#XcNnwrFfTOvb*3=2mO#IoJ*? ztmR;j{;9^XnZ#z~Vp-Xgl&C*pzpcPIOJ4wbWoARL$pbNB|JO`$Nprzi^ow$!{c=da zPfM3G8P`IlrXV#TU#^~tn7*&;@lDj1N7dWGl1hgZ%Ss^@%oL@FO{30p)?UXOzk zj4G~|*Tc9Po=?2`$UyZ|kLpltc(qp7NDu(ZoNO_1WR#!&G}?n>ZN!-=433V{gemD{ z%Zf+2NXYui)PgJ>GVs%~AKpH7oK&?AKZdIXJejhxj;ce72OeZeC5q3KuKZ*)LI=y3 zNHaQdJA{SspKmJKsf9O_OWrqm(DT8TZD-O&G7r%#f3inzBiN1-2hpqYH1;47yOI-> zJ~3EDMWv=_hX6OS>`(UF$HC(!v^vNMtil0CP!kBh%`c0_kGwH@tUYDaI!r8HK?nA7{_hNJ7Qyw-oO|s-$tXZkyph<%qJ>P+*lX+D?>^5AbiTE*2U1LW+prn4uD^81tS3mpm!-& ze{y;{5irT;&MgL9lp-ns$ix5)VKVq}ODJ?N0-*JUBk#bh>i;$$+zQ#ok(z1VJ3eyF zV8^jI^RyCZEg3XAD-bJjviZ^ZI4>d$@0sg@=^KH}YvDI0TefVW&eo#gA&;YVu3~Rz zqrYL2E%abwUI2kAD&Pd`dsv|}3!o$%Lh!rV@cd^hYZ0IF0~buV!x@gfAxS%LV4b%#ALBigfHP62c#Ezxns;Jg{x;0HyHejM(2 zFU=w;tZC>pObCl`Ip=ho5KJD0=-8r>>#cPgn=_7co^lY<@S3R5oAXAWZSiigmLV$cpl!~bE7g4=~k_)iyVN9%vY2vUK zJ=UczYCXc9>2)XE+RUzgOFTE?Fk^a-EHKaqBU3Kue3ZM0Ol)YqU|ZgGH`a4p3qFY| z{60+i#UD-i9LNL;P3m$x7*HQxlvOK<+WK!DX!3sSN*T6IHB7LoaQ`LDhNeeU!9FCW z2G9>u;EF}U?f_o_2+LW(`a};{!F5VFnQ}o?q1>!`eLlgf&YI0b!f=R^%G0A^OJQv4 zJKjT)4&}O&0texC4n@#O8@x{Sm-nz7Z@l^eT!UQQbJl&lKj~6pc+`H(H7XBcSLb2; zsjqt<<=o);*wy*?%~xMh!QV_p)4pbIRji7LT|_mQg0YE-x_ZD|>?@&I#V8fLZs`z+ z9KbqBJk*9`J?GZW3I|yNdg_P2E2stj+XI9h2ntZ@b|5d^289Y-zi-Bu6bpyCQm$WL z!z!e*H!v0p;erd&3p6%19!>5{;#5OH0xm#&@X_X>Kk2l9!r&az4B{wa78q8*Y8ZCE65}A!K71Oi#`Y@If zvh8BeB`@Z5oW!{gt;rgq{|6D)CI zd{q?{6WcB@&gK4!=PzYFLMeCL-wNWTEHwsoq~ew`sNa@>KH&^#v194@608t551#*9 zxTY718ecsy8QM0OA9zQ+f2H66Eb-_3b^nuKk)`AGEP(t zs0DQ&*6?UqTP{#MkBvdeh3vwh`^FY}&RCm0`EM~0pPu>w&uLAwFg7n_GH`i^lk z5g#m9%-el9`@!*y`$h;oHFYk6tK#QuAUTF6CdS6aoz0M&qQ+oq2-rNTNHA_jgigz7 z#sZ>JWb$C;+}C~VEV%lh*Gt@aB|`SYGob?WDjS4AGTYFtK%HUp9^uF=??)`sLi3!+ zQ3vUcs*kTg-)IF>dZ$YD(OBTB_~?$X)5pie=s`D|nV_h(zh}G$CQjQSl}wG)+$pnE zL+H!_^EKV2RMSMXH$L0e#aA;P_t*aJwfJc@js*{e#oHNQ(HKQ*lU{9Gy}PoXs;6M2 zYLBY!0#cf_)NVFdX?`1Y)NuH~OHuqIOTGwF39c=>9*k z%$?7`AOrSS)$YpIBo0uy|8nmxqJ5~mnaaQ-IfHEvulcx_cV>o5iy>c2-4 zn>fl--|3IT!Jz**tPUes^@x4BN-9su(4ztfcCW036R5N&7q2PeflQ2xg** z?*Dd8ePLsL29+`c_@q~l+$f`v@^!sD&enZ#a^))y>w}@aUXis-OUQl<@0$p<-iw2k9?< zJ%dv{My{)|^}{TcZ{!uvsHmG#f{e|?7N%a8@qprz z!VwPRVQ=pr9PhE3D!HShqpu*{b%4{R8_8}dIz!9@A+C{H&3T<&(TXp3r)n=^qw|#Q zqk&}X$b;aCsZ$v8vY-LOF+A%BV5swY0QnVG+&sd@C)yzvWTTde7qb7z-31N1oInCh?O1N>#su2M2% z1_<0k@W!NSQ^ps@Howf!Gs$ zTZ@;Td%q5T*T%43JX?FJ?NQ>r{Ht!{Zc6Tb*cWc?fCL_skJMNX5DWoy4wd0jwLp4& zT%4kY+3p9u+)hCDG)D`jZp!-5+=8Za_zusXoG8hS)OrJ7LEnqqpu zQ!EmF(qHbN&6jh#Fe8m^85q)NX~ zDIx2|?L=)Y2mYBHxI6paB?%L9NN?6?kJ+@muB+t72{iFyys~gOB)v+qKN>G`F68x4 z)SPScyeW|mAEz!n z4%*w&t!6;LF|`)b0nOPvL>Ck5cA}pvbAZ*(W;DYVLE7_rY}wzcH&F|R8?g+!q6|`~Ta|^h+gspZ>+bh87HQf(Nc35$%?IxXhSTj+xuZH)a^!NA zlK-8rZMC$V0Yqyg*uPhglt9rgS7WZV1T#?@`@Q)OmvH-vaOplVQg_G0p@^JQ1h`@| z;r_u^=$-5UloV!V*CB1X0{xYAe5!P&)gsy7MC3O-u7d;h#Su_0(zLalYtNB7#arRy zN;n%iNqV+7RgzQIe=kTpEwY+VA#Z9$p?6{-iHn}UET4)1$huNbQnIPlr%>|2(;BXhKWorWwt z14>jnzXxs~{myw*NZD!h7b|}IEHEk;vU|zY0D(voX}EkmffJqHMidN&O} zksJQ9%_j?4E>OruhYVz$-4??47IScNis<$9BYYMP%NMnrxPojj1vvGfmjQX4KuXL> zRJ}&@XG}hJ&{f`DO@VrR>g)gznMgHPE8Lp~Lpm>*krN&YJxyih%VOwV2PxhtD6NFL+0sU z(zN%(cN2=@5YTf7W^Hu*m0^;kPMF8C)1J#o;}Gj?l-oAmhC+F2=LZUEXY9 zmZYPNm1^hEfg{-t9hCK3d_;5Ps=*)j5&31P74XB>S!ZPnC=?SDqp-$un2u801^sqq zod_`gHq~g14Q78}SD1=Oa#Sk0(5#=CprCsPaxSaS2S(@7BU3#R-k_d!?}iK*`WDcr<_3q0&VvO#_er z;o{pqT-+QT8kV3Lh40@L*z%?6WI74Os&LeYCYQf)FKymoJWG5&b#PncD7~t6vNoP&B%5MFg3%X>}r$37UhJ)?*WAUb?ZzYWC#Qs3=f#orB`v1kZr= p>VLid{g8jhg!y-#{2yyaVV>8od;F9p&!P2VwBB4V^Shlt{SO{kDM|nU literal 0 HcmV?d00001 diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/y_vs_yd.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/y_vs_yd.png new file mode 100644 index 0000000000000000000000000000000000000000..7c60fae2e378d13fbb48d4197e1b300b84a0679d GIT binary patch literal 309408 zcmeEucRbeZ`}fsSDM^t+lqNz(_9#)3hD{k+5y{S86&WGfGD2iUip-3%LMW?{J<6Wh zJnv86@BRFK&;QS#_x*a^uNJQBbDqa}9Pf2rUe~W)q#&mwCy_`Lm!u`-NhC`AcE{Om zWcVfFREq?D*=#9sNpTzgbKIuqi9c^QlUB1Nk<>2`|8JlUI)4s-DPSd~YNcR$+sa1U zLZ4)!ZDn@X)avdXokREaEiCVt-s9om;^01Y$k58lOo)^7fBv1r)WU%Cm`|(>iFAl` zN%EYcZRF@rm$VS;)yk=PD)+tHQa1<5Zr3}zQEDuU?;N$^qvS{-}+ApR)#UA%#s`KKK-`M|aip0z)uyxlq8y6|(WqVgkfgyD! z0sqSTYx(0NMVbb}Pb|kR#WMm!YX&Sf;359ke@AW$ z|NDK14sX2mKmShrPTG^S|Ns4)JAoApP4Y{#lBD z8^u2>@o%H}XC?k^6#uNmzm4MmuEf8M;-97Xw^97F68|=ee^%n(M)7}F;@?K`&rO&A5t z4vmEKZeUYR6Xb*?p>LZ7!pAVd?5~K9jh# zv{NHqq=tU=h`Ikh!dixIrC)ijd7qKU+K+l?zT?-TJ3M_{6PZJ6q}0^ZMmzF&?vHmI z(AU?OQ&T%|(T~Bay1Lr1B~2~MsG0Rfwh_(in>l`d2Zb*T)kXE?kEHw5I}Y-w)f4nz zY_K8r{8RmmW_e|Z{Utf>3y*GJ2H+zzU!|%Ci(c)hJgJO;X$FD~2-?8tMVTT;4p=|qq zWrsaHPD``jvyD}JD_xcvV=7*Wul~NEzF9r(YP84!&JVNlg_9q5WNLr%uw5Jo?VIfR zWNn{b?=)^{-sj7Iq1bsf&SiaVs+`j~GrDynp4MP`@VRM)WxXivNNa|_FFk*S@I;}) z&`@#_gn*bBCiWXy0;^vWuRJ&GDq8*R&z4chonAOyZC}7aGFw9dxk#CtoBLJ@ z;~`KluX9FTt7bCaD_;F06eX-v=4m_q`NW9HWv7MJ2^S_xk;$`BbxsRCk99vj+CEpf z?b~cMTSnPO_Z_;QpB>9I?JBajtF!5H;tx5cw&!xlDKF2zt1(|R{~>p#PPnhlIOBDw zF^Qz7Pkg!4@*hiQN7S=!br1_hZqje;^Tkt|g}KT@)HF2ZbFErkXMLED%ZBat7nzoR zDC%;am4(F%t94tn?}5to>$~yb$@4>BunmJ>o?rCY$9{EPzvRzYdu6kV*1@0o);{Au z3of2Jcg||`duC^bQ&C~Xtd{R8or08^!KY6ze+}jQ#W$%Ma=~@zFmqY=h%!ViMAUI592eraknii zxillkr2T!Eh@FLOl+c;++&;fBA!{QXDH9K?i8KEPX-~YlZn@27+uz8V(MA$rg35oe24>E;Y;5aaFNj~g#Bj475<;p z54TeKwcjgX7qS`eFuZw)S*JB!MI^?->cL9-h|@5 zufnUVq{dUl`(6xul9>OJI0T0 za7|2~y0>W~>1ood80Y*J&V}Y7t)We%sRpe%)+!b&nhws8)YjIHFDquU8E#5eEwnYC9d2gx_V$j;%F2?R*eTmiP1BRSgOXlC-wAZkZu<$5~DHf3}@0-CDm8maOpV0@~#f zb|L<2B2$trd#_%;v*Tqi-Wr$v>@T9q22C~V1}x;{<@dB|xj5B^aUH=x3;xYW5}?J@ z6dajI<|tm7PBZxC%ILh%^F80%xP>R;C7!zCJf&#R+)nAvtxS%)%gf8ZCR`3BP6UIX z#nF*V*3Z6;2(g$fYCYa{&>LN?B1tY@XMJr|t={bdmvKv4?m)=RI4t*+JE!Aek6j1p z8ed)WFJ2upHJ|J*O&j_udH2WLV?>jx31P3f`>8sZE#79Lb85PVlYb#Qy=ZATcO<<4 zv%lvtQ$^ODMmoo>q(hL{BXWNh*i`0Qj|^LlcjQ@)*in$q=BK2j==^xAFQ=$TeNg!R z6SSxD<%!~$xl^RvB$37bK%!UE`Qyin7R^LW@b<=8&h+|l9ygEA+I!+^S)7#5+vp9K z?54_T<8czK^SA4q7jj%M>%b`BGV4BTs!T?D_8xs?0Yf!l?#XeM(3)~e=gEhF4Au74 zQm<4pG}W%Xa8p!KsU*7X!ne>OYJi$*`>U_*e1DJr8UIPo-(hxMWUfg;?V8(#Y^&ej zR6p2TGY~+Dg;&nFHQg7GKoDQ|d@krD8=H@*V;_B{{oF8FaZ8!k-gvclx6d%foH14& z{qgQqsSRf331TI(@+^lgaD=8d=3xl=ppmxBFq2$ogF{0rv2)a|>Xuhl`cH^^;nbv^ z*if=%VqvP!z)4~8A*EPYht~S4Kfsv2=wYh{&p)TuPCiF!UF4T*! zJ5p0qm!)PDMa)r?T-Q(Fv2niR^Yev9Sgw2{YFxG0*{OwxLkR2Zd+%qyzUV`;_jsIN z?K!5HgaRWh*@I^iBgTHbJFztT+p>aw+s5nb@9+NDgKlBoUlow{Dw5~|U900Zx;TOq z_EB|F!j%VYI^_DMEEj+7!-(HpLOL55Tr*HNLc4XMaOSGWe23*+?lw~QM+Z85EFuh$9g4`MI-E5+B$ zpB&%;{1T9RHB(^qdyj6#6R&U{gNm7YaVCd9qh9k}F5-Sn;*2N=Up!qoHt0aA@@wyl zOisKWluV51qN$D9ozBZ+#KVd#kG``OVj{hWCC-;7uuGZ&@1=x<1TOR5vNQwrpbP$t zQFEK=K2P;k>Xvy@W!@@%koKy{yERPg2hL9K&8{WosI_UmcelUvdeGnVbQsS&!RRoW z`TdRd`MX_3qCj4KpD4wjV3RKZ@e-Bu-n5Gm$IR=;JA=yA`7WkSTX#J{^XD%y*leaP zfU@ntdjm998?h|@lbun%iBe=Yj+zge0P*AE-@fJcV-%&EC|bUExBWdkf%5{7U-1@m zT54J%dqX@nTG~lY&WySDZ369I?hMt(Frm>IHc*fnnluQQ?wXdS_Uu^&wi4NNpg%^ebaj8*(+Hem@wLgv;!R71yABGK%@?n)5-nfd=BM=;vGKPx z96l>6D~6bUI8w*RC>a_0D*gS{IcVwm?>)h(Ay7zsO3H9#h6Yh)YkzWd7pDif3>#kD zFx^T@G9>^!i$bEFX#D5=p=bwmdFGJ=v{6{b$~W4d-bR1z-^nB)J;TcfkHi*3Kblkvrlfynl0XEDb4n7U=>&I!wc8o?M#v6yS;&TWvFmwy@*^r*jI zPsDC|Gd7NVfaByz*XPgajnE+WvEMk^$iX% z2HooeNM4xi*(56~t9YI2@FVg^9SYJh`HHkTw@Djs-qv;H6vgdmp${KFek{M2 zLi*?)0Re%M(o%xKmc+QMc>!1PWJp8?2fJ&2u<8Er|M_?mtL80ZC zzj}=EOd__sF+-)$skfxMVdq$Cc$+jx#3p(Q9X)m|S+C_?WF*7F;$rd(=D&-hjkWys z`**B_x6LR{%aE!q>&_-G z$++u9xw!%Yf`W$+9Xea?K>XC8t9f~Os=)5GVQ8HaT3T8!y}c`PV=tGTSC)@%91JzB+%FDG&A8h$ZokSYe)d>v@ ze28u1s`SU2%gM>H(yuIw9zTA3zwrH292)tL!ov2~MhfmtOiX+*a70oLzy4}U-V6Nd z1MJ*~2{+8)6?A%LsNTTOb%*@Qxj4R6~H*-w8LX4kD#<~mv^6xM<9%0V0WH@2d z#Y^nb_phW|f7kC4+TMlx_utp9-*FZPj9z59Cnd?D8|FN@E^O3h_19+aV4=rbJM)BH%#Khw>Gc6ff1Q^_| zdO#SP0iwrO=(zZd4h{};1O^?t7Au1~y>bUZyP# z#klC*GX>DTd-twn%7ym?%C;P;tfi%eHQYMpY40#*=dacbCJPIT zuwLIMPt1m!STO$7yQ{?-zkV&nf=&WEaETACtuF89zZdDM^mlU{y8tT#A|uuN|Cskx zd?hKmK?_qHbS=ghAwW5^vf_$4!(%Mj>GE&G#R)zh9%Rrv9;5eQuZ4x_!6Ns*VZGl} zS#}RiSk@e(MQLxj&zAH=!?w1z{U96TUB&)1Y|2Tmcggc9rm0ea*OdTzm`!${6LI*n zbE2!b5-12%lzDcnT_yHX`u4>(u%<9wev`IGm}JR?WV*V#3rkB9=O3C>)#LpuX?|+G z@MQl66O%FKoT2{yTac+9wEP`dO8>0JnZ(NaKL>_$a%_m0Y@#|Xr>3N>ZEkH?@7pEQ!$nG0 zB_t$v@7;UkD%XNzVW!Q5W;mA)g~d@xjYQe-kA-g^L`O5$MT`2}A8XsL-t2<0b1nUO z!0O5hu@xKGn2Bk*n6tV(--n8qx|gB+nl6MxgH=aL|DuHjH+U>3Peo&+LPBavFd1|s z+o|3yrjhU8^MQS_N=QlGMcI{^7Oz$?OpJ`|@ax;0=6P_AYpTFuo`dvyTtsOBMG}lB!{3U zTmTB&k{XX1*w3xEO(Crz@Ey@$ft`a7KrlM4cl$Q^jjhDe?fa(@38G8&`Ev2_oQFn> z*5O|IaO+IP#Log+z<`vK{seA#srs$8wKC$2vDs9wlwyja*P@-5mzSBfwUnl2v}-d_ zg2x(h5cKcy^YK-1O{Q9M3qc2MV40O~*3H(Ro$&%9SnY9!WJ&7N-E)PnQ?j&yn++ zc2egu^P$c;PoI9uQupNxg;I(lRW6-GlQAIC!s1YjT&gm=b*Mx&$*<3Bq=h~4`#NOH zjVhZka>7|SPMz8b5&c2SNB%owct?_}tH)6h)#P*}S-j1s+{bX3KwWx#=|yZ$Lna}; z`O+O88TkY=gH3~pXc^MxsP#v9h)->85sQL{4QK|Xd(U7cZ~Is~m3br>y8 zllir!#UnK}wKfa{%jV`?_DPh5goZxezW4a)%K9kbP#bqLuDcz% zRQK=Sm(7GE3+NwPLi3*vQIssk#g$n#hLe2``kZ81(&#pF@{gGL-W~V!^fm*mp?4n; zb6z=VSw5VB@xEQ1Lhgi#iAim==ySm}bc2n`pZu1>7Bup$yjc8{7x3WC_Nz;08d=}d z(a}K~{?I-5y{(P=%HXr8C|?}AZ8t81f!m&lLPHOHafYZQeJTnPv0&2SV2*O(Jooo4 z**BPi^EAA?w6}8zG)p77?Qdt5A!lP_Q_nSXv%6qN0u~9VrC}ge_-#dNYpBifKWHF6 zioT9$AcrlNFmN)P27FdQ zkIwm!$z^3q%Y`0>MdH;c))_lm4)qc|_jSO?1S7>)V0$9YEBotX#4GW)1ZvmQ(>uh& zvllygnwM7+&vi>r?-4l->kEhkNf7v0l~P`gf4j6D8ks+km5BZ9whYY=5;tzp$tx%X zL_~N$d9w4@uU}_XRA?_;xR8WKSNr9Qwuy-^%!;$j0Z9dp9}k^4vGrPvSUFh8B!qI# z^{%WeUNjjAd{2IU{z;W|2I70PwcQ}3!~!S}b42ZCK4EETiOEfd=_4s4LvHG5Z!ZL- zbHwu4*35x{fx|*VbO6xj@7_JNXV0Fe0Re7!BP3Thw+(2H#Lt4U6bsOkr1>E~BK0;l zMOgCU#Up%t`=+L*Y}eOBL7yLuj@~siG&~C~W^Zrb(AxUAs7NdY(gF71#RXqF;%Rt! z4aZBKu^v9$Q{%8)?n5hm`SSS-7svoXU%Yy?b#FRU@;!10Q!#wsc*j@@%lUs$juR+o#5 zOZw{7HH*&3kPtF2$&DHs8U!$hSA)}h)|c+gEnQuOQDyJrA8WpRDTg8!rgP@ZnV!DB zP3*6GE$`%F-&Eh++Hkur@-zMO@Nh5vnh@=|;bvyV3q`>ot&j_PFoJE@Rs;zei!Z>| zoCCxI8%??%yU_?j1+jFP4yR9_zHaj)fvnQp)5qt$l@)KaxC;TR9Tz4y5bUq6&LbqG zCDc;L$;oN|{{1B#9V<0?QQ_eS=2G`r;xTNe`?u@p>P`Vetj}J?SG>Rvev_3Y86{+W zOJ6@>&^uUVA=(e)3c#&s)Y92`Ez~JpJ&*eoJG)%LeG}E2Hx-z+P$?Q2u|ifq!E+lJ z1zQp!O%u!x(Y^wx+NWc@yPHHwNjXK%dQNrRi6ln3GhyQEw`(Y^UAuP4KGfHr8}jsB z3iA#Dg#!bau4qnHcr4cUXm^|r=7y{}AmBz7W|#EYSt~cTMG?C(yp(>$Xj}FUC>whU z33~A|?WCBB9f2hzHt(aQeT>(gsc`zRWEzVp*q77gd>*oHKz*OUE~qXg54P+GVo^|J zsO-UWBei|j(C{Sm8LTvmjWGDZo6Jl%AD3~68b0s_N)TvY5zkYcF z^~K%HxmRxV=8B`E2nLJ?wzL=UK<0JsDKIneXRO~RaC`WQuD-rkGU<5b83+&wd8-oi zxu~O1T|jySYqcKnz3k)1jW}3%qzBa_RaI3bz!Bz4vv(eOcrYJ7ej$Bm_e}>yIg8LYal8r8pNhDUh`6lf{ynr5H2C;>&%58({BgB zn}RVM&V}K@+46Aa;*7ra)oz_xSXij)5Q8+Pvzq4uz5Kz$hg1v< zPoNwStw&H$ZTvp(nKN=3nxa`I?fW33J$(0$XC_7bWj}T`Q1E)MF|9@9jMi0PYc!1LG zgYzUUBO{;7j?UBc`X((@8(2qM7#J9?=iK|LBYtuL91kq2ws@(L`~=;p(Q9mxO-X1w zT1$;(g;UCMOybUE*!1Ga;$z2;SI;@}@bJLtCkHl>g6F+iuu?G_r)~4*&E1g9!Mn9J zFC|}x+V}OX{$)6*RGY|lo&}}bk`ff81j<^1?%>_g3EBu0uS`(;hKB2y%rto#tid`E zO09k_3g7E0`jV9rA<0~dQHzmFy%qJWPe)?Fd4*lBGxG!T%)~PEtVU}aF6HQ>zzB&i zUbwPct(8&$2n_Gl``MMkYSNZyH<&JY`!?HUmGP%is0Z`Vy)11B}BO?K&3m}^drYO=Bdl(rR_wyP){q^t*LB_Gt z;avDyLlkR3J0^0bK|Q0bgF_#rA8r>H5Kux01ulpbcVUE-`$&@6?cu{s9UUE$HJrsK z=T=WX0#z<;Z>NWa9ZZ7$`%1*g^Eo zZr=fcT|h*Ys7I-!(RGOF+RJ~&2$cAZr@a_39U5LazFFJQa2r2Azif__ zrjr@Y#-LAtqlKj<)xm?lfGC`7igX7K#2VB`?}sQ4c(NI=HDTuN&wLsnlaK>_gM%Jm zN32mh7DQa1Ph8L~(k+Ewq}`Z!WpaML66aCxy;83CS0KRMjEsJO8^N8C2k|?lROKGf zJn}333MT>VRnpZH%9;aHEWoDOl74|pNJt1o<8Y(H zFLZ2ZNuQ853TvOoZ}4aRim>O;XBhpxd+-(~|NI&BwFGTM&235Ufj*~-jL@Hnu8an~ z&F=8!ckkQh@#f9xQyTfy6!d&$aEDIoRqd8rvW2*7x0MV)V=~=i8VwIm(Su^Lof)Js zt;1p$IkiL24!k@}&@%DR5C`;xN(iac_V=K;RoBI;{8u%8$z8TESf& z1#M^eOIr`1Q)62Zi; z#JlmXsjCZ7yNR_jJToN<-#<+AT1W(dtWUFO$BwzrOilG5Pf-i} z=CxGJ&CfqX&>tFV>LjZeJz&HgrW%lV3n0Ib#_v}0*y)qix4SJHYP8iNI_bSi6? zo7qO?H&vvit88L!;w_u}%nt@(yZ*!YI{e;onDTK&WKx%|Tp0i#DgXWJSCU@W(LLJ{ z7P-d3$M>gTFqej&hu@1+0ZR)Py@mEY z@$ueLpk>)%U7RcbxlbZK&Z26Mg&Xa35uGi*mVIsMzAh8h?drMz`|mz~W% zJs;U8P*+y=D95*~Op;1#%YgMnXOvA02uhR2@k(=s)~q`Uoi`B0dO6Nb19hMh`o^Wf zH7I3rE-Emf>Slik0>>0bx5i(j44?Az^Lx-d+S7BGCnr05uDBP%Pi2-rOqc6-q81ky zJ5YRiT)GvfopO?<4+qQSdF?%60j*Evx0n+ln8?oIc<<1>91D112^B!r8sFq4AIOT( z1XnSoh=@p&M!GBv6?G7)us;dl9v0cFaJ47jCnqG7e{h(;`r?Cbj#-aH=M4la@{lqL z9s+L|AltdWWF=f~7HIJ^$hrK$oC_N}yKm0EO`9Gv$G9LxkbeI0F7k<2Y43e3Fn`nW zljGJdP>ZD~CV!NYlsq}}%#xwf9C@g|FG!5Mo)F6cCTPz!KcbRtq!c`+f{jzOs7oRL z`t@sEWHG+P*I{WkIo~FU(o2m6!sbP1ICX zb*H7J>8)`N*2ie|uL&@5`4WJ5t6o5_Cn{{0|&PSJ7)a3q&gNRjAcc6M$ap1kRS z8lDeiP>1Af@)GE3xON}X6z_#M6z*b-nq!uxXsUdf-(}fixqkdg#L3`SM<-`zU+SKW z+mja41&t@Eph?Gl;CpJ8(^|BcQ}wJSzSZCG%$G>Pz~n^4VLavQGj%I%jm@pCX&?=O z-JCkfsF1e@zk9T86fzhA1x-7URrKj-LA3{QYDMSx0`b)-J>L(Qn(4S`0b-_$QC#); zGZp(hX6I>`b7*j$A%UJlXyB)Lcs>Dhm<`q*kW&#Rb8XGg`UDA$km6y$OMTH$?kKd| zi>X(b6eLF5k32A8XM?EMC0a~72jFhdIWPS_0q&qY=?Kr(5c`kFYg!YzQZ=+!ciyqs!r}DD$>E2oc*tnHqeI=+-abw){sNrL z$Xj-Wg@uGX+?k6#AkqvEVpNVFJ$ma`L#!-YH!^U0&U@^n%3?hH=8w3{(LE3^)w+#> zjs(kuJI9l{!Af(Tmia8(@kKovEMlCTl+Mo1wI<~5`uYo)13Yur-XWU$>DjT%4M;!0 zNZL_kqzFL^l=33qayJXu1#4g^5Cx-P_Px5La%Q_Yl^73;_V z)E}!^eAm#$2E67T6?G6k*WqDnPI>#4wdD!!dKK*NV@yF$RkoH14@8P zflHW`l`IhG+lIMYXimebc$QE;K_O`2^VMb!7Y;6nHdW4QrLlY@A?je%=-AAPn}Fxfq2g}W;@CklvxG?ye=a>Udmy>PYyzNE}3atnH92LJkV(2EPR?#DnRKC0452^aWu6u$Y z3f=_UzT(n^pRcaPoHlGYBpc2xHCFkJFwqc=ePcgoB)9djCBtL1%hDe|4nTs48`$EC z{MHM!x?Jm#kV9kmSC}vHfHn&YQ}Krcy#s-EVi8a+G)JU$Uu;C2orA+ng(4EGqV}`9 zW9hUb#hfDe6S31DY2!BH@6Ljzd3V&AGXNYUPZvVg3jQ%47aQw_$X>EY2DA4k$qN&m zAI^iAy+O?UTpR!C(T znX&?&1KrhdOO@*cZrdUldiu;6Dezz0zDEnu&n`mLArJsPzeT@v@Bjq&$Ix^LBNja@ zIZb09#FodfW*NnuPZ?>df&TUM_C7$}dEZZqf>w$Ar4DeI{-4{cIKr{WMCDoxc;6C) zYWVfN$<4%b@+m>kR*CwrixiC8b#`s`_gFQpvqrOUJk>HwAdP#m~zJ?4-P6>MK6KVJHzloT{pIHIoangPLSPU4)@)q z<&~B3C5-1D8&Wi zs8nT?m8VQ5Z$M1wwM{G#yA|&+xGK0iN4QV@^RB78tDE6UFQM zUakV#5NX;6Sy$HBf#@(8D^XR=8stzJZsF)*<5ORIfH$KPZ09>rmV?++!>emda%6Sx z9v*Qx6NPMVL#zlClsdQs@7?~>8g!d)Z*Y)11;Aqy!&`mWLN-9Hs$*7+6G>JiS5Z+3 z=PI~ACcjv69Kbug9aEIE?bQ6SEtTeBVopMcmmiW|2H97Acbh_C6n^XG=N-gggpSwm z+t}P(j(2#uOs2id+t*j0?i9J>_{6F0Fnv96;JC`81uZY6zgJT>%D0(d{P^k9fRRe@ zLQx~B1ezKiPvufkRh2aMv=_*P_0BaaXpWBp1NSnD*uHpANB+TXh71bbZmZqHIaoGg zM1NJL*Be2Q<59ayg$tep5(MIz<}=8x^-bi&_)gz1G9A zQI&|S3x7Rs9dJxcj1fnpc2k@CQ;12(;2h%PQ*J7R@AbIj;g8FKu+B@qe7Vxpw+gvS z2ie63LyHSjN1&d)X!-n{9H{>VIKhMY_}lvWvDmL%+o`x0cB;sg>_Lx=AKCP%waaDQ z7k2=dbAbPq23GC+-+`b{UyX#fBBYpf9g86ojg!Gc;hL45J)jZb8zgqjj&%C0lWdm) z1XW_jwfyxBjR3FjF2XJj?^Rv;6I3pwZ4GR(IlaHjkaQYF#vJ`jSW1kjwrxj3N^?U( zLLjuAQE>R=LGh{3Zbq--(c{NQxViUSiQv^XQfP+8>W&9KP2so}0=o&q*kjx?h{NcF z!+-pVuWxKdhCj-}acOot;c`LuU=(vCMtKi*BG+ZT=w#~oXU~#>UEbv6T!bh@fJ4O$ z&4ZwSZV)A{tgU0?;~&DFLnnq{eSk0u34jVY1K~HNbS37#zCPlNs~6m-h=_>TI8L*8 zgYcwGP5rS~an7qtgi8e};d-pZmS4le60E_@a2x=wFsMpVn8hpp2nqUOfDNj{{Qro< zZMHC}yjKS(Yy?5?+%WHa2`9_B&jFMkJ z3vy(pEf^jHuM+&hLi8HEFw7NqOoRwN6K}!`!+H_sAmT7Edna+b0c52QI7z^MHc6fB zGpuiVpqYzk69YdJ)}>`-%OGy`+xsCT5*ZoU4I>|06_0HKGkRE5v=*w?rvUE_<=fPx zc=Y)3UZ~~3!W@JRgqV?@zCMeF!=>4F(_${ICvXhhgM(?nSfSExf@%j?O#xU|hQ%CM z@?BO&a0%gj_W2i0#H%2^w18_f#Kx{nexf|h$LE2!ff4s#p|&I6dIwZ1fJvR`T7p;N z&W|`|*Jd?0xP+uf<-#<9y)aC-a64$kumFCtF{j$?Vt9%42)f24dYK+*IWz8&5n!kw!mim^Keb7Ne z1eXgDR;X4!)0u5d3wr6(aSsGy=?X_R!Xy`=of5R6DOH6MjrklJzFeM#{;!dd^VhCX zLf_J=dj<2?41O5#Sh2COFe(Gtx)8E#NK@nCHENO`SneGg^F@m(D=Vvdg2Fj~eD~|O z&*Py)cMlI&TRHRHDj|J6uC!<42q_hPDIOcXQ6*joy+GF+mR=}_h7RNDwEsq4(yxEO zoJO^g%O?jVYbXgq&jVdWqoQO=w@OEw0L+#eFLebQ_=P)KMD7>p2R9>}&$^S-yukTH zMQ}RV_4M=*Szpvdc?V}ySePePy9X~1Gdz;HAR!19!SgzLqoeadNC?-H<&WW^5$UB* zPEH2Llp;L8uEdO=d6pN)l_-3DeE}~wZr!@IDP4me_pH|5(uKhZ$2^8ZzcjGIfu;$m zY1!f)?ZJcW!?$j#VKkEgS0uKMv|GOZxRwQ#erm1Gu^!eD5^j{ib5f3M;CnC&ZI6LBONp>36;K*CgN zkLcH6KxbP0mJjDb@t~sjCC9yufAN9@m5+Nl4@1^(!zMCMRi)3*Vq)q=%zd9ffBvTY zsSb;fPy|a|NeKzM^hT8<;={U2oJe^j_SJv^;YJtriEGi1kiOU!OeG=x+rZS6(!s$2 zHs$%-ks#E#-sOh_u|xhMf(QFJHEZcxL2|Q9yELEDdH4SMwe1RAqvBUE{?KQycnzl# zi52f-enf!fB{dP%+Uh#b<+A2D$QL8-Qg`X-o=(0KS0avf_)Rsbpo$Y$IUJ=E~x^B7W)7E>4SE-|q2qr5o#V{b8L!R?Nzh+;j6O>$qTqmi4!NKX4gyduvqbvBz zzSo~oZTgFdHT}VrG$A2%Y;qnnakI?KOql_6+#V3Ok~4R{Nv6-w0lq0^g{~{Bclk@? zA#r9i5C7mPJu=KWx|O@ead`19($d|;)isC}pXbE?%+ITQ)m*y?E@W#NBVzX~rxV!4 zlAiBwH?$>Io-TA&K~q!HbSa;G7GuTk?ps0w0uEOh69LhysF8Ggqo$-%phM3B%%0l! zOrrK>>{>;U^K(4h+`Sy?xh2nAtE*+6ww^uszZ6vNABYEyJw}kC+5#E7o9XkZ+1Y1u z(B(NG2al_xdqtu-TXGyZa%3DXsLVtk4EHcgKEnprc65>X-;E~{EN&YZSmLHb53+Xk zN*S7~;&vjUqQRY2_(hg|Zf@sErj*xPn3RA{Fud#%l6+AKng|+qyGGGN3 z1LUEhp(=XqNbV01`t+;=q{BOjtq54j4P?0OmpFeuT(g~^K{r~l_Tj@qm?lZq$!(C% zZ0DyC;H3GGjvmkRVQuR!hK2DNU={WmJIq7%8#f|kj9#l`MAxb#v%We$gCqD~J@!(R z`{>wM@$;cdCYOE~=#@A}z6gpa<*tIgb0E%!J&RGVoJ9JIyO=*1Db)&?20YD~=6x4} z`$wBoX%)nfFZ~(-)J(3&1F4#vYS;ott!hD)^9-S7)U|leQ<$O4V^Tv zfv5_tv+w?p|1APu*pDOrW#!=E0O?#DOf$qTLWEU-xO0Hk^ZfK())oyC<}#^||z%H{v{;RIJIhco!FXTXb!e!dQ)&zj74zRGGwIbA5 zACZzr#Xm_^O#bFF4Qumi@*hFJKEx0!3dA9wb&2MzED@ZVc$LDT8#q%PxTBmKqT_8fgMapPT9Z)yJ+kiLd8XZ0)S$=;ujHIgU@@r(qjv=mJ(829Cuz%a` z45okqx)Y>y)EX{rILWTBUzcKPgcLU*L^g~YXA-SN-oh=q3`+AOG$+zx*oFQ)^_`m$ z*8aHJI`l@`8wLj&=QTuh>j}4GW^%H-EyuLJIbGvh|Nx6`z(3f*=(FP+dTm~hUOY8gYUL7NICvozD_P>O= z0|#Nt0b5+xs9{&neY$vIiphE5+|voQ5T8B-Vx;a_T3Gbn>nvok>BMOunl16DGd2q# z!-_@gzkmO>_(`o^$u7fot{NB` zVvCx9Vo^Jxf^KvVU&4A|6hQTpi0WIM37LWF+S+~qbGsSD`NrXBP>=TZ0_W!8QmzFW zHp6xMtt1u1R;o+@IQjta6RwXV2sU^Q=;nvT73XjGaDjvq8a)Dj4#)^2xGS6(3EVAn z<9hv5k+C&Y+9U zwCLTt$MM}&D)S9P7p{|CnavOSAjpG!TS1_k)9Ur|FDKAw23}_-m5!8alipy~@Iy1< zU}cp_5F~eh{Fuk7NNG`=r5YzJ%&4Kcc>sxIsn5rPWoU#{*scOrg{>DOJvq#wf~T?8 zZOZ{;srq>zqM==TutAAGE6jg$5Y0kslOJ!TeydOK6w1!Y8G<7oRJXXc>TnOqm0CO4 zv`JQ1{dDPHo(PuF-}M5_WB?(klOQCV7B^*OcQ*FNAv+ie@EFJGCQF!5P;YX9qMYp3 zz0QzSm0cpB$k_lI=FRM*rZ$7L6=+FcP+7p`#f4c`sP~AsYwCAq7d9hK`iBKSVbJX2SZ2*f}XiELtQq#hhEE z8^@88815Y7#I3K-ip9GFO2*Xp}o%Clf@ z6ZtWy+@F6YBH)7?P%w=i;K*`|RyH>7#ok*CJ=4dX9pZY0!d*fmhsaL^vKyM3g4q1Q z+lY&JR8(%bn&-$r2yAVUeaV}+m6nJM#_WW1NdMGS-^C~N{C+I&VG$Bs45nnibFp(h zj4*RJHHq~jaI@c-c8R%LMu|Dmv9PfGm8vTcxZQxVG2>9XYhr@i%l8Q(0Y2wrAoW9b zP3$Zzzr|e|5zGR(H(y(^TbXUVMxJea`!*TkRf*qGv{;d6{1|0Buq~gEb|9kV?!!wr zK*y-|??<45vhzDG>k(HN7%Ew!Xi31*k09Q2mq&z$_aJM8WcV?#(GxZtw6wGxMNS1( zGx?ag%&=d^?_b^%vYuI7EZ%72&x#};m(#WUyu9RoVRa3djYOucGZzKsbKTb{JR%|v zk`}ivBGEy0xOIW!>m%}B@dTJS5t1P|Ck!$IY`#?8O<6bMW#V3PKh=?%YLq6ygMsZ&L_6QvHFkO?ocQ>a=?uT}u<6U4mVf4OGj0P?5!N1F95}6td-wScd;^^ZZm!2G{= zXJS_zk+JR`9eskO?S&H+CScCIbLY;@pXXjr%xyq^=oSD3L7T^~Ef6^~LbyO#hJ}Z7 zi5g(3ScUyJh-vxgj6KH%Y}6ic&j_SF&a4jd!Qqo9w}Gw5PBBz!gJDzwkO>UspvIm? zMSY=$o~uRNEd^{lWHZx>DPLOsD751tE(qxWs33r24&mMu1o{(9&wl$l;0-Q> zW(X%2i3!l=y-7m2vf=_BNThLtj0k?kf3Jgxvl3bY)a)JzsH~!oRUUyH;Zmq=ABchn zoV?)0dDRdU=n85fj9Z`FG!4`f8M(vXMK?OCE>WpX7#t%^u&@8oyd-2^ySkE)A$H@x z8bE&spG{M5rBDk1F>vpu9DMc#+$0Xyq1d?-7g)A|K%O&xCX;}x#MJOoo}kQkMEE3K zL|PE%l!9Q4=vVuW8K91cYbS~HYQ#+Q2&Fk*?&utJA!Ze^!_S(p!}w?kaY2h4~Fh-p`kz@Q14wKmwG?D_7m6Hh!CM{*y(dYj^GrPP<(Csh_alR z@JC^%@D}4%94MVD4Bn}V3zCxEh@Z*~)z;PBW-L^Ced7$U%K?}UcvLpO_7CpIqV)?z#Q33+@vps6RarqqXO3hh>LDh6(4Z*7_9XAoqKj+ z5fRJ?MuQPkpW0fJ_Y+2H&**^B6d zY~a2N2%Y7W`NzV#j>OoE-B#R7MK>>l&S3;!vbMUjm zi{0dtsWC{EKHKQt!DljXBziHRatY4TvxB+38s5koivgKLRfs0|@Enb9@1XO5{(MeL zR_=9;DACi#EvGP%H-SZh^{u$U{e=R2$(42cVaYkf+fGB_BKkF~Q2Cn&VM10QRu;DO z3yE#`wKonOJu2Dbh-PjG41}mky|CR2Tt&l_dHKvMj;7p#^FYlU7h%vvSzm#wE}IEvd|j;*pHlVk_n;l-R3t(`$}B(# z0n&sqhg7m$RwQ_@wotkjOg4N(#u3$n$oI<9-c=*BoW#B5+xgm;agPL&lHzaI#O73$ znhy^o?%-;;CqU111?+5}>tBYRyDeIcwb6*LOg`M!yzQ~R#|)q%#LR1tj1)7V(;Zt9HK9223z*}$l_HB>o1V(ANb8*mO%p?)}$H$S> zWUUL^jOz)#Uv7hnO=QqI1rXQ8=R_%(upLT*qiu;6DS5yw-3V)}>*ut(l&x;^JS^<= z&;E4p;Fqcp^nLG?5E;eb>UWr=;aySgxI*L&K*AP$IRuu-L4@afeQy>y3eI@PrM$!n z^BB}^>*Or8xrab#^7M9RZ#JZur!O7DQS`(&M6oCK$Wl3I0IOYv>AzFLg!r7eKb27!yK*?~+mr0((E#)a*cBg2kc$)r5It zNJ=4T7CZaGnXP&fF6NZ49w-x{l(yF&)?bQZ_JpiRP9Wt1dcRn^VYEC-aR$s zB{14>$6!w^9ia`*#zkKyPE(K!aghq?Yg2W+;c(@<%Zwpv%{$1+H-89td)?MnV5XW- z-u9Sm*&y*q@!jn!r&Qm#^54VPexyCWSsRWEj@L{@^0G^z-se4pFgY-GHGynlmGSqXRSL!skcax{1pVE39QKcMnW_;N_~&U&{_X0DC5oAP`Jg8~eEG z)(;^~^%6wxP?tt9^p;vF3kV9hf<+EHXNX$`4)R4<@6>fvw6vAH;TOTc!?&Jhl|gt2 zHw@=HPH}NjLG|C46*2*Rf&v_1%NJa+u5}1Z0aXM3V>UckUJf0(r@#N@^nLVlzrO}@ za*Ftu%F3;TIOq#Ig-EfmRJ}X|NnmnrPCr6&5QdV)wcM%KNZE29EH=J#M;k9)7--8X z!5nZ41q&;w&-Y7hZ5bMflIA8BLCr#2H-MR%C*gvY#}%|h0%DM(sy%lfb^t+A4(muA zYs3!?CzCZaGSWdRlUY&HdoM0@-u?c@jYXL?IK=a_BuHs7K3}HJDzb)|pPv@s0BP(B z!cTz>v;V*WT)*8wd=L|MbN9i6uO~-RuR;QKm1JhwM;UTyWZU6syah^F1W$lzQ;)fz zehGJm*SO^gix`LicH*z?n5iR0oGIcu4)7?97;l`bPo15Na1JGKueE!8ocIhB?rb2n zE9&`H+cD1-Z-*-WAEMqnkm|qvA6L~rjOY5mO%X?Q+Q&pcC~(p^_irY) znW5-V%_)JObiDwz;G>U{aU$?x){ZnP0~6b1!(Bg^Fc1%;I{qRuBI1-2_Igp*IcDE| z4y{%v+cXSKR-TNFjkTKUtJ-1k!&~iqjN!0}QMstr!Gm-yqh%1sq2!Hv<9(_LNR-1i zt;Z-)ptlc~(fMk4#Z=%hk`cGP2OfH8Y~zZa>+4?+bMtFSl$N^#A31#C!n3aL#K(+6 z)mYfml$;%(OS7R3M0sfXUY=M3^B4~SUPXO&8?|zrGvJojM3C=-zi%0~%x?6}#RYTy zRU08Hiu2Bw@HVDfd4({~N7wWHydDB}K%3p;? zLaoHvX4@S|daco?_z!DSd@P zQ{u~)o;j8Qd9qf2$G_tg3z#t8{tbQsG5FDjeo*LQ#jO2Lw`)hKp?Wfs4R?W=is6jX z?%hlfM^>Xf7e|s9p&Ic|!OpP?Uu;R?_!Isa8*FXOI#G_c~N-YuMu7CZ`-#vW~}_*y5;&G zK3d_trG=3ZEc_vuKQ=e~hm}mzswyjcan~~re}QJI-mM}wCWZ}~PWsGi8{L7uRl!An ziU#4ydl7$rj<=pOVA2d-D(>w-p3Jg!>%Qn@ty;%L4}|b@0UAZ&=yWu71YZx9+_$d^ z2XRzgm3?!nCR*8>_vLO+ni!93A?@eUU-VSdI?wbUYHcp>$+mD*lX-k@O@-Z~}QkNtWS*fb7UYBr62%0R2$6n*0 z_4?%E;XwmcGx#{ap#Q{yyp36nlSMGNtzP z!bT>R)%hFwtL34d8dC%P{nuWN$EGLim0NGvZdY1IC;HK3u^Ly-4uk3QK;2n=`0+N0budtd;GJ57g-Ate8P!DO zW4I&RaWzPjB(qJF1NVN2|21#q`R5)m{j_*_usZ^Ce`Zej$mB134aR1`;rNd5`|wFh zP*_d>Qfus-oI;@X2)K)UsZh^no&ZI}ow{Vhg@4zhwniO#hw}$;=o=v~VUS)7ef1|K zuIQ+yt;!)SeWfe0KZ4@tHYFar8NJ|n^;d!Z6>VLR9P!U zJT&8Ae|~of%XjTFTHp!GbGSSV4SQ68kytZ}?j6K4XfdV^GWV(SA(BKx#GJU=hYT?Dv2?!EyAgZaHf`2Ex zT9PkH?jW6icA;X*y^7;Ydluidw;PM${F0G%`x>TRoqpfEk=)e~M!)x>0@?svZe~j@ zER;ig@OX;juAs@Y`@OTOIy&o7{D~e>?72M4!zF!I@U2PIjkv-uo#5{_qxXn#qe|G; zg`G4$H{4P>V=;4nr#dz4VFBr907LJr(sx~YiJ#tV9s*3i*Zn33Dl{>VZzlTRP;Bru zs4EeWoS~MDZdJUI|aowm%EkST}OodjqE?xUABf+shg(FNi4mjG{Tc3R!^`T z#Ai<~f!ycMNl*fA8RD%a;#9lFd%@^8cOdJKD>yDOaUDqXL|?YeLi+T$1c~AG!or+0 z?8LWAzr-O{jzB&H(FI^ZwCgi-HV?W!^)0ueaZt1sXzuOt;`pz%KW$DpOg$CGpAgt% zMCvej0`AXvS*mkCG{lvt%y^ z1qa`WsiP38t-V+-zrx!(Qy}OUl8Wh>9sOI|}ukaySmP9UPF)-}P+4~^EMKD`Nv zy9i|@2<1{(X%DUie$FJ9E{K^qeT>cNNQ^+n&LHvq?TBo6w6GS}nPKMF0RZ15u&R#Z zT+t~m1!(Te9T^LsrklMu8vs>Pqz#FF#S`>f@IxuO>)jtARz{%M(XGxM?{yoK))fZv zxIf5GV|Yy}d}InS^b2;o?n61oMAWHbA^MM=Fb;M#LrEC3o_|T8t?;41K-VeNuSM(W zphhHg0cUO#59RK$6xPRxS*ZQ3h_}RXCP#eG^{eBfs`*ysQ{v>Jy3h|R`EdQ(b`S|u zK;F(TmYU?)ASO45$~m|dYGEu&1p^wQZAJ$6S8hDlRS?eF4m|kduq0Lr9k_WniLk-Lr^hoR5WhJ7O#r?`_auRoXvM0EQD z%2P)7c5wk-ctR@SORK=}@Ti)N#gopCDo#tSW_XSN;gA$YP}pk-TIl<6D(>uDw_b~P z3P26Rc{c|TjVpk!uu`!y-&oJrnEACI-^k& zyU(3Jt;_bIsJQrTbK#1)uAEfpEpn+9m$hEL2lJ5vPp8AS6KjIgT8u4* z=$A;q(wZMqYXDY1!o36{hhCtA{?0{$XIC8@z3B=cQGV!=`Nf>)&s9LVwJN?yL;1Mt zlgV!zh;99OB(T2-8m(82a4uB?gD9(ngsK&Aqs)m5HE=Lq0qPcr?f;niz^yEmW|X1N z00EG|w!JdUMQJ2w7c3_K5mBHke3!G4)<^8qD7opbV6{XlZ2;p=4_rKJy45)9X%O9C zAMmoMqxw1t@N6+AwHeV*5LiZwGcd9ePJQ22l?;PElnwX_@-NSRE-CCSyd^Lk zGYaqIo%|#BaFz$M3MESjK&c60;EvGFdA!L75P#)T`Dc7O@%%N1t8pV7Ml$)nt%ogO zCsBu@lD;1rp8HM1f)8(hKw}7DhT)%%yQl!S;hfvW!M<(VQqnuM*eU!!cHgDHp3&lH zbyb1C*wzWoB4dELtL7bmfX|;lOW2<3AQ=@P&LV9FyDs==oW~MDQMrAIe&xzOm>my- zW5lUd)9$}ygwvLI*kM)Qp|sN*XZ6d$+Q?OSs^px8v0nIMwdP~kivLAi$+@I9owuvx zSOI@WC=MHv`bBKGAn~su+~%~qHo!*W6b5caw7{L*Gw7YPq6EZ75zD*@!oKx@tEe2} z%khbhUt+ls2>apn>(}q2P7<^zl0q`AV1a3osIEL+8B|r-^S(HXsTrY6S2!tDaXSN~ zzv|pIU~}!O#%uJR9@s=p@enYo#<8Q>XdKT#p^hkExpoK{+$laF@m)_|w&pJvTKy9* zsxC#X+mdJcBnj$30L`muwS|IgbTGb(jCpCBx2pZQD`NIQL>iq=WM}o}BcMGQD6JOt zpP_s#kG+3?JC2kLck^HFFb3p`8m+v7wuJHXq=8lKqk&TJnC#?e zDZPBDeEBAEcYvMtK@Z)k5XyIfmuI^#doSMX8d}tz6CbSD1s6X-L8R#nIR&%*jtvi- zgn%5UF8^1=18mI9iS@NOjvjD_tZb~?fz2RY5!<>QI~Qe&s*6i*F9ocf|NM{Ppzy~h znT5CfRc@Hj$-#09@54R0Z)*zF2mb9MSnm*;fAFH7f8fS84#h4I@qJqn-xDKsZ2PSH zB0K(lfLD*}V)1CgdM55Zwk#|C)>9niSPU}_p{gWK?JPqa8jn z@al57EP|<=oYJGe{jn8ErVX=w#o7Sn2gElrQX*%IjhIO7ctGlF2R<&;p( zbksZw!ekBMLs23<`n9rvDqis(T79IY@&b55CB#x<|0n}LxEGy^Ns*h7cgV)M65oS? zG!e_ld-ptKz=eX=~J6rB4tv&1O0_nWx`^&);dYPQeok>OC~MGdtIB2ThNI+BK$2UtTvqFr zjiKOh435MPXWCUBjHRKSt(6hD&)Odt>~anaAF;vMVA_es(WBA4yXQGte7I~S575bf ztPJ@5IZbhudw=kVoMeR*D8XoMF;g=$8zA%&c2So=W-t?miBl3P(vDA`-bRI6Lo-E# z22(Sq>+hY*4|D}_@7~0bO@X}S+4JWu?pkL3asqdujd;`3vkfvT#AUDm$Y?8Fm7Yc7 zSrrs^?%!|z!I_iN?AVePe75~3&<;!x*pGzi#~;#GqJoVo+5QU`BMBAu{X1ivCB3WF z2z@3buv8*tMtv*)wtwQ0Yd%f7y$VMi(h7_k#K@tytN;iw9t?dym~GXvrbFKaMLgK8 z>iVjeGca;2JbhX(d&=H^Csq({%{M@3h}4+$7FbKfwn+*NYwKkOQyii@wGF5H`oL{Xrf_CdQ(@&h(lHH&&)pHm0SKmTP3l-VriGX^~Q%M z?nnm}3(3$U6-gJcL2&hZRlwk0)fZO?v?c!qT@uFl$j!9GI8|d)c`RZ@w6oGEMpL6^=2G}m_vbNT&xdr<}##b+)S8E%+Pf{M5SF-Bp=nPN-)z~Sc zcZ-V^kdtFTBbiBH!=k1@Du+izBumih>(?Upo7Hyz<*-kTS0F)Ukg@z!De6-yfyL525{0`60Z&;L_MDOjnkYUL@U#+VKgt0w~~5?`!B;b2)9_lMMcSaWMw9i*uhsaIlGgTxR9SBOUZKu5+o_GfIzy`-CV%h0H22KssvZSV^K}xd@ zM@R+AvhJC&U1JS~SIp0$tvgIYaq;U%??pU%)(Kiop>FQH`ih+ zN|Gf0e$QEAXJNSpjE_Wr;htoBFDtkbPY|HUBhqPLxszb67Ewhm4*s8 zOGY6^Vn(+ovX$GzQrGDbd91)Yj*k`CB#WFfei>;9s*QxrP`4@FV@*Prin@e?^XGz_ zn<^Nu-jR_tP&DYTdfoLD7ff!bruX@=i^u6lFU2=AaNobY#EQ{2&jbw_i++D@;b&oC zS<5ZGR_X80$U0e&Pw3e7$EF}=VW7Z%WyKmaUV2}|0TBGY$Bt}xhp134|3F~U6!8xr zyM3yyM+sdB;i=_FKxkf#?rcP4Bza*Z#0D=)*KsF9&PdTsG4c7Z<0f1~5a?uFFY?cKuDS!XW&IJWWOHDLgBw;~kGVS_&UV zxjBEfL`k`pLyQik&9164s0m0LPNXl$>LQU;C^bpO85F+!4MsjRsU)^-+xBuChsP-~ z;ghL}2{OnJO)la%3vHDb9h3v`ZfSob8pqn^F4=?KX#b9Y?NZp`0y zoPUPCI?xYUqy1bt|M%hU*8B}n9&W!pA>I!w*iC?+5AX$G5x@VTo%J^sztr((R)qQBU_m6GLLw@Zw0wS5x&-BoyKTa~`bQocKALLgg&QkxgdF3^aZPXBQ^@ z_jo%x@0{9U0rmtzRG3WL;V1hg|7h+!KhAdA)H=WKdRC@MZVfBMIptVJOb;An~w}L z*@zzl^0bk>x4B)}*|5BvrRWLN;UM0pxQJSxfkKihr>62B1XUGiZ&9}3Dbw|AQXKqy zHzp=c&whW7FS=R&SPDu|vqo+@@|}a_JAw9Xzz2qA_9UN0ff%^Vxjm2d}~D)4LiBzdAa9$-~W!Z`(2L!kItz@9!V-kEbW+ zZ1*cva}li%e9#Y?1*e=B4B~3-=1}Q@*!sk?`zH-&qoIL{?mqD(D+?((_D5S)#Mssv1%D990WGZ;MzJ+ zq{-uwH0vjh{EpzyWr#P&^f+nM=gZ;MgyzKtswJcc=9Rl06Hl9$s@s9nvym>ZaKC%d zH=!x4rB>7OaMs2+&KS(@$yit~B_mS}p31A`)Eb-dykutzZ&M`DCa;lKf+Xix?m(%BzyqiDQBcjy_481c)M&+q<&A{fEoZ~RuuM29sR z^<<3G-T4D<2UX5cGeL6E>Cq@u)FUhqG>L+fxd3-Zv`q6r+S@(@3S4RaSdUituJVcd z7i9_ov(JHc~A z@})r~-bWovLLi}75%-$3A`w)O#(tRVpj9?B=zN$WatKJfOsk^;2CDi;7t)Hm^@?hm@UQcKW|!Ab#gr?_wo!GmZ(1^OH630(b_v0^3B8dgh560 z*u=LoGj}6<_Bsi6!Htf8upB3{TD{5s!gGp8jn#%)b240IMk~kuxaw$Y^CjMqtZ@DH z&GgBMmpZofsDQ}16(>=5fMoK*hXEDTNW3_JYmz~Js=jWLfu250`Z3fE5~v^n1#?CK zWVsI*4Fbp(cj4qdIe|0KB2?f&B2X?mx3I9VD+rN+WCfywZK#C_HG zeM4P-tjC$D?P^X}PnKQ^(Uj;XaPY8}J_HCvcsZ*sEa%pfCR6*Mu}Nicw)y_PHdYw* z047awAZL%n$XKNRF#K&mJ$sv2u@QH`fcJ^v5D%WV%x}QT12$?}9m#BK?FIP8wno*D zX4{!^Z;TXbS^ZoNycK0|ABQdn83h99wwK@OM!BJZx&QI0dt{?tUcA&g>Iac)Hi^}DOx>G=b^kOsVJ-^Fjx=xFdP zQ5j|yKI%5^Z5`3)r={J(#i|DPGJU^bRqEKpi;3S#CfcC_q*eJcH_~vO;t*Nr( zi;l9WtX4eK*ZhqTF*Rae?(2I7fj=fNtbl*r;oSBgDDz1QJzW0Gio3n1wnX}%4Gw{* zrypn|(V(M>PoKIR38dBeTwhNaId*wdHMk1guu4iq1bFx&_3P+lhz4`9bWSzzAe&sdgpLeAW34UWd!Z&mo zsc^A|I1G(P>#hWK3jJpxlYD8QymFh@79% zT?&7>-~Qp!op_bi*rNn3y!7KfdUv8#gdj(sGZIA*`iC=a3y?IHw|~ZR7i90&lP};t zQvRW5^Byx+R5iyrf8@WBe_*5F&~#4`)jn}Q_xAUvI8XUFJ%ec!jQ+8#YEs-GAePxS zHR;iCBRWf|ns?@{rU_5S^DAHK20CrnB6|e{YjAbPi*wvqCRtcS1AAq6Th-bjnQ#+hXG-MDq1>5;14ad4w02+cgNCkH*Cd94E zXKcFKST$kuB-Dl~K1%b3t||4Vurg|DhDP@?%t?Hldh|@`pK*mJmSy)?|6pd*2B4bJ zB6rR|IO%vqd;@9f2ig8RoUXBN+_=5q3gZfy&;61`Oj_Ie1W!iU#^PjD7XG&43W&f*?q}WE)45P1nDHW^ zciR6B=ujK{TqF}zLw+%Z53GA5RZlot{Ud|PX=@$8#l*(b?&p_D36igF-G$SvVsF_(@|e`mdvK}( zwo?n)d*X!%J^;V9`tJ<%yQu}pCQTIi*=&RWRv}TemjgPX%D9a9=Uyen#c7UOE$xAk zz@MZ5@49Tfx|S@Ah(8HSCs2YAv2a0Qp{BeJUM=ZJAl|kC|4ssqQu{fJ(RwrsFhz~; z*MDH%ND>+V!wpdM6)k`Mm0PhOcjhdBlgY8{vd7dZ9J+Xk1SCha84Xxwcw*w;cd^L& zCSy7z>}dbqM)4A>9_%oR!LhAvS9^Wo;iQA28uomqRxDT&g|52wqM zldrgd;~QV<*Eu>I!AbcBsAF6K)cwU2hip61NY8`G>@wLLq?xuOT1$*Nni- zeTI^V)UhY#h5FMzi@`-9hSd3ESQ;WPC0g8|h z)wT;K`32Zs06aPFXPXf?>h#^bDwSAtaZlYSk^OOkm5~9aSw!a$KMt#)E*&Zjl9K>w z{K$b4$e~Xb2wa6m+{?>rJ1_5{%zntGUL!pK23CZ<%{MxV5Lk&P&IS?Yq`BW7#5rKqc)Av(nByScy zf}Q={*M_TLJ66GF4x0RTW|^^YG*}E$f6&o^eK(q4g!CrbHstVHtbAq>jr+($zYgdt zkZlhcWq>xG7k&aii{onosMJbOF8K{AS`f1sWy<&%*3RR(+mj!$G_s*14e2FUs^TWA;YtNZ!$aeJ_UV zf1Uu34um~*+BXB=fXp|c7!_87KXk?|3$DlLiEgom$jc)-Iy98-8aY5oB4oMKvOy4q zV&f883q|N=suI$1NOTs?wz{yyJeMC^B1=!VJ>HB0m&5&mM!dbDB&pe_c7k^3z{TRkPPbcy=+Gg=$Z~uCM+68nS;GJ*hLl)AaO5y$4o*S9M~Kzi2@lD- zxDii!%An@=iT!8quf!!xDE%um* z7~@@$wj1ENCU*^3vyG%##9Feg(UC8757F!)xj7_>23U5Ds~oV73M91ebq1SFF-C^0 z{<6uQ;&Mk~aY>bngJUHboQqlTLy`wVVxs^!8*<(OzCr@vfOAOLs!z~~*y~B4KC?Sp z@Nb<`R-OZ`_wQP2w%IL5#4JF3S_>}to6%_}T3KuJpsOY}6S-3SRPrRyh+?z?zqOsV z2)tA#WxfaGN|CxpM&AK~dmZ#>Efq_?*KSjhSxI$b(ApLVq%@qdQjCi$cn22jH3Y2tgF#sa`mVgdO9- zzIvFSuiv;)PPoUZI$(gR4LV#nvUi@ZGkT=Uiz!!I0Hdp-j^uC9E)$H_Lge)}l%BeO zasbd?LqavtupF}ctqITr3KG~S*{Oz}Ez%a3kcNacbTn{tFhZ`>q3ai&yb)kZLb#w`NN*AZklp+fjFHkR4c&%`QtaI{n7yGDJiJP9?^ zcP>Odg}V4AM0!Vx!jhP}tB7U1ypf&m8H_df$RwGp*5ymPu^GtO&F0(h+`TJ&T>7`T zXp1?RCH&;Wfh5kNvpW6T>fOKmPpcRZJeE^}9<<)F$-?5}sOF%$A+}zSSXm00C?uJ& zxQrd2um0uUniyhP>JvA{c*T9@01TChV@y{d5eWh8nQ1-{_J2);HF8$`tKqIthEcwb z1Kyb6?9g?~W+rBFVK{i+k)p@pql`Un;E~aT3~8L$>C^J57rwl~K)*;}+n`_Hc|?T-uWgQa0b@h$p&GpH>`mCmP? zT_3mf5%P$Pc<(Mc>0KIiw;I~dwS5Ofnb~IY203J#y{jRZv9qzMFUI5Y z&*-e)OAvs1kVLJDPjiq*#)>w83>95Qhlm5R_wmt5xID=-Rj=-TX1xNVbA!M~+>Ud4 zs^V?ABB|#Sb}+8lc~((#6ESt;o)skl&Gy9l)w}#EF12vRE0DS|P>S3}l*c0+Z-XFP zL1b(U&QWU2Hyv;>;?%B}@dHxlggX7ve#HE~Jj5!g|M>?US!B@`j+M#T?FJAAlCj%) ziVb+DB=-t|#g^Bf{7eEFnZa}pumzbY3t{@(u;^d-pTmK>^^)lc8vc6@K@GTl2{e20 zCz<_wM1BYxnVtfmSMSAH)8;8bAk-*)cnjjzSjun;K#GjSMjODIbXPz?eSy2u&*IY> zci%rTIF-otJ}sw6(Z>+@SBb|~Z1?I}J-4u>^-w_j>~MmTpD)T=C=yy$p%H0!XQWf? zdC3HcPu1_aIS$oj&%$u_S5{Y#$*-d$x?K%tRP1n9rg<#6J3AlxcjVvXj6i(0HIj_y zdX^SLvyX5@fAjtfxjhu>jS4s;huV+x*(LQwS~kR=os3S!pQ1EZ)!)gUFD z3cJJ258c;Yi&2r0QI-DAci9}qb_445!+padQUfxC^dyEfVj>5M@83_n8CeT!gRx(b z(8kYUU(a9)0PbpG;k=ArQbfd#f@idiMXIQ-DY!QMosrS>8sb*l8V#lF3=)lo&@>oB zvO=Td;>ZmJQG8HX+#*yboDkw@<`6NyEVna;c#%Q!sV3lDQ9Cxd5@;3t!48hYdwRXW z_hhgXbR@3X%*dd1M|2N|{n_D|Lc<)Js`rS&0cg7(KsF8Kq&P~?e0Bq0G{wMUqXaZ} zsukV~zm)U6M~`tru<=m07v)j|Rb1c>aPH}@-*iXmh7^Mdb|KE(FYP7{Q8&&Pb!sceAC-t*0PLb!B}zvYXE2*Z z=ci9hw1I(vNgI!S@B@=Ty#n9A^0?+|nWX7@ae0wg4F39tIlUk$?3+ zVrEbT2qepQgU`6#uIiyfMe6fgC5P6(MqO{_z9S1`%ZLEmM!gx~pu!{>oMU)+cohqa zw^PeV|GqW=(VA+?L??W1x$Dy6<&Q(WZhNq>NSQ74i-_$oNuZMR%mmSQYH97La>xze zxcMQ+EPiYIyE0r^M=$80!SW|sjC}_r>Slv;5>Mnd;!L>#IJFmb0LZ5@v&1IMqxJN) zd~`KeZVW)csT$QEIYR9Z{0@6J;LJ(=v0X@GDuI)tElPB-c=inaK>x{*K~4#qn`!t5 zNNp?R0acWIcb>}HLfeqqjVQYlx9qOA`$ZM+S5H(D(Y=2KrA?qc78wyS;w1~4sS@OqA!-xF_5IK zmvRvqeaPCgfk)mT!b!xkLT$V+rG)0o!ZpquVx_{b!wE1Ucg185%~T6 zgKO%P)+eTstWZMB1&1^$dPXUrWLUmpg|(fX`bBLFimo)}RI0o5spE5d)I<^vJZz!5 zuy;yRvyDp-5XV|w?L#>%W1N5F-#4NE9;LcBF()R@Njl_}AKi(9jJ+ zqC!Gz$VeV(&P_l+B3SLuoy%(5ah?~zIMGkl#s0^XPntyOl#{q^AX&BZdU_3eQj(Kv z+RxWdV!yk6eZLHKL9BwO=)5z?x+t;T{rX5DD31k{THfHQPsZA0tTs-xS$E}E!ZM-@ z%jypVOcI>OnNZXiCr%qsw)pct(|B+B55t&C2>ggB&4vn>3=rd#h%j=BrAW|6?a12; zK$@@qx_AsXu7}7zK^_;w2R|n$ya&fTf<%G!^#@Ff=2r#*_?++BMG+b)#a`ZGGzpG()!ByJawh zkA{}jkOr|$G6)9=+sf>mR`3+O90ZI=WVNy=bW!^y9%qM_e;e3!gw0WH?e~yw2h#v1 zN?;}PaU32w)nI^mCFQ71G;?t6-I3+)Z$~ghc`VvjZbN&sy4hnG@T|iYdRSGpMlr24 z_vK6WZ+Y-}{d(v46R(n^uuakuBUS}ke*A`}6b8(6TEswtEh=gLxHc%|M zoL0h6s2Moys31S8zO`shp%^I_LOR{=G=9#@9Y#&bcKU7pGA3wZ`%!9>c|-pn2ONiV zDct93fr$H%nkyXY601J78br5tNVLrg5t_-k3lvuRKxPN?xNb=-#YRV~b^07(Y(4sS zpi_1T*KcY9FjB&3{QtX~1+$t_nyjH=tN=HZis?$IjCUQ_b+kB=1cE-}W}$&h{jWUD}AxdLBsBW_rbMn@%QeLg|%~Ce~nw>ofvN{$5qTqC8q##Licf9 z`&))0@&PIYe`k0tWqyZ5>pON8hzo@@?`hJ-EXi=Ue$(-)eyxWQt*<0y=3(=sr$9kd z_IoKCEazknZv1O7Ty%PK?x^$Z0Ke`2;?44^}+X%-M(-8@TG!Kc)O zT>h~l%1WV--&;x%Y`}a*rz7^BBm{%jgd;6R4=~{p>>e*YmE(LRN(UQipAp zme}-+w6BjNHBqh5QywX7bQlBama3!DdEZU)MSed2=CmM0Jl|{8yV0a~l5*7J_y+?M zlh`L}KMVCRPKLy5aipJldGRREelOh*Q?Wy!|HM4U&0Q8i>gI7Z!qqD_gtrGPdZ~T7mukm%qa*y%t6!e`gX{#>?%EW-+X&rS|V%SLk_ypT48U!Pebt6M&9jiIqxZ z!$@YEoWm8_BCMoBN?X|BGYJs_TV}Y>&hGcA{SSHF13tWTd<@6E%8Q)q(6TGrHVu%$ zejV7{N{dPmZh?!BSo}`XMBup!{vpK*%y{F1_B`?O4m50Zk%vUfyI&azQ>KhB$!Ium zIIC%wGnLkG~La(=tH-8OYTVq zP8=Ed7}+7DOH@%$!hE;zp;jUU{xyFa=K>L_b6~EH=pV$@mo15M9LKptTAP0HpYw{F zDfJhGqP5^~2n@IOlS$O7+v1l6EkAj7W!3j8YyujV>s1M$qw;y*=}&St+za;4PY2gw|fN7sd9 zdbEe(ygRKyCi;s5;NkM@BSVd?v@c%#?Z>9W#atKSh82q=#WHG*WFe!$?DtRPa^W!_ zOn8>^nbqFy_b)ETPTs^Oa(}T+=&>~ioI$2TZb-FMB+}Aw^CL;{8fy7|G5~HvwS#x8A7gkdb=~uE0#q2RD~Gz)Svm4fEe_M>m5|z^(UI zA|~wh>w}0}Sxv*|B!l+=;?H0A2csK%v4Qn?bfmJ_uA$@ z=XNQAI4Vcg_n9OcNu2ue5qA=*p-bfjxIrD=eCk|5o~!HX!kE}zi8>6i47)hmlhv5? zH%+|6V_8l6I;v>s@eVWH_GJ!xGysh6K9DP8`}ifpS~YV;>PHnu7n4P2t~&9hg4RPl<4XvgHl4nZ1BI02-# z>X%@zWS1>Io+-csB-&N_ey~^@F~MWTtI*==as~p}mluF#;LH_wYW;DsFwk<~;QV53 zeSK7x7-pBpmt5KYk`q%Rd;J4Y)-M{KC0XW#qwm)*rgF2??N~+GOSiIh>_szbyDau^ zHJV9JGXT=>cq^+6wM-Bigh(5Vidwa6S2_%FKx1R2&M=RdKnMImlYONe%!i42&Rgk3 zEK9c_#5Wv^N*jjq65Rq6Vsqog6MPL{m-Jv*#j0xyHZ5)AoSPtL5?VLMFixJCE*EfF z=Feh|M2VP2uvWKwxbeulZLj+K>(hB=`{^aXRce7LXGJpK^&4fMT=!5vqlsfQ;q;)bax0hlH2Im9!0NcSc$XtVuVu7lS0MJ+R%Oxzf5@4S^8C zIQEQi&=KgL11=HKw>Cq-BrY6gT%&ukAC;zG{@dUVaBLMpy0(3TgKDG6{KkjdPy^Pz z&&LKb2Nnk`GExBs=HZI!#gd8$rQAjk%9p{xhY|vN_I%H_`Tk!aOMQvq0C*H?Z<};6 z8&g^AW>MiyUd-?%!F-VZ^Un1HVjgpAQ!Y%qI6V+B;Ej^wguTU+MT9*Q2NCOnHl3p9 zW;i2qt-2tM&>W7&g$>W4I-<&ij8zN(THzYF$@&KjGuUW$w3*EI{NK>X0_J28`Tzvs zmyHKtEQm}D#KwE7N?Uc3Mn!bn4M6QQAu6@Jfann528kH1Si8#dQ&VA4Q3PWq#tj5w zz@NswMjRa^th~GcS4eqVn_-GLDxd41U)Iowi8f~J16BtakLK@;QbrB-yZo)kk|qqr zX=@wN=H?(yO8*-|Pxu;ca>nBZx(|TH-i7<}dy$M`9LPnMq=1J!H1-&QkoXS9JF5t8)mlbDxjy^Z1E95`tnHb`%k9A&- zDxy22)9Qcfs6xRa1_GoOK#E2b7b)UywGa@B2`DO_Br7U6OcdD(DE?wZZUOosL!EN_ zmn`6z& z@n&=ME&iy;j>xZUX~4bT1amvd|5@MwL9WOCeRi~s2_I)O6|nYtGE}XJ_AVHB#T9^G zt7&>{mT>b`)i;Oq?^H%@CwGiRC40izuf#c(;c(3<42{NdqIZH!w zcEi$<^+Q4m5hG&adY2uC(8i=To>VcyuS4Ll3_-vCN*MC|-o41-f%$RG%kQ2T2#aHC zDjLQk^6RS**`UcCgB`RMGX2!x0DOpN{})rlM8jk_PSn0T2OS;}8#mg#FqE*<>ZhaK53``9~j|#N-bmF!upeh=H z@lf89i8RjA+U*Ee*9v?aJZyhg0z;=j>1gDjRJ`M+Qbk@&tk~6miIL?$^b8-x&*5M^ zIz16j8b0ZuQLz5_M5!}gzkRX;#qGS{{YO-aCp6tb*j;&BLoq6L z12JB8Kt-a{cUBSf7E8heu?7>U^N1n=QpNlKL)F$g@N&49-$=knrrTIPjI{3^IV+%G zbl6q~b{eBg(yRy#ga`F2^v0Q+B&xxmNgwjLl*k>o$$$yypZrOBQ{>sJjo9?~s_QgE z{_X=O$4m`(@mzw011U4t+>R$?G}34{^WGn;YoEggf|&Ko`ezc{(8gKSqj3|%ur5u@ zc%%e`E4&!Z!Cffj)Ww0Vx>Jc(SxJvz`Q*>7=>A?qny;CIS$7~gn9qIdB1CX%0WS6< z37X^Nhcx^50aau{031>GtToki1f`j3lMSmQ5iCaxk_e8jV$Wl_{oE@6vLa^Sh^_X2 zL(R&()W+wm@kVZ@elwP$wCaFIWiAmI?>eZb2{)tv4f{)t^Eu=d{^GE@ve=5yVy9A0HX@$VA>Vn$+gC)q zC+oPo>u`O)yyGb6IwAMLe7L?azpMyvwY0nNAX|Q zV1};>pnJ_6yxzz`-v)e`9K_n`pCwaoa7zS8{{9Bg!(SXLJz8-SihL3F-jBQlKjOR& zxe*-ok*t}a46pG>Rq!Dh`fu@!&Ly*M~ z@Oy+?UKh0Y_0)*#W>OrB-43nH4dzslaA?>fVIK9`R=sL7H zqj{@kA&19`N7L9e$AK#A2GX3YNG!cLesXZN9>2W&-Qp!?y&}3$q_T;np?QZ0rjSF3 zldta5z1-9OBfIKm3?N$v7$j6XhdZ!6s4)*`J_UGpY6s%>*C6}SA+!mB=3w#7#dIOyzY+KCYX~KvFXyX5vB-|r?*F`tDYa>ASYmkkQ*a>?%jWg(~BRsDx z#b6q=e)y(A1?u19pmm5KTmKs(v-#wznbxi2@7XpD4IYdzd0g3W{1Wwq&@XJj3b^+3 zxF#GCu&yO~$^)aavOZbj7^0`RxhIVV;jtZhpu2jJn9MNqqX6b(BI~6bGvh7t_NC?E9CI7fwW>Z z92%zbL#3By*MswHyLiZ&NUteyw5GIi+#UV=N1JkfkA7QR*rvoS2j?%>M&= zsPSlB@|v_HP|bXEp38}?to>`(!Dw{O#0U7x+usjHUXqoqk@yKuKW|hD|GESueJ8{S zf`yBVcdyPqRqTN4U~%OZ;nyLTD+$`QHcDc8b_ban5VePWX0b#U&IXJzN=(u^$|eYI z_CAmRspDk`6XQ)94yfwxCPAgC9Z0?)(>S4CiIC0os{>z-i6P9Omv*h`Cna za94o0rs0QZ4r|+R9=IrlB9)H=P1IeIEJ$Ebjyv#(qIl^AWtbccUh#~})D4Kv3Ri2? zK)PFN(FLJA6?%r-5>Ojl%g3&XU{j30dzS>pvYk6yclj|+JMuY`gKIe?bwGS66)eZpS#{dCbTzRR*ZHX zKmtcvwP$wl8TG)VejEVT-1E+ta~=z7CshcWuH4)Z|St z`J0#dCbC)o^Y-yBZAcL}dbRM(bU-r5KbK$*7Pb+(PW!uu&nyxMpSU;UP^1Vwzdk!8}I76>$q&Z2{-jZr(4sWlb@14RL`CxE9Sz38@EDFYoC zBQmZIq!|C+xgt=WB#8rPq7{PCle=r2z%gf3Y^5WLTUl1_9&Kn%3yOY#NmO6*QW9O8@ih-N)0`7N*QWR;7#P zE11a>8n*y^b7EIR@YQEyN~L*fl>tc@#6Hu=0U`+f!>y#GBqIiUTsVh`h2T%U-BJ|t zW1t$d#`54$^pV9XxC!XuU&J5O-snT0yP@>_4xRfR=xsl<{*P$YRp zGHk2lk9f*%uxUs%JGjVA!j90c+`_?OgBm-T&5s0L5^pyiv@W;|IK+V!Zb;@?3c|q^ z;W@Mwr5OIS`sm!xJ-Fi4fZBNL#jhme_uBe#iy!)2P-lXuuk!h;Xc>s*4!mupG?u!) zIf_%9p<*zk`XJT$yE7nBBxeT!8=&CD^iVUAOy61kp%ssu#NF$E!#{+c7mQs!6zf}8Az*by-2Vp!_uU| zR9!)hc+?d+%Fj67p}`nCDkU}Zu;VlEc-ACn6!BUgfZs)6N2JlP`O>f6@)h{Q%K>q~ zi(iSpx#orsZ3ql1tY-p5;{?!qVZv{z-v-vwiy8XzaSQ^3cdq=xiDD|?q^zP(+F%I9M zrV)QcTmZ%Bs(*qBa-9!jL6FsfVC3oc!fM>us@;M=@r#&4s{*p<8CtY_=|_+gwFkX> z#X;#K=d3!F<0{cl112^p^^t=XCV#OWV00zuNHWxughPCv2?Co717jxN7&9WE7*YPa zEWlIU`{m13gho5&%T=J}AmkSAE%U74cNmKyex{i(xZ1ECCou!%XJOn1T=I6OrF!)L z5DZSRn=+VN!7>8>=ih6kHjs9%6#_P`Q_u#+e}{tB#HAUjn zQ%D*_i@)W1jb^0x6^%U&a&0^ygWIgE`qws}$wPpJ1WtN=xe+muuK*o#pyfgz`RB}#5BWbdKzCAx;VeN+EjyRKXI(fm@@T7Hl zBmg(B#ra_t;iu_7I3UvurqDL$PYB zahMAGv<>12sm3<%FZt1s`My6!VArl)0E9QEC%9-Kw0--7%jEAI+drkce|{j+xlSlu z61C8x%SAmQ23cn(ay! zF8K*qcLE7ZR?T=0vfuMseqChFfYq(kpXGbf)6(Cg5=k3?33T<|{@WU`>mCQn1hQ;X z>R(hNiWCFP$I4 zXq{jbAK%+Ng~%H^3=oOAD70iGExr$*)#Jv@<(W3)YVPwToA42pGroiK*o;0j1PAN3 zXORIs7r#Cb_g$Ei{ZTJTJaua(UIN9RYs>cCj9sFU;L&-;xj}AN6@_JgEG0zf2bVXf zcX9MU910$1sa*Snzl=>Ud33wCSHZUzDG{!l{IqcBt^`vJvuSuL&e%1Uk%l*qA3Ly* z?3RL`%|}@7eLVw)r|ISSp1Cg@{5XaaJx?ZF8ZUHyvu0P+Z}W+s%UIPg&HAI5(kTIj zMNX|77mD@ZQDhO&zKy%Ja)a;WH8`dW6E2Qs{99hP*7Fct2tx;rhnyLim?$U-F>~fC zSRPgKX1}b(?*=C=4D9+dy>IKv}p7(*|C5}C@;@>ViTS(`|D9M*B69fgI5qcxy4@`I zUNdM#CMNPIEl!29m~lFzYHz~W>Ho*xdk00CZr!8JIO?dQjsX)Q1`x>xR8WFrLO?)~ zs01;9fD%P=Fk=EFiYOQeB1r@!2L(k%M2V6SR0Jf4Cih*tN9WV;oVtJ9s#~|}){i=8 zW<=|IvXAj0 z86zF(Yq0wkNLn31e;k>+uMV*eAQF-N`E#AQeywFbH~weKn^|A%#2Tqru{*T#^+0P> z+)Amyv8=&Da~Gekb7#}7J5rlpM8#$8KYghfLi^@J$aDCFYQdkZ1H7c6<5x(KMB;bP zAol{sYmHGXM&b&onCiY>fJi(HE-)UYS+oX#)kNx?dJ8j`n8Fan36H+gv3plC`woGA_ioO}^yu_*NsnvXjChU$b z{ZabQ!vgefcF9nD!P&M0gZLKPf4WXl?Ex}9ERFR~j#th`l6@5sYU$mJ?wAy}2Gb4( zVSOs_b2R5Z^})arvF=4Cvo5Gh1{hgHTO^u3Gr~GB%_%I@6(|f_LeU<};{`y-Y?n(X z=~s*+Za>kiKV57CDKM+|c4uCv3p4#36I`MKlrz5NS;ARx`sdz9c-f2g2GBXKVc9-M z%0%(ls*MDoM1tX@RI#uFzTa9(mwTNH`L0D*l`?A_f zBj;eu(IwC={8C@V8w*aC>)-ZVk+t}b5@>M}-yY@C1o^$#Nf@+#6${RPR2m*N8~8%k z-u-+0RUg>re4H80gS{avogQtZ+e9$Dhmq+e`U2q*?*Qq294W&FFai))EQK*MAx`tk z7`C$UnF|W1M%t6}fu$QyPhPUB!UZPsODH6vx@Mpc&TU8CoK6UMZxJm+BwO1-1}es`!StCi zB-akK#3^L8+U&yTI|Q28^39rjwbF`BOKa_#t~shRYCwNm#Z{v|J<~bGOW>FyHD5U8n4SOxrCLn6J~hIdiFvGr#lFk z`dp63c`kK%#eegiq~T`yxie)KBZyT8#CdyRd$Oa{{#OZj!zoH$ntJG2?+$}mfcD(6 z_i{YXlPdHMd|`x*Ro=b0WD#m}ubR7#RHIE#qE-6=iu?EuJSQ)tnKg4@&tdNMXwv05~ zyCQm-9twKB>&J4`(256AyBnI51%D>{^)V+vepxjVKI%1yX~8eFXpLafsBw|NOmR50 zTrybWBYbB+W41E|GKlF-NP-ML!ES(~35NhTT@>=0eZmlm!RYu~STeH$TSv)-&TExI22$!%u$L$NO}~; zmBn;YEaEhl7QKFbnT`#Rf+JR)LGI{7na3I}V)?e!Bx5UjH-EW=#%i~JJ1D_$#uSe3 zFG1!jOA#fq{BB)1`>IS+pPTSdVALNjNmIL!Li^0Qs?ZGp{2V=Xs68-W2*y!M)2Lrs z^nlzi3krnn>k{!{yd6_7-}oyL(6Jl6Wgr-te$uJj=A3P{z*>sY<6<#SHU zB59^?r5TPtM_tC^?$2j$V}m{~avkr@ta7F23vJMf^S#;=Fvj$Ihv5Q?^mu$AK*vfx zW1z~EeayFOg1cP%$kZIQ4|)3IJppJ5x=oemK^@MEH9+R5Y1^90q`5DMPKF`FodCkA zR}5B#U{6uA-31`Ug_&87`9M)JhJvCI zWGiE*;g*Q7c>(P)TxKcD%rg7Sr^<@z+p@-()Hb}y|A1L#6vr5L)HlR|s=%ei2zB1{_GtsI>MC`RR{P5A z%wlGCs;k}`D?x-)ZxyVkqoYF4F-B*O(sdb_oVW>xJ`)OJr4u#)4akgS;gdZlJe}|N zyHFK!1mAa|CvezxH(n9bc&+d|aIhy#LNDa`Z_mZ%6-sJH;aU@rwmZ*g!(`6j6}r&D zB@ie7+E{zCL?$L}pPJfS2p#fvXCCwrD8uA|Rh0ZGNV@Du`Et{AAd-O*C{^!C%HEyG zgt3h4;$o{^Isg+>&>=WkENgH%VRMDlqK3B1SFR|o{1*AAr_As%N;UkfzMXx)(CF4I z*ReKzYWMqD^aGqTj+C?#N?4|iw_FsL(W4MHlVOG!jLD}PkfCYBHoMQ#pEseiApJVa z|N8Y=gl?{gWu9n%W(uKPDKP(s)^+ZGwaaIL1|Xr&y(*Y&m4LNw8EiioxG= zyaR~gGL}Z*XfGoH!HDv$HzBgwsw0s=4770|eC>%GV@yt_l?~9!L;0%ea2xz4qeDfm z9{6`>|6o{LUA5)~&;|j*FRu%utB6(L2|~BLyZ}mah7Tt&7``jtKQ*RbE}kUb5yehC z{e<=GKl^DRTbJqYPY4+k4z~Xih$F8yqAAqJD8zXK2<7Xo3mnA{=D10;g!*`w>!XMi zWw5;1jn@-pvb_QK#4`I-7u%HXmG2xmGfmVTXeF%n;p)jZ!Kdb9Io-oI@K?z3T~HY< z+cMVUN^1rrjyulR(19R;Vv4Yc2K-6-uj4==bmNC*K;MM)G}gy~5EiR*Xp2d~cHPJQ z+3i$s;l}(D71`UZ3nu#onWYKnIkqSH-tzH@p(s^l8n=T?pLI-Hbcs)Y8%YNTVHLN1 zAC4Rl$trw&Rk9R0uKW3^n*?p2wAU-k3`tt(%#2HekGrfvo68?CK8mBo68nk2bYNrl zkW!e890Bpso`CG#58AnHYvT2Hd&G-joNE&^o8>IUtg$vuO*4YtLEdCz-BGUY&!MhZ z?v9zP&jI?u8bwB8DGg@`;V!n!n-%G?b?Q+=!xv4SvP&rGe|Uef#ao$?Z!Ae0wr-TAWXNO@a=4NUnrpb0c&+!@^<@<4;CtjEc+g6&_JxNLVdhd#0W}Ng;D@zVah);QQdvg5}tmwynfBSrTxx(}6#(Jl9 z#%Gf;Ex3sQ58+CIvAt>Q-b$>1SUVq8(+Uc%`bs8V(N8b=>O0 zx+$r0x5;AQRz9FP9f5lxe5&OS&BVll-8Sc(y@75a7G6c3SIoOuz+#}%C?5>lJ+P>e z9z8s03ohjJ*gbc~W?>K#w@P0v1rZRNg5=Dny#90pPD)R3f%uU!kURV=CCH0K(+(A#RL`Z6{m=*{p2M3_D1?o|^j3>*+L6laoA%)IbEz)Ag-{{izHvEv0L=pd5SsGIThY6`84VH|aRXHLyXK6W z!<5+#@aR`5iX}^*ikJ7H)}=a4^e%qj?emBqim?3PP_v>~=3EFMQJ=Q+HX;*JNoQKH zVvv`yQz1xWB@Sy{53>AGItmWvFnZkz9X%h0m2URtmgG7B3SaMWRxKel^UQvY8mj^k z`A$bDe(~UXRI6(&a;M8HOkhl&IWdQ^rD~Cs9oqNC-+yyT36lxUotn7hcd1#<7SU2Z zIq}ou#kMt;sP(#qTHdkx(6~=G5Y&!d6*^vMp%iI8*SdGv#NUOzsN96FE-?dpQcIHVo z-|}hII+_MNb{KpOCH|p(4$EX^Wzn>14q8-P0pRp=WI-g{j+Azv%&KhAJ?xLyVVfOP zym)dtj`)0`xQyA9jp6tV6Q>TTO~~1=KoX?f{lLe3R_mf(AoZxO!>n|eV(off@i#Tg zvh2eKtd~M2(spV)P_K}Z`LsJ-vplI2=cUjQtJSLfs2KDxRT zeC9P`Ww9fcz{MBWH-0Jthc+Q?_LV;tRE4xzgH8qA0Dvo<8E6G{YIGnu`x>;Oh?AcW zA7ows>d3kxnzkxN!(XwK(EPcoS`gNLx6T#o*w)%isTD#YOa6qJQeNk_`yPc;rTZ0s zNFEOuU?M~jsv(g(!InsujboiO8v=HiYoJv&eV${+ z1LgtZ+*Lb}=c?X(Ab>mY6zxD25DHXsV9lC^5GQQo2w|((YU_5!hx&F|b3pC0Z;9JH zSEUQ=G*Wgj-d${(>g#6$*r^_e+AAg-Qvv$mEtLKEhs8b^nSrqKB9T?}sAmX|) z$T#18)`~_@PBonxhftPcCS7E13F*h}x>(aX0aBXS}!&#(iTM*Zi#_<=Mys;jB<75+Q;-S7N_S%J`Z;^X*u zwJL%m_mE``6`?mkwTJ~+=qrRz43vEddQA6CH6ZiS)26*EZri@%SNd9eXpNPfd5e?D!ghrXXLJA*=O? zcs|czP~}1Hu#foIXCn`=|LI_$d@uzk$Lvi^_3*1#ucmywz;y_uI^~gSuQTCFIfe6v z|I6FkT$I!l^Jk6O5@aUQg2E6m@u{k~cauY3KwxR|)6|oH01KA0kfhS{YSd(GotR^E z%W|h`$k84f7#F6*{e})B<}#s*{6D^ zg0>I1(I(nHvSTeO#_P={K9I;B?~iK&3F65!_EnAupHNmEAs4(kp5hyKEVR(F-yN~G z>9wB20M%q9JE9E}S!nSHC9D*d;?diV_Tlx%QNP;{VDIP8^MWyk8sfeIXG+@OSuCoB*a`N9ksj52ZCP5(5&4@Nfwl6_S4hSG+qG;mbyCn*= z2@&3ta!A0{dk-EwC|);~j*ho4lC%0_=n#bwYBe3L&|p4qLdLoiMZuDkosuKH*s824 z&IzE|gU$&=2aO(Q=9g@H`Z4tDCt)AGxkRj2x7vapB_=BJ#6a@Bq?5ilbK76%R`#B%?{& zV)(l}Y3YKdIt0xSX66Uz>Z5diu`Ei^lqEi%BdG#*9BB`fO-{|8fq@5q>i~XRwkK84 zEjxsrK)kKD>?Iw|mCI4K4nN>xAi&E7qUmpPu89+ZqCWzIKcCFw^q1>Ufj;}4AQlnc zJl{vW8Y*&4PXhjt1nGU~HtmxB@&iph1!A6)m)I@E*&w^!z~G|{cLF|8fmi-oEU7BX4`QqPfhK@3QwuE@M5!9E*(^`Nn}+NIm4DX z7sWJJ;T{+vKGe5r0PDdM6;1wCUmzq4X|h1~$~MKOcPKn)M|io_r#`fNxw7PEU%Q6W zli3<+LOaEH{$RU9uQi)@hZDsKLboY0BKUHJzN_^3a7FeDbSR}$YsBdrkjz&ol)!)W z?!cdYZi8cRAi6^pNz;isNVFCckxv{4@xo<5fbD z?~#g8`2RcokRh;3BUqSA2h39WNa_Mf%*V9B*&Op|q!eL`w9+QZmGQ>n#&ZtEI}+hT z6dEO+`E>B9xDM}wtP)exIW@~03zT*dL4487zT!mT)>v>bQho2XSu$&F^9#hX7o#oJ zB^b&&OU6t{X@eUFeR(@2@FPO2+p|zsBl;={`x6aTO$f?kOzHyADVGqEXk7DQpznC> zj;ZNJkgR}@l#hL`hTbCqCBVn)!J$InY-BB3hUs7!_?JyT+5$HLVDyrDl+!j2SPbk zWdkda{!Zkf2SA4`KjP7}Z`Y8nzm2t%S8H3(P2771 zRw@Z9@S5nHm(ssBXyvp8&##HdWSm_aMP67^woac_+AK~r?DC}mjyv8*=61GoO=K`; zEI?(eu)y-bjplm77^DT{F^^<7$Xt9R+#sYA(F-h2Bs|71{7v|gy^l#2!Hbd#7&;sk znn~~(c$X6{-Am~7mxt4E0mXbw5#4TSX-PCDin8zHqrC^+PwWB_QN&QI$<+&y@y=I9|u%u%bXUKi91(U+s`5{fQ6;4?3+1d;&^E75` zC%PsbIda5zR95Db*EVV(!Tv?ewz!8YBdtI!--t&T-Tqx59p+;vECL3Rx66jDHxH1A zXTI*qy+qRb-T3SE6JR0A0x20I^-c=~3?$DW*O-f|j7R=RVj&j0cl~3)@f|ojn&6S9 zk{|Z9;s*ru4UBLTx^cKuINHrwZV^Al^;SA3$ z7X+T&1#KfB_N9WMa}z~RlG(>IzKDVB(}$2s<7jV@%20OYgy&=@z&R$Aqy!%`ns>i8 zR}=tj`l@E2wF z!btfz39te$CA_((|KR{SmafviZUcluW(>lU@CT-TQo*qV3?K)+nN|{R)qUI)wt#@u zPIU9iLz}l8uYMu|9+s0(0<+FhjFvO4g(8^|VG2vQPjE2D!cnI{(j=Yrcq-R$bo%QY zc!G95pdKI9%hd0FLiSELQ`yJ_KD&H6JaB35)K09X+PS~8E6Qj9pz#X*u9UuXM@rK@ ztXsdwRl=M`kh954L!k${$SM@w_V8pU&)VB_pqicoGFOPeg35q)5}$qdc|ShmxT6|n zkMd7PG@r-Q4H$CN#iF;jx4#||qTiFz=)S_k9e`DaY$sz@6Ybs3J_XsQ_9ah|Lg-;+ z_wowAPfn&KKtPU!pjYW}WhHyRCjIaNz$gPKHxIk^3M_Hxuzg_e{P}X=HX#9QCjzPN zw6hI&Inc2Lyhiu2(K%)qMh}b^09vf3)c3flWZsO&E%LVQ0D$Jp-Utu! zW#E*&S#pbKABV0>P{LU)K{bP^RY^_XqtF{@n!cyk>i zRw+xOp3o4DNZqtVn!FQ9E?o?nY}8!+;v{i#;Bd+^E&qh3`wGtYS>U?=cv!kHVKgYX915 zlwV83n&5qI`$#eYM7pzB8Xpb^>5sK)cIWbpuf7yXzcX+gfskU^Dq-Q8!$IcGZ3l=G z=3B$bU~tBOzavy7ZI<2jY}#SWUz6YcJ7e;E#U=Es48~{gmk+a$%%XAH9X$FMND?(o zf=K0onidS=6JKFL5Y!_fSk5Ad?&CX&;r1GBG-~W%;$fypqhm4}WQOE{B<D~1gyt?8GZ+t!pyJM>D$`^F!P8Ol@LIOq-B&S6ij z2!?98wwkze9D-meCi_Erki)uQrZ{60lU;{*Va>2;RS zaM~>$0dWXX!035BPmQjSW%PZi)S4AQ@Fs~1OuWx0{H2;Nys|qH>kebLr`PIXJHhX1 z0LozXt5=MMhQkvN(kn3T?8ajDBn73i1I87#(e#;bp=PU2bE_v$*V-eyu($AYqY>br ztv#!uKCOL@Mk6Dstf3HA<>7Ag?RjXA7B@Jb;hi@%hhCDgCD5h&iawzeUBh(PBVOPb z4Z)p@r73@O=OiB80|dZ8m}gL3l&sd`cii0Ps7S5B1|LW&N_hO38n%=BV{Rz!;BrVq zvgpXiLo7l208s@1M$1vU%>F1xetZ-)uoPxBa2y`W^txd{rtao<@Nv+T=#^Alq`F$-&--JX(V1=@_ zwbfZLj9I?lF`sW)*=cj!VG2z+;9AU*DNyX4&n*MwV(Pe1=V5n4Cs<3 zV%t9WgX{y~?+<%c1H*6w%*r2H&e*~ZW4OZgbZQY5+6^Uy8cY`)uP4SFb_xI*-et8< zX*SDyw8q2^Y4X_Ii1@6G7hr$QP$Qxb9!BTn>Zwzw(gY!bS-cUyxt$IA?I8PSBwmuw zrvt8=IA^TZ0k%&8th%RAQHL@TNK`m4qtoW{)hYkHD1$LM=9}8&fBxXzMtLhSVw|Tk zOye>&aKFBPsoi<=uh4x`xp`{VfcJG)kV|8W0)XX&;7 z^FsgL4EBHgzj}|3(4tr@jNXk4V8CHjHPf+z9Ui`P)=yW_atzf9V5U6cob_<@k_~6- zY!0vE|AzI+XX!YFc}A7{$LhhayN#(qoFmkO9kJ`ozdPmMS04BLf3_gJZ?`fS7LN$n z0t2_3hBSZqLMOmJFZYv=kOi+26dbNJLtKOarv5oI&5Kw>n3 z5X>(7xcS?0P;S@IC^wU>N3w(6X|dEQi(|$-+5~}tsnzvTj1M6K-+?#1(!hSADdx>% zdwqea`CKnwzO2eEa^mwp?z!v%doaDk7EHXvkoZfoo-sKHoZ3rd+GG@lZ4#Dg+JO%b zbL8ml`woTam3zD=|8S8kQzwy8yIb1$K0IC*G56dc=|3xsx;XDdU^% z&ntWiRA@OspOvJgx30pghE<`;goqj_s6OQKqr@0TH{O2B)}Md%s32?-fY8q=0VLSz zfso|&2$T}~ISbtb$?zV&IQEsV;MfxQ^RI@{uM&9;Tj{OVRg=%bE2k!hYj1Fx&}D-y zd>QQTPS{Vtf^96bWZY2;jHDFk`&XzK;l-TOM{o)gc%lLc9Q9iwe}0ejFaSv0(024q zAtHx;gXS_mtoUim=a?Y}QYMsPv84(=CAtv^p$9#GSp~afVTN``vLCH8f-W*d7EpGJ zB$xh#hleGhruupexnL03_OGTPMra9(EPkKYA8r$__fEH1y-HNn1J+QwP$Cn^{RoNF z1F6Wlf%-=V+sLf~!?d8J0K+%rr&!$pN3Aw|u|weIwiD@sJod8loJa8XNY6X+`O6nN zKPE44=4v2Fh1rNcm(ghD4JhU})EhCis=TGfQ%Y!I~N>LzQcq$Jik-7f_ zO0Y?Sya)eJJhG_|_}$2Mc$yZ`6TvFv<@?<&?@0J}cta1vOAl*rk6{pSC{(6EKwidD z5#oGdZoT(+7MyStdb|t5%;t&rIw! zAK$5r+4sMrI(n~FWF;qFF-Zx$K=kM|WO?&ZZ8jU3wLp>*8I`eWsOAgbAF%8v2F6QSsXjU{+MbqcZ$2N z>+(m!(O(b!J@4do&RGS5qIWMB=Us6B!%B3dy-uu-)84{pYY9<*A+1x|u(I@!x+R{DKNT zzAEue77bfa3|`UJ%h+;ff2vg&JPJ*ZV2D2EC$R5D{v7RQ$Y$xt=^lb}9sAgiy8Jc} z4Mr>0GZ-n2|9NeHy^|Sim~f3pwyq_$rbZ_d?g1IlFu$o77~Dno+fR>9RNg4BvCjl!7ElU7;w~`)7;4YVJ%TH(oAs&lKURItuDyG&qw9|Ly##R2d+>(< z{@>hk`k?BY07}d-MX$#+w1IGzy53Kd*Ktbd^rY3Akpix!qx0<|QF$3>8N_1#{N?7> z4=5YQhw08xShZrsHfU~^T366I2oz3J*+>u$ zi^0rLc;fwQ_kn&N16gUKg+A#%xR-}3b@49aJO5)lZpl&Dy}Pf~o{=&e48Y%D4{fv@ zKc1hT;b4mn*`THlYni{lcRq|M4a`9|>Yu0j?AcbuP6Vi~`M>4-eEIa>zZIjV0#u=X zYTq09?ZQ9>+Zius{2>MYwj8o)`y&{$rJv{LJNA#`kbn5#!OKTxHVlciYgPYQHYkY@ zw`o=Tzj*_k6KZ?*G!(CcOmq`tR03Aw-uHrd6hc!8gA-7er_Pu$&^m_Gac#^2Zias- zyf{M3mp?N&0cr4cVPVp!GOkpA#ZQ>+pO3M0Ddw;Z_enBRYC^-pTEKSMYF)W}xfn8Q zrp#GwMhZv+pv1?cZxQ#U;dq;23d30$w69}BxA78L|Lqo6rdZxbBkEd*Q^?S&GVBwc z&*9k85Qu(?AD>j?)8f9W>V-TNW_-KWo}FzE_t|t)&_!xkRTUi|in}KMm%HqdAVNfL z&sRLV8XWBK2|G7l;?I!T=HiltsYS+GOhZNrl2CM(_@waHhVQuh0$r~?lA9Y9QHmr9621LpGaJ&|CHF3DrSGJQ?@zo=< zc~_H)fz@`m)y-hYcI8YE)Qr8ATcsj97793P-|vEJH(&l=t{pu&Z5(!W*{-_Y22DA!@@R-if2@dYP$?Q)01-_-8O zg9p11VIDc{WOPNK6Cs9%ynN&WOWM#8;MV0~;o*zQojDm<-~_1;=fxyU<|z!3t>?GK zdufT})&CESU@)9QQ?xc^Xl#ntRghi9`B`yce&{nDffY)EqNDYdcMe9X*+)LulGd#k zsWUxNM=4Tao4`HqdKoqmm*Zy+J|Mgw>@n+O1q?Iqu$52P$*ftk7cQy9L*fO*wt*cj zfk1Y$A%}ys4(xahgb|>xxwB^7g`k4Ax>n#x{1FaAA<9I7sW2%Cr+ztOV*)wT!T(iZ zuK-Vl!IElDz7r0l`02XSdwb0TpgxMf{*V16jaEge4) zwdd{`(9!o$YuJWTa7_$XH;zMfp)rIv(ZVX2wgTR=^nh#qe0@Ll(Fi~r)Z1Q6LeTnP zytGCa{ZPU~>X8{jqUTracwF5MdwWPCrmMxEaR!nXbu+Wrl4eY?_rqhr(?$z>n_*ZO zcy<4@BZr;?A{I{XWR_Xpg~M=$sG_mA!59(^RY>?wYYXtC`%zH7$V?K$3T+pS`-MWc zUsO&ziH`U7h1}HF7#g{BKuBACHjB@^YL6;T(S4A@6`ZorQ{)0i13Dvf%Q$IO=vZGn zfVrNG!D+0}ne2PY{)gu5blv?Uv3-9>Ck}A81o#D?cjXok_43aYbRPB+PYn}~3`}h5 zy<*GW4h^Rj@-pr9l{5{M8}C?7_T03voeTy58!<&FdnQ31lBNyHsJsllR5?t zOG8jlP*O@V)Y4kc$F~EulKZgc(Y!kXMre5u_+onpD|VwPZ`Np!BD5Xd%Q&3j%Q^8r zPjjWwM;1nOhrBUJu3itHSZ57h2@zX_U%bV25Agk_d>sy*I)hZ)fEOJnCpt>eiw>dVEupn_U(Y(PTSCkh&I$4 z5G&pXMaTZL2i6+=A94;up93m@#<3w%8jvW_lqBdxpfdWpVqCQ1ST(EKfj||op4Ozcx`-yG69>Cm;iuPh&x&N>(WeMZ!iJ0LFiq% z+5Co$dbiC2TL7L`43t63w~r-`Vv|q*#gK6w&w!iDSSt>*@?hoCyQgRPcR3D!nBen1 z54{kR+aTLBp8!99e(iN!%jlV3o|dw5`*p)w{>%!E{arT_ zdqT#8zp6?ag{hk>G(A-8d~!W&0dLGmvae%Zy$>66{-$;4&^=>k)X**|yWO8$h2<23 zn1GAiCX+c|GY&m%Pz|k(Be|EkiX#mCz{7nJ9tO_6UqqtzjU(r0$Z!8!tq`qanXP|P zg$d1s%pHbFjC0A7jzrH|vyHX9Xo@I@WtMCx{umWsiX(p8ckjM>peS&n8wQjoT76cq zm4oQnb>%PDpEew0)!jMOVR>e%!R8xZ+I{M)yTaq`E3Ta8e6_UIfc5rwdJum|podWf zBHr{i3?|rvb)w`5_4WW{;q^6Y=zXRz2G3m@G&AX&NxXDS0v1L+dh{r-h`OL+ckRPd z;zVwNR%NTi#8l8jm@o+DUq)kUG@@Y56`$MypoC})jDnzNBdDL1fl;?{XcP3(Frfu; zeiI%b2G-u8c6}1N&`{Bgmj6k`Z)K}CY$)$Cy%7))K`<1HPcPLGQO5xWwdrlJT19{; zQ@^K&u)MCeXE7I7TaVLQ5E;*Vg5Rd3b9|_L(oBtb5j1R~He%7q{+x!m75uH|FFrC} zAT&B+l-e8?H%YN&a#*#Vzi{17+)HFFPLkDcF+;cW!vx=$iET(v-#;87xfK$r zC%QA4I-GjtjX`xyo}9SAmY14WaT*l{uFHQEeCyV?Bt{pKm_M_5FtN}CRb+e}=pwkO zBrW}^_Bxm&f~fU|qMkm6HKLZlY_J9v2#g=wk=y|pBQRvc&@{ zQV1QmySuxwbxUFU=|`D^2?APpQUBNXP2Lq~JG*;A4#7Ei$8>JabX5aTn2sieXl)J; zXlAwR01eF`d-Eb0rxZx`++e;G=8NjAmXbxUVw=u7U4-xs50@R5PZn;Fl+?yi_IR`o zW-i8fw za6gp6W-`4EMNqbj>PD3CSqVPn4kOp6lRm&mI1;9DWqf~~^u90!&M`RI98ia-JA*Z@ zjl$i2{Mi&+0WGUfqh#{qURkXO$VGH8*r2^|COpoUuU$*x{d3{mxuJMb6C971Jv=r@ z*cw>`@Pxr4!%U?dSQgbrCz^mvn{^P8aFEs3?KE&=I@S;o>Tm7Bo}wnTbASUL9SMHZzBATL(&4S#+0W$7vNX)b*;m>>UBI0gkEAfA>e{%;#Zya)x|j>})Ya5@ z(`#K`wQUGe!lCYR;|~o}o%^@+S}ODE59`b;E-C4UHT6cYB_Bgrp1?c!?&)nXex{;d zeH?sV>7^BcaBti!KYQj(BBprPqM*XR?n;yg=Zx(=Ku%6LI(^Jvg*QP{iTXL@l>?j7FPVC+7!3V;%K$K)V5dITIr`}ZfPJs013yRZKT`d%vO{J72|*sYb6C` z|XMn>JDZ6)xdXRJihV7|tG2F)0jB#qfM&jgG zFVB_ud|ivpZ~x*A>9Fr)HaDly)AGS=M{ zuCfBs$?|DUJgR{Y>q6wcd)9@mpA+U#exB6_-3~b4mTvy0 zr%C-0!utWaP0>Bnzi!GdRV-2DK!>&TlT7?(Moc-5tX*@Dm*u%556x;IRBVXGiCNdQ8TGGZf68@$;h;0sC!s>DPOJZ!k@$tmOQ;*fu(1@P>cwN>YX)AG{lH0pmCnh@(y2WX- zT6!Hoak2xe64@3tPS15fb3d5OXKGu`Z`cJo=TB2qxlqze4=O%B{z4MyvtuYYTGG#h zA@{~Peb`Cp6ySRx^Y)kwh_u?6tPaRQ2?m9?+h1rz?Y)1&Ktx(v7q2373sEA+`DYNF zQ_&-~Yh8!`legV<+=V0ZMJK#>F7aPf%cuU}gi?LOUy+4P#rn32uC+oo_GLG-cKUmG z%Vg|OFj~j90qMxYTqKTuj3w(3Lb|@rFe)m#CAkk?=q0tw;Xy8y4NkMzCF}=vkovc49-cW~Ay4K)C*| z9_XI|*Tn0tU{G&gL2jr6u1cpFVIze1V--4<@@UE+4+G=V2KY=hxkO9=J%S+vf#o?8 zB4PRLj6mFHhoV@jj z;)wr#N4ctbEfKGZMOH+&LwO^hPT8#k{Fj`w8!J6GUA%Ci_331uQWTt-Zn_x3(Ex}3 zjdJs}mX)5vO|Pw?(TV6~XrbWdJ`iW3QPC2>NxSwebSsYQ&#FOH(-xeMWr(7!k2*Rg zHNYL+hN`L!(HJri1*fiA|F{xJ9^+a~js}3}z_;(v!3l}(1=><6s=p$Yl!xDR1uL&a zcOHn$>U*aXdFnu$WBT$$-@csVkt4siId+Z~4+qnSV1#V8Y&-`i^&tmCWIz5jpQDQ? z`N12e*0PdM#OwrE2m_s%R?DO50Y2Ipqy;8%B%mendZ-CX7^Q+-y4z$>)4O6s-|Wp3 z2A0(h#1YZ{f`Wn)vZiTgLeqSw=NNJ{z)EhP`1yn2+pKwSpOxYwPXCg< z4HjQgYjYeJ-{r7D`(efV;ku4LrubCJEX%Ygt;*t84HIU%uHvF=|7!uM2)L+R2RvX@ zAPOmV5YN@J;WbXf!eHs@_Hj9n#cN_V9{=#Jy)MNHC7)XWAXV|qK+=SQ3Jj@(ai_Cn zn81~_a|RXZ{sekN;b-OY(^_`EGX3vXFI z`8x}a0y!UCi5>eX&^6K5Ad=>oHuczW@#D#*-#7#$O4G75rijsQuL^FN9MjI;=Uu4) zH-Y6bRpTQ;p!t)uzBPp5qHpQT#kb%pEHgxiHHYx|#^bk;PkJl5jdJ<~qm!_50(O6x-9<|%$Q zv8$t4#1UqB&1!tf(>ACIN0O_>>}w4Z1SBLr%$)PoL^C(!u&reE6RNu`i`FhF-V8D> zhL}CT&~WS2IXc$!)~;YU*?_*$z_g%5BnhsbzfHz$pfXrRP}!t1qm6GmgAfeic7rig z^CGd%thxDqmeE~x{oma-o~SyaHErfhO{~*QnQiiqI6&j;2>cR*l5dY`@9#O&>>S%E zC@mqkwsQYmuj3mc4U(_$NH&KG+!k|DlDa;AMSR4i<$Y&p*Dlj9$U3%cu?sVr*adtgT3xE*_%9Y59s3>R3eJd{>E!mnP11E!Uyd zxPT#J(cq>WB13H}bDLpU>qD2eh2@xkNG%LJn@2OZ)H7<(94o?A+4=lG@#^RFf?+Nh zue-lLJkk1kbLLH^kArgB=(B8BjkGg;eV)b9j$yf`(rq?Y=^%1cM~qm^{o8%#zR8|S zyU1;eIC}PCD&LLZAyB2aE}Y9;hI3ipsrx)Oj;=#2%2ky|8e1P570 zp^P&Ih}`jH#Qm6_)$_TyO!uQtPG*{IrZw*od6YqVHpq;}@c+-|(ke6y@b|o4zT5X(fLXtl zeCkcrdP&uO!}2%t{&==L^xRN!m2Ft4WpMxgk+;u1>wmwfShh$}$w9GwTxIHvt1&Cs zuOzT$&HMTlH=rP%lw^E6e&rJ!%Tf!c1l&dIq{74{vuEE!y(G^>wrGT0_gGK! zN=k|Z8$}y1Bt%3C`GqFfda=y|N z+7uMlsqZh-DtvpavI@KyzLFPXDk8Y=@g=#X=o(^!X%qp$-%*Q2!|Q^Agp6jIF$jL8 zWF4sBB=J$9c;hN=9ER#hd8W5v7Sn|!B3&RlK0<$fJ3o;F<@bjcN1~;*acxs+u~NeH`=EiQ0ghsEbRhEz3FJ>JlzylSKGm6bC5!mFMYJ8oB+X+uXijkdm|%g zq8mE;&z&;|y0YTy%8IAjUW@(%{|mJbs|t!HhFA34?ppSduG^+DqgwVvRN|KtoptQ& zWc5+7-Oj@&T|M_MM^a?n;soRhdd^%6B#AqW2OS^PG@pQx&fSl=T+z|L^Vlg|Qg}b^ zs+LOx?-OffPVJ_f%jQXY+?SvO$Mj$^7_Uk8`-R57R+x;vTHLb#U{-(@L)25_R z6Tk~eNHN+_g^)0+EI*9kmRZbHFnYqF<&Dgl)z!wVchyJR_zTU{v=M~^ue~c5U-IzK zz~`Rc1~$E~s@6LZlMHfiZj?3G#MG|b#3j2DaKcG!`&qq@K4}=zyN>Vum{O#nqN&5g z$M1@ZPl(wwJrdOfns3>5vX}S*Y)$bPW=o0Osq|VS9_Xlva=qi)Q0bJ~u<}Lw)2nWr z*dt^6){*7vg2m*|6rYy1(X8e}&xp%5#s_JLvTMeAnInuY6uI_+s^toXByUWPhgd_6F-28Iy+_~RNhCz1Ppb~60 zGaX{*?lzbZRpIozG%`dPu5l(HPun_F`IS9-0t_2h6BrT_2a>p81TMe@<$#4E*(%=P z&cgwJ?ZTLTqN`Tz!e?F=&5~hAfwL>wGK|WGa2yqi&DNnnvKNvdu*RL>r~`L{ooA4V zx&^(|3T^;Jp#Q;7Ou+RV!C&$#LAiarj@L(unnHAt$R zHP=l?C#0|+PUjHLXQkXYPB7y*yqzSj&*kEZ!X=bH3ik6011|AP(I=h`vTm*eL?YNe z=L8t``Jp3lNt)Q10+PZEV4}3%gw6EXR#f}(c9`P)nT16~8>1zs9Y}9OwZ}duI%+KR&2kTwefpaY9>6XNcTC%XRdrusFXw zinv1nOPs|EcYvarDc$GQve3wyrH27*9VlKbSx3B)%9EC~*TN~nf#!)x3dp;Z+AzSy z=d*1VN}m0hzM+WHT;(KS6m+88^*t)>ggYJAubIY}KX>ji02uV*@M;;T26dlr%F!u% z<=QoM$mj;n_$$3sTO`pJk}yv$YU}x_c#P_(h1xj1u^ufm{>hYok(+YnIA;6ExckhA zvCNi3?$yBzbyp}av`Kwj87eqEEY@7BdLuIFj;M`RimAsDQVv2FYEluH7UV~~U6Ap1hu|FF>fGR64)I@P_wBhn8y_y>>gP3t(- z_9bn0O#iuB~TqZ#5lIzbvJI!LObA4P5zGU+5t<1FY_8CnP;!MZd9(YceJ6B4|ugrB9gT{a;M^}FCVk(-tzt9 zBFVx4ajHiO47UGz_u`R+N+6l*$hkZz2b&&k;WeYy;lQwlXD)o>ET zf>g{M#)?$e()wDqkfu%mrRO^6=>?OQOtHfO05=JN2%j957Os+ER00d9Hbb~m*tN^6 z)+{-+z6{>aw=vCnPTf1oVs)zBqAp%LWd;<9yL->mRJMEYl97H?H-4SPM+9)0sQzAU)Eq zNJ`#u*Tao&O|-~t2P>eq$E(|OACIKfcHl-lTA)kghMd#kM#aU&rFXYY208j9&sp)A zSu&M?RY023br}c`GFuxR2C*1r;$24)XJ5j^gBZy4Yyv!(aCDjH(ofLp@ zNgh?!Jb~;TlFqtlfSKBhCHOR2zu4zeR*c|G%r=r1tVlNWkNW$VvB0LC4{LX(h2Ne# zucfN@I0Nehv;zA`MB1Z9&F($JEu*2Ch6fq(p&?R8COW+b~rW9RY?_k-b zl(LG@tyUaB1~!cc_?+b7DxhlJL;HEw9AeA(-O+}?_3DwTe7UgsX*xM&pr^nmt4=WC zk;vNgX0jBDk#08jF)fk*Ee%C0CoyWN!3g% z@qL3kd`xQu@|19P9FBzWesmTxMvGUZd{0I@yw{Fopq{m{&ygD`*V3uKl4RPi<(V0i zISw+<2l(_PD7d&3fMf|euEV|&JQ85AN*Fh@lUd^{LEE8o_E`g}az#g#TY_p2_S|!U z&!z(6m`#C5@+!dBE*+dDb#_hDiCZBofo3-mxO;wIJunOu=x8TUav2JQ4m+sGqlt?y zT+6RtTaB_3(AkP+C1#?{AIa+f`P42d1-=?F*^0xHYl=dgp0GQz*|8mz+0<+YLM7tay*`Lfkm`DMgems6(Qh z3w0RJ00l4tNLCSe%SazYii+*b+BC%MCQAqe9F{%UEt3gl3{oN0}^&MnQ6qs!w z5$9x-31TGS)H#d+OnHq)gVoMHonyxyK+O4c_R^d6*!BQ+>d+fmiS(RoJWsnIC(Z7b$XwzQ~8t$R_QjS@w(vc49Obt^P zoe!`X3mhv5Et(xFm*uzhS#$`yn0Bc=wKX-)MEM{Zt%aLku)GH!Tx(@Q1X2YfyOl_z z!x)cFuF;aR?a+}PY&aXvwa&E@p;kFJu5K+R1A#F-z^@YAS1?xmd}$BxfDKGCQ7I`O zT86&+?_2{~wnu1;dl>g%-7SJ!OFg#3r@X)lULAR46(Z$*n%P=ojQ9rx)&6 zbbjZq%sRi;#N<=>XaXB2Rj~`ZfMhxX zdOdaMNB^ZnIw>D{|MwW!ArHv)?uhWsIUSTkn7I-L3y z_!z)9o0A=UKY5`0m>!7Lz6UA@q<%MVK12_bT__t*KDMc1I`<|uL{N3u3#B{M(XR#H zS3#N_4x5y@aDP+y{W&)J{;Mr zl+mE&;@?)3SLC()&Bm#B&nakjeH&Ug682zH`J3-|;kJb3Rt*2zAYFpN%{)p?H_<_G z)uv5VeQ(g)T)N7^9{aRypxV3wLIp;`J)i>#5Xg*4LLI8yXOK;h0s+plnvQ-)lnpw- z#N7wd<||ZY!pN|QBmyvVOFO8MofgD9jF_N+j=#F?QFE&LL{NRYJh}T9Besvt*D@&H*bXN zlekmR!Qs&LHIPP%i~YrGhijMZ4b-)_LET;B8x`=N|#Vs-Rm-pjD#pUL7Tr7w*V>e22a4H-i}YD5lz zDyCI|PGE-QE&JggzI|H+)($w^!O>~J7h3`uH44}z5(ySIj2|ZFWyqM~rAa%2(dS*8 zt>kQYmdVKi2@mbOZ^OzFj>N7FX99t8e5$2*NisE~dd8$CB_8c_V`;A=u!Wy41Wo@6 z4#!Wuk1CJT6UI20NWu>gr1!@kIuEDeeMq}su|kQxhXo8?ktnjq<36EJQ6NP)>?FzQ zA!Z*Qee|w?*eEr_xB^8oM*94&fol$5K;M1?EeuS|7pZRiHk}%~b5DZuSZ$e^nks>N z3ooJu5Oe0Ki-90!p^aJ3FokD58Sba%rc1b+(K~)-lxjYByQ z)3W#fBmFYWrcR%(j_`~O$kEkvcGvL@)ttRa5B0ONFpew^9Xo64?{85><$>{FHUjpd z&8MO}Ct1-9Z&JTdIN0r7h4)Q@zYsC^%}gKrdi1+A(xRs69l7$jn2Z%KfA*^99DP;B zSY7QJqrOtXWbDRBkr?ZuZ%@3M&XL;P?1jKciAKk5ZSZqzqqE^4gnrWVaeK!Q`eYht zIieYllf==&DR`WVstMkvN{=*Ii>{9GJlrCg4gQ>(w;<^zSxwfu;&{dQ< z%LKnj2fTd%m!)Jhbg&1OhiBG_qczS_w_o0Wg`@v2R>x9qop$@UM{9$bIhaS}sS}m;HUm{VxCWdfj_pxjN^2KJ)#4-p}*A>lV^X=Fd44bM#<44EdG$2|_jb zc%)U9d{?Lbrn*zOkIdv16d5+hvsQ4GSjI)*YdINGjK$&!66-m+syC@vVG{ zAR>x}lcfqIJi?NKxPFnpm0VNTiNmSDy7$cA#ZADN$mzRTDsadDjlRchA3JEeGGx? zXCk6X>F{zlSfJlP=3!Sx1DC=LwcVNBcbx9=8zj!pAneNZxYZxu^xuWY{>K07cz$!w z-cY@3NNqsOV(Kbl-bCGGsllgqIU4$XuA6^6)xu@qEZ}ZDf)l?6y_A+!;X58i3N`fc zOxs@@HYA{x*}f-ys6P{|&41Uks}QLn(;rO5-ICb@J;B(}A-q-Fx=+8V;I^FHs3YK6 zZ&WUR%5%_M>B->rx$D*(K?&Oo_H}vrNBG7hyo!yq8JYS~qp{rpzrjdQ&F0#T-~mng zv^J%g`jfyOp=imdD-KeK#*#2HZR~Zs0F@;nqeSscUrhq-Qa5u9x1cQK2oRA*Y;$7( zV9Ll4YoCta=q<7VdsU7_?L4MqILVMDF6tg9z|YJaAU=@xJ5c`GGYy1>BAJa)BH zgm4on=SxUljLysJrlT ztbnV)v>tWUDK(>W!pF@gqq{ws`Hzh-$zK_mdq*_;czKX6JnUDz(aCbjJxt*i2*dvi zGJLRL23LZ|Vj!2(-5yZ!C1Q4bbC^<2H)BHgjs%TGRc;Y2{G0TxD*oO7-$HST=ge4w zoI>LJ#_?PUe8$2pzb*?~%S(a5r##!6`eTj;AL~lgYiGN)Xpuq7!s*~mYF8{IX&K(x zJGcKk0`73J`aCQMR2G3uJ(40)Ho1~Op8Wsu5x?aMPDu^^wUJ-bYDZ8C=iyh!GMbKw zwm9v%&D_4!KhQc)TUYS?4Erv%GAd;x zlg~K!{s6+t26&~#;SQV1lE?cMNeTVJ(^;%MwN7D#Nns)+vg`WaL9A`oib}h+iko+Y z?9gd#j#6U$q4SiLGZ6_R!lOZAgGHe(9yAsXT6Ili_l2?15bmI) zo;E{^2Z8R5AKd=?&7vj0Jv#s4E7ccbBfGQ5JbT)D0?IzS^1G-w=8b+8RjY6w=&vd` zY57Zj*Rhb*=f7uO7@U?X8P(fl2h#svT$hcq?=c639`hFnuy!e;=WAE88O`&peth=6 zBAZ9Q{_0yiX8ebuk&WMyZ?8ybU6nHU=J5~c`NtO=eE*BmZ%fu^e7mFh%8}hZgNI+` z7F=6W^xs#S_W1#D{`ixBc1}Gsol43GFt%V-U+Te=_>kt#zge(=#F_uTY=8fSlDkWa zww_X>ir!3GRIuhRo-3Dgo_BYbRez`MOsbO*{_m+}_xv{M`t~j1l#MI7>5)6?tZgi% zzHPc&md{l*w{aWal<&~5v&Hh;n6n=~Tzz%9L3=}Vn9#IoLdBM1g^T`&OL8-9=sV2X zRZ8oB+)(omEAsBwVc4g?kJHmRjyClv?3lk7kEZhO0*-ORbhcGKRGpdgop1&E-%H}a zjKTkYz)fWUMM5ssaVVPRewrIIGySS{Nl}2K@ufgd)f+biQ`rCe%bZNBex2ol5`o-? zX&$*dYi=elnqAYspD{J#n7o2;3em&;`%1m=>l9o_ez(mkj5h1V>cgmT#VxYGO43Sk z)6c(4p`84KrRcw(7U(r;aml=ynNhVXty?f>@vbgy=GXE1#_-#sd%ko^s(G^z_cSB=3=Wf~ zWzODnA^mETa-F^ZEkvKW=wJ4V>`4dH1>cgr1DQPdLJs;-|JbR}Xdc-wlT&~H7f+Cm zb>mhL%>VoHDf(j0XnQWku{kPVb&34L520k1&i*<}-gW) zk7VlTa2Q+7wc~Am{xz**H8w%F;@0aDcKnZ*Psfpe4^#59Pm!ZFRfs0dHFMu$s{9>g zqoaA-j#m1;GyI)xvo+1JD%QdEDx%N%|NUkBXTR@n%hYtLp?XTL`k%8YgJ&1m+M3VA zkA4RV&he`8X7TI?Xf1TTo*V(+A^apfq z?Ny}wX}%{&O7UdStz^-d)juDNLivZMw*5z_HUDQmr<7xk9bOdKwOGJZk&iRN*uph( zyI{r0#@O&W^PoEJH9E=MlT~xN$!a0*R)ic>oaO)TnC2Y%?P=F5$I7Q|9+gyS_J;NsQg&idqai>Lc$QryCFKF->I9CYNX_>V`%9*atrdKeK`t$8M>+JSktxlb>A z?}M%7nX3~l55;?(SJL`X+Cs z&nSk9o+y_d^oso4GdDH&;Evi@FjZvHwfj>1@0-6zl+}LC*2|bVlVem_#l=}$?%ADg z4{w`$#}9k=MnpH+sVXk|-{;A``|XTKSQFxH_+E@jk%Mp5cDk!dBJN)O#mng8a@*Bn zx~K|Vo82R;0=AQbO>Y-HY-fnP)^>|icQj=zC1Oi*E6){w^c4>a=^hN2wI~}9)O|K} z)4b$xZ;!R#s4Oj%`N3cFRpa?dWVrR~CX3Z-31W=gW#&w+?R4UL{#tXceDb%8j#Vp1LpWOZ72P*pk!75?KFnq)NiFGu+OfZ%y0+SWQhP35@U*4< zY}RMr&!;E1P26WUGt!G-ElD~$lDIc0^?LdL7NAeuZ%f2H#CKRq;do)%o-12YOEg48 zj4BWJykJOBJAHa2=j5BG3ZbJlhRI^K|JVq-^y+T6eG~fBZR!D=rl@pN`_BKZJId9e zxz5Y~{aB=Al7w4O*qVeX+RGMbUlA|umdq#_4_BVFt=r!!YGsvRJv$SdysKLH+ubt} z%2o99T>m}dsox**N|pq}2mK?x6WXVJ_je>l>H@BS|#QFQIzb!)PoZ%vV|D6~~+OjMg|RI}teJv|xI5`+DZx88WqENnE# zJG{<)=dl20-zQBD;s?Fw%%bk~i_z+G?hS|~y^>LQf62-`(R3t{dC4AEx+M8j*)j)k z*iaLwGVwr91;S_{%=Y(T@4fc8&QxwW4?WMBlBhzuO%yov4YLjR7Io zXlw`!L@9I_@`_)K$fNZ4b@FDF&%qGNGJ!qUvY)ptWhn}~Wmr3CYOP_t|IWv336UEO zKHoE()LZwJyt>R5DI>zI=$$R9N~LG-ukr{=T$B*EOr}%uNMz~T=0xvhRyHoy+5#!EGib@mFg$@bL31!~Q=HY?Bh2F`(yKm@q#;|BjO7K@5}?_kTYDvZWdJRZCo< zn5+vk<|`GU=p}3A3wg(VtSJ1l;%=Mg_>tC-6BY0Bp5IsGQ0i%yr+<1R?Af)ycurbo z^FAt$a7~_DW*ztjvSw$Wo;dULgd?7H&Z`f&Xh{mok|nAjv!c^tJZK<^sQADZYnn7n$p%^|L40nz@yFN5cy;FYjOWBSn;W@+8dqYOwTKQ%4 zW~aC%oWJ;SLZaZQe!Gnn@;&n(gTGS&ECQ6!6Y)$0sY^7>&q1>U0#p$Ii^NPTP6Cx5 zh2!%YHU&k+TF~uibXJrB`0ti!^hFVWjoX6YrW4wi@oBi-)x%9>nHa#4Uz3dJ)l0eT zpI+Z9^n#4HHk*$@xS>^X$W8s3p(G8K$UDZz3M?M8oJ$Vz&s2Y-+r?5ryHS32yHNUR z&wkhBIO_zX_wQP^cU!*yTTD+wW})j z#-u25ZwMVTYOWrw5AeK7v;vglZeV8gqBVvZ3bc@NM+5!y4qiy%EFtn#F7?N&*^*Fd zK-sgK&Pt{P<;5_&?QA}$jg3dq>TL}hXmQcfGo$Lol?y0a?*AI8M>{^#HHe~Y#CCPL zF7`HqzP5^k5>@fGE;S^~acBE?7SEK#6>A<3d4^h?$-H{COGsYPCEjG2bzI}YX137t zO*by(xRjJox8pG>3vSez*P(>?0DOXT<$+w!bdzWKmr#x~6F&@COO%uXi08qwrL)36 z(^Ay>3}fmJ(rf<44er?oVMG}W<7pPD z?5$hikqt+)1n6AP&oWbdwt$xL7)qcuY`*^f#J9{t?OHxl2TD}j($a13MnHEG#;0J> zyEl};G2;PRaLa-yxOWrUhvI9$#w4Z>jfi4>Uya&kbI5B)SZp<5av3c|JWY7T~q9o|9v2>b>`kbN@Q->3= zeX20a1m#8T&}Eyp;O7k#%hAzx3v3iEOH3L8-N`wl@^~{NWkozW9H(!T7{7-`nhXnw zPH_0Z_)QRG9$Oqn2~<*e$NMucvmD}hV`Xim}m6nCdZA|fASP}-qYMQQ?j8k`BZ}WY`zH=BlB{W_qlKWQ zrt+2i)!x<$x~+uuH}V1UX(+lA${Ydr$#IUECQ$xnuki;cSANmB1qE{w=x3zlfcxQN z*9`_rtPVJt#2znfs2v^Zq!YHw$QZ%#<=KWYEk;{-Le!$hhh~aK>m(3apm8u8G0fmG z#W*a(IQVP{j)+Kxm6$oYOo3kHM=F_6wOyMc97x_GfI*XBW}HjF6Cr>;eX!jK zRG9aK;RT(0813s%%Ml-R9G z^Xn+Q1`!MN^%+wgotSr%1)U}ElH}Rbr(qUF3PiA$c?eFZIrP;;;jdm%7(i-DK#MK# zN4?FNRPr}K3OI*fFihDvza*dl(EtVzacmF2(YecZ**->l5i=CLn^;nG_^=i^^@~Hj zS6RF?pSaKOHhM2-Z^$yU)qTEEf}%mbz)7sAD63r{g`e?-gKuL3ZbOQ z452XIxal~3I~C`>IoiBS$1kHCXVt;|jsGLk398SC4j=BK=WJspjJBYbSV{AqM&Vl* z8l#3vCd!s~EO!Lpc_xeCFEzZ6>usCf4I%~^qxI? za&Yu`YWd<&g566z4g*683CM{E*SumJHQIb<5l9e7F1mOdv86)L0bS|cnPa))4Y(>m@Kyd~Pn;!BTe%`;I;$t)gA&XThQFi^k z_%!>8?q%*QMQ!1;?iJ{UdQ$K^_=&6{={R#w9t60x@H*kdVEXDC(+aY6K7#K>2n0Br zd+v_>JJ=M4ueED0tqP4vyw23UaCUnw2D?%?vs>>*`j;YCQRW=Ob`fFWFSj_Ze&)Wu zGBK#;#vTL5IX_{^N_ttETu>lcr6AcjLiofTv>7psZ6(YW&)B3(8q>Vb^gn}|lpP2af zi~6VylrK6xqN#j)8_)W%RavEd04*;R?`)h{>lcx!wCGA?`@)%_L2I?K%jJ7R6xqAE z%aAR;|2&(V4v^$~6x}lMwU7T@`tfGnP#16GqCyf_%kH*-i3=LBQsH@0Igmp_I?}og zOc)O}ZBV#L`5fo!Ign-0A?h}B?$0fGd6MAUKGrZWDs<|p-U(B{ zV;JHZkn4%H8w#hKIMcC12wxIAo@`=5zk~(B;;%F_Nbp5u+EG%cS1Sliq(>qx(7(2P zGrx!l_8!EFO_po<_y}JJ1?zQezF_A=GwPxB1|{pjyLV3uwt>+c${u0Os83&1D99PSu| znTnY{=b(fIPi{o2$^t_~L1-T;2oFUgC|5-qFgGX;4XD|8aDSi z|C;Ty3&#*yEc$n+R*a*qvLBwr$Wix!u%CXuUZKGB&{hRDQ6Un ze_9HQz|>lOBhqa_gs?!!m#eti09!g5l2>tD<%CfHI{wj*A3uV$6NNr-V#MY}I;Cj} zL|LMh3L84g?s^C$r!hG`c&ApQ1z8Fty2hPY>pb*|!s3>4W^=J}fEAQvxh?P-6h z#}^m8Qn@_{QaI_R1$d)}_*-B})J5-S)QmsA9|KL+3j(!T(7~19Q466Gh=(&Vs9W!Q z8-X!~8_OGW`gG6e&m&`teMu2h2ixYL(ALxX(jA!x48ke;8e1C2Tjh>eUx>V)QFi-F z`|dP3sZeeDJ{7Z?LMy(KSAlzWG=%wn|LW+LvNfB$Q=sD3ty?GG7|njNZAB`_>09zC zh?V%o;8;|~g;@jYR==#S^=w9o zG3m{Fn8XdI?%K={n+|Y!G?4P3SF=H}k)R%lREditrsjRHk(Um43bh?AJKvGe4vnBy z(JEUeJd)oNP5C0p$%)lS*w`8%*#&dc{b7-qJ49RtYfok93S)M{DhhE}0UQcYF&}zN zHXG7#kxr~al*l1MG%T}F03BPwuM^)VZQ>*)scy3U4+2DWlOTY>5)Mg(Us&u!E;BMi zxMZ^f=Ln+_5jAYQIImf#tEmZrw;VkD^9sFq!tkEsx$JJ&7Y}0%ZRF1vcDnKxv1{+5 zD5#wp5=|_~?DP3Es_@gP{n`LyZW%vniBAqpQsX~R^T%`5`;8-VhYo9*4W-mDX^?#% zy@U4t(KR%LvN^A$s~ZaY-Lqe_33(mDh~z`PW5#)jR2SSA`lcB|yG;EOS=1cM1X1+Ju?iWmm!iDVg`N z*m>79Q!F!d>7B}_LzV8bYSd;)FrGdTAYq-z7UwP1sw&6A?G|oP=f$`yfJ_?a)2n}O z>b0#vBw+Kw6$7b>dyih_JzJ9+UNV6$>_plGHeuy$4_p&kz-Ner>)`OBOKW(v;t>b} z%DG=vsh{hd43H)Uxm9IS_j*synfeR{QDR#vGzcDLAdD@rLDq*h7|9=Cw1uG2(B&K>xdk5d!85gV zP5m~aLrLx#g4zOH-dsocXHY+n#e#~GgzYHONo-Cg(+9K-T@PbTXKe7MC1zkBx)TF1Gmp}x9**L(>v?=-Cc z{%lYT-}gRs^KLljjW!g{YU0Gm%(ccPh=$A;wwnHACoE9xwKSWO92?7=k-F>kQRacQ z5M^*&S3FajHRlks@4FyLUy~AriO`u6)+`QZXkilJ)R_#ASup&RqjW;4 zR3ox!2C}=^Vo>0r^RIWN6XbZtV+8#Nz!Hr%lKplSv-hx> z&^B@{8}YKi7TEOXl-;~pF#M&$h9IW;iaTVeys_Z9=ah4Vv}covBo|j1Pxs@;kKJ}s zr3Mr!&O&}}xQ$3=k&7bL3di}Njqs*(hln*ZR_oQs#$-KF*wq#d1hykQK(_Gq-47uW z=7%9V{@7&C*(&=(B^%V2cKn$ZR-;g98SK>KGLu_+%x}&sSlRTmn?~v1)+}bTd{@iP zR7YH|8y$G|$>zILea^vkwS$+OCQp4%PBfIRjs}j48+Qlsk8EW++0#4Y3hQ8d9&adh zfCqM@iU|q{X&`8>Q&*9SMJ&O^`*ya<4e5LxS}zl2Uaq<{xY2Q@k*=lIk0SXnW1;X@ zZxx0M9ATcpxitmznM?chDWxE|1_7)T?8WE&h@K3=Sj1Z16VZr1vh_{n_JUV!9A=7m zItgeGVSf{vbL&PTHbNd6O?o9rQiY6+3N?VO!4|qHg2SB{Dhk7U8upRJ1INQL+4C`& zpy{nAS~RLL>=qh8C6!Ff-T@1LVk&J}3QMf~dWs~jX&v5s#-|DOA8LVo`xF^?5w}^l zL_F3pB`P|E8wCTMGIP^u#2__niYV|98U2$iNGzO!$24GSj)GC9*hgtGvBqTZD;8^^ z@FVNaS{aRxfz2dGM^OC2Yr}yBke5%Vr z%KQ*5+9xsW!(Kr^NPU);)}KOyj)!z?z|Inn$i==QUyqKylccLO0i-H2(6_dLkUf#~ zh({O&6ioK=oHa3Ny18q|j;}^@lfi_kuGZFW-uNsQ&1DlvNW{g(MJ5)P!ADhP?+N%T zP^Uh?t2h}s^Xne2YTQV~ReNKK!}m!Np$oz21xdcRQ^Dsj8ZG#-V#q@bRko!S~ z*T(JT#BB=M7%?`(0#`&Y(NsXBUTeI;uWm`njIkAR6^4N)ajTqeK^$}d2A=5~yuXB) z*2c)KDz2gjgOS{Q6`VMkKa z<-W13%MUW^)%DZ=@O#aWqSk2Z`RyFr;h;V4;XL&5v;F&mtYtOHB+Ij!hHg6#sgu^g zp3|jYAt)2+L_AGwJ?SvD&#j%FQh@D54KNkqlSPzV8fknV57&^`7RX-HH~8MVRgX%C z6spk4xSh=5$wJg{4_s%?A_*WlO-)5%itU$4Vs%*n(`&T;c$F-e=jv(TFwi1K+HVYm z!s-q7Vjp_Gv>Oq7F7UOZaX3!*b`I3*1)x3VfjxVkZ{FSQSC)i)m*@s6Tp$^sL%YG| zl_Jwj35(E=pghN6@8#S%G}M;8 z1hzo(&YiFgH5B_xMWv9OH`G`Hy+sH`nRD$u929!p*7Q`Fcz6~n{`Hu9nTod4YR~5~90RxkW z94T^>KI~rDiCu1N9#E3h4J13NL%ZkT;p`U;EKY5^ftr(c2Rs!nmHI}|*VMnhvt6N& z?o--_9#!;)flUp{YnG+?!ZQt#2)sVr%rL7dy%sd>|LB4mwvlw=LW~=5 zSd1H-2Aw;R)ESC3sJ7X6Nfw6uyy92*3{zd67aAW-@ZdXb&d{P-mKGL%T5&+;5S>0{ z{ce|k1`5MtHInj=%%9$w{IXn*y}L2u-YHq(`33k;H>0ocRfjU;HwA(G&%341yj~GJ z(qz0hgtP)DmR4UvaWIHQ2mnk+7$nl^IXP;VP;gS6(5``38on9)I!UA!?4F~l#g&4S zlQ|qnn}{Z?RhUSSp$YA>A802hG>p8z*hL0B#*TLG{LVUIK!Q{fR+~)2+x0z4k1P_@ z9UlKA!&;5BY^C)5hUhH!;WrH0Pgjf#J;AQG^`we#hfHdS25xkK0uE@W?R zs{08=ELMvYp@F3wjssoGa zD^-b<>`^Pg#bk#5=pvn{^17iGXHedAb9~$d`^yj-KbNONxNfXqE1STy$9zVQm80beT5EMbXtEqm1;qXJn(hTHD#U1t_D<2zy)%>oD!Si<0_jySOue+ zeq|fy5-d5Zv<)J#$|MTwqI?^BpcT18kcN#vzCA}=CtI@$IVcitn-JjiK9Wc5JL3|J zHajGzZ54Hd^HzV5L%-BVm7K|!LS#XZS4!u8M%yEboIBM4ROuK z)B?)@<{k;kcNnqVoyGUynY6CwhesP3rIqW)rA6aUb*;aYh=m!DA~MI$5`HB7lkEt{ z@n>+9ZnTyJ;I(McA_RU8-0h?ti|8yeEQ1FR+9t|(L(@gfpGD%aQJ}AeT;OGXi*{U1@;Ju+;^bWu86$*ZeCw&>@Xs+*pIL|J?Vy)vVUG`+eBN zWxSorgV|alC@skeGhx-In)5~LZ;QQ5;}Wu1Zg@N@L59|m%{xCrl;bPW8BkmwF-E6G z3N-4T@M#w5MBI-nHMk}t8(FF%QJGd`#=F^C6$a!}=tZVufh!)IjXC;7-p?&7uP%bA zgQOQ)`hjnzY&8k_B>K<(yPVE2oz{KOVg&kwc=SBg-8Z|V}XuM_pM^Ev$I z0jidm@WOipapa$*7f2EW+ajGnZ_~tj_T0zQo5PfH{&dR0-pF(QE__7asJd=Sw_ho= z07)9@#iISjp?tf)nGlI@Ae1#!Q(W7aYv!^x}iNP|Av_W#bDvIP=8K5 z-?c1-7M1?_u1Zcs`#Ru&j;*gC>qZZX4qNJ@tKSiFWYX;Gke{J9g4mD4{mH#ghmIa? z_LG>h#e-io=$O{#rgVryPWE)_$mh#TR*|&&U?ssx(S^IP(LfN*#}0x`@Z+^`3#r&1 z*r@V}VY>880ITD9Ghd!nJ~XYH)w}##Uyd3vf(gSi*dnWN<${aiP)vonP>d&nJv^Fm#0j=n0`QXpu&vzYL#Xj^!)ERCrH&^ni>XoCsy zu6WwG!cYxX;}bdl1mh*gV%AvsnyJClFg(aH2u`|Tab|X>w+h91RCk{nA1shHNzOna z`KzI8*P5^))N_(hXmgJHF5Za%k(?V4|DJKEAeb5P!*%@g-?7=^liftIbROW)E3zri zst;%5>gG6_Un{X+M!H5$w2t038hujZkw?tzciE->_I>+GY6+ct%kd8u*14r290Esc zR93BAd1h~jeqx0I;`j6o#QIfTjOovfUv0&QiFzDvmZZ&vpvl{J$ovfw1>d}1n$o_P~ieefpVO^&El$sq& zQKeUkiK%I`-_$dPtgOOU0yJBbhfhTb@aePXM|mojAXL~x^3cYqKOI6HBN2ce_-fP^ zw~=i~3P`emW)zkVN=R3Q&X%tZcK9C(dd%yd!kZAv&6NVYO|e~fI9}Dn4w&f}9F(X( zpSf+{@vYp7YaYIES5pq*%+glcaN?EPkns;PEXnb})dhGTpI9jaVJ@7ycZ|EsL}E zF=X9lIvMDADy6k=-A)XpdC9~8(~FZ>HMJRLXFbyzv)S6cX&zdUv(v50GY=FPHThpP z5CvYekc7jRo2@P|JUDQ0Q~OoV>2bT*hVWRuYx6Q=DaEFwENrgw92Kyo+ zVkd?+-V<+(RyO!)?xL()yS53-u&3UTF;z6qU*gUC zv9gN`#@Ju{fr7~cXaO$D;_*rCfpjClInU#)1g$kO8HN#LJc3|itAm3g28D1=h>~#u zKtCQp?DtW|+~;vgJ!et~?vP)Ir_GVMpnrER%s`H;Gh*yRY)(i8^o^LpGaxFieCM&7 zZ>8+C5mB2OUS>qTPpb>u_G?&*0Ik&EfVM0Jib6#qo23y|xVk~eLL_Y7{NlSrsCgL5 zKzq;T&9%`{6zlV%60_w73)`3PyS*IKEe4|&P*yyd=dQr<`2i3L6|BU1LJdLXpjqD? zn+;YIRsCrwus#Cl(+krtZ5NlUW>=3cKznJ8>#bs-j$Au6gxsI_9~jDP-dPjGQ=%gL zF^57~e|=CCP4zmaSSUpXCU4dV?~_yzHfYg4H{0&0RL~y1Bk}z3O?}rx<}qAG9BaxF zZyR@Zl^@%1O)aDE@3Q*~PSx~hROouVofTT=zITMz?PFNKxRVQ2S97?vcHR1GQ8tu? z5YTaWr}v2o;}MYAW&r?d}xhsR`y@9k+JU{TCRJX$g~vPMbSuveAPm_He!Gm zTV0SvgeQ)G%W)*=vnI%W{P_c@+Pp(WkQg20uHuZyaOj@*ud~S;x(Y{GVyQ;VHMxO_ zzRDI96zngR%Kx%aI4eYvgKAKN#U24CS8GXL-nTR(wv9^Gd|XCR;qYqNe&yP==4qSf zAlr~;C-&S8$ZDZ=v=T%JNaeu;C(U`D3&e8NAA3pwM))-*Tu;Y@ICmCI=IJ96ZgqjT z&$L&*_~az0jGu#9;n>^sC(Y_Vxc$CynX;6GR{&7D;S#gFm5JPCK(C#&r zOlT?KCA>`Cob@J%CyvxH|1HccE9+Sbm;eDt?zFQPIGx3t?f>$~LZn?#G{y#t^=~sw zl#?pQR13uW*{B~jPKnm7eYJA9kS%%K>rw#ctD%{T4cCts*gMWBUFOiC+syI`MkIK^y9JVt(QiPS@bMll(*d`GXGz|s|>b3jfz?<&< z3{@w(TC47=m8%N+)tS?$Xe1=O#-fi?+#ylfoyB42bqS*el$#zSm{KLTU6@TlPwIsl zoj?BE_zo#_4BWNUiAgZ<%z^hpN;XCgw}!)h&WxCO%&qI!hb9}Cj@BGgc+s#+`|_15 z3BdnhfxsnF08`PpS!t}`S^!_Bf^9GiqGM&$=82%_)!@ks8={`cO-htXGy^NMP;F`N z4E^@a7O3Wj!8wjw($wwSx6i1Zwlkgmep(x#Op4qGqv@H!#YkzqDi%`qzdo~<$i<0` zEI{gH9D1&`3pc_di}aNt7Qe+t6cRL&mu&^hE|c6kNDA-Ww!M_ZaP#b*Tra=2vxZdH zD-kP!ZqzbUm4LjG9{I;lQlaEjw`smlzMFhp*&Anu9o?rg*u`lg2bt3vks)J#%Yz4LYLW z8aE$k$(}?UNszpQ!%P9PIR#ki!027`nT*0eTHtudY@~Rg!Hq$d?S2xQWEVz9%Mu=S zg$ukZ!BYNe7g3OosDLJoZhQ)HV@D4kZuFBdcN4yWR2KeD!GF`l5S3ZCyeIblDMZyj^zrRz#N#KdCyZ5QZ%VQ3e zX?;C%cQWkM=H7wZPOPRI9VOjJthKUhm*a%0d!( zU$a1{(51nz!qIS#16fwxw~xib9^U-VEeUcASiEDD#?HH- zXOek&=A5)V2w)8suiw5Mo!n4RkMs}NL7j;Q4tRpKT9(40CIv@p)6L~@?Z#a`9Dl@! z6tGeLOPO-PhlE$ELQy@BsATB}OMuI3F8HOq{Z&|B{#qd5NJK|Y0XhmaB+=-KiI3Md z3&EOolbHQWo(ZH0kc@a65q2Z7o-2e^IKqkN+W(8v1FeGu&%fR=7WSznB!zig?LtfL z5s8pYi+g4d2P(Y{L^Wj?Z+$xVigCJqB?^&xdXvPS;yxA=-=iS1Ol7mvWk zFh0kTIfnK|l`&Ny)PXUB;R8GPUKpEtY-ckE8`v5O!FSEScjP4szUkly5g#G!DOI>& zqCe3i^l~jTIo*Te)Y%NfxkyJ4*J`>^i?6YkglTq<{y>h)&_e)`rvwev*zcVj%mA(C z>VX3XJWc@Kk6lOd>4l^N3Q`!-m`PfUnwokXJe~I_Are1kDP&mE|KXx;FHJUoKUXMG zqsd?-ZfZBjn!L{bNN2Hh&BN4>rE3;u*4}z*-f(s-%terS881m%pi+wsRBJ-Y?`tL-!nB>NKBT}EgSd33Qh}7ZVVAleINEH zA)x}0Z^*g5f!nEP7X2IP*~*Nmdq7q?4hSQ|CaQbP7zW6SaAik72NwhMP(HlA21NHjqt6NrDn( zJZx7;L7OmU2?dR?Thh@=u8>Z+Y#<$Woloo$xH1`;ROT*zd+JT_v79k*Sw1<;03X>} z<&Ho;iY7eMeODDM-hwKolVKHF{nCc8YN|4sLc0|e1OOxMb9%AQo~aQVM8ta?nX0+? z3F4l)I8>E;!Dg&MKFe{fcx#zMrzLEdFHYt>hbecr+r9zP($vksK|BK8tt|Z7lMsiF zWP|&b#QNrIPtM$gE^fM4X77a`JTAOP@d-T&IHvX#xMGOI1KYo}1OFqw7dhB~pt^mu zBYi%>3nQSJfm=^(0O3g}d(VzU(Ltw~n%>$?ytq)xo*j*o*)W@Nxf=ZpV?nUv`P_ii z#P_*PyJ0^aM%V`SWjnVPN^h${5GPfzwZxNwlDe|phC=yB!Wr3je^v!3ujk>rrL2Bk zaHiY4dx~Y-`@&fr-jMa_tE`f$H?_tD8n!eGC#cw6xmOsN&?h;#N?|%A=bvQl(y?mS zWX7-+S3_UT&o4Gn6AZqqq<|Zum+2DqhdEqmMM48@q{5yYyxH;z&rdyRuVu)nW5V)Nt|=f9uA-xwQvYEv4py*HVK2Og zqjX^DwPBCU;J4l46pH^vijTM@E(a7UL#m_z8mOW0Z|K&ulUh;O=18kof(g%K>Dlqq zFh`qgk-#Yo9uQ~z$j^|->2@<;zs}Zv1GDkJ51KK?>{be<+>DR6H>+g2v}vI5wp!M! zi$c4%@08Z18aC)DUmNn*{=7QStfhrMY3`kJrHou+C#+B=n1orZ$AB475F8`xzJ*}& zV8#~FKnH_$lei;i$4Kup94Qv?_a+4OD$iNzRjwjSKF`7{&365&4ajPfaKX77RF#*j zp(t}q&?WRwy>;VLf))s+3Ma>~GwZr9H{ymQUby$pjO+sa7qlD0caYnS*6Z1r0XygB z=2p|v(#oJC;aucoh^^?U{N#IGxJ3}+GgpJ94GpDHDF3!~yTw4v5iLTL%DwR*#*kl@ z9)sDnG8{rPDrM$8)EijE?1|?O6<=toMHCg?h<&GKi+^I}KDyj<@uQVa)fd~>OMi0o zusAC$Vz~Tr(?I7U)`?+OPxTW%Z_ zDZQ>W!Fu-z0^_5Zn3y<<+TLU<`Jl%Be>|s~+Pg=<2~CTxOnQUb2x%6{4U<1wB&=em zB5K`4hR%B<_t>E*_m+l6cnukeiQN7*ddX@!Ivc7-EYtv;c_`Cn&NA9!-4S;ys=KsZUqzzL@a&$ zD7pCAy^qhx0h=HOlMpm2q%`0}B3*F9Px@-;{m6YbB6Hwld89b|2e4}$5G}s_Y58ygT-~$Ls(V7lb6ncSJPdJ0h)RjTsnJ$iQCQjxf3lbAJA;js;X&p(Vu&N>ViC z>UJ6gZJuwc<*5J~4wLoss+~p*ju2DPk)_Ze+9NEtHSjbjX>28GUs_ z!xT78V{QVU?!?_y=Qg_^6TrslCYicRx#CF{&)nj7wm1J3;?$IU6$Na0QlY^P9q znL+1^{&NyJFD~sKhpMRA(OsZ$R94f_h4wfJs;i{PP3KVn=>5kl{!xL;G4cF%7tb_@ zj9A(uZl}jOYnP-p)fn~F&Z?Kl%uUfWweL&ZX6pFcII~$OPvNw>>65pgEST}@heEMu zdQ`k8?}Ekx>cxYru>dfDD^C@_C4^rTeiwRL8`PuD7e#}I>@xL$*WH7&5PP{MhgcFf z`6${T^61woD7V^N>+3t#k(BL*3z(aauMSZLsz8#|DN>w4LU(1Gp)l$Taj#_7&4DUF zkPy-hwQ3SY2tt?!L1Utd3YOO6Ch12t_A^RUmaf5UoI6o8R5<=@%wW{i(MbT@?P4%i zCyQ7$@e$ef(ZpI!x9=M>$T9!gav&)Do=D-@ zftw>X!GITsDO-#E1jDw!xaI0X< z>u;4Sd+ykwKCKFnA}?jIIa38p$&Be7R2`kXR%TL}I&R!xh8vz7Qn<{jvS%da-T3EG z&QCMtgf;|FRoi_AWyWf_s|n;vrLJ9%>j%b++#DRGv`8G28_GYx*DT6!3}l+Uj@DZU zdyr}YHnujvWvnw<+?q;=FAN+0U}0Tdih^pb7fF*g5lUMW4NZ5Ft2UpjIQJp-0e^1a z-Y9qYtFZ@I{7fRZ)&9d0kmv2fyX86y-}MET%b)iNiW}&w_S0oF+v4N6OA~50S@m^@ zty2i83R(Kcn-BdW5j90q#kMnIIUVt$FjR4)dA6cv}kpx zlEU^S5DZ#Lew%ReD_l~D^x%}dn#6c+A@PUikQo`zFy3-H{jc_50$ir1z8iMf zUbbkRen*-sR_|aPiTa#ousQ3X$JluBOraK<-M}d_vx!F7UkKq=jJhHUCcK)w6t)OT zctF6Xv;;S7zpIrjm#Kp~2<#U(I$ioW=+IZdu8aBpvBvJhbe2#nyCVUk2*qrejwl4i z8>O=3=kV0-d6gL=v;FCv2|=F~;~d;( z$)=k!x1+Q2TKkyX;4658-^8MifEkQeA=((qognx(k?w&-H32w}`Hz}DQG31Yb^1TSkgDSOKKk~P{c27=-Y zCx%;JVhd|Q1AScJygzIGg;N>I!u;ueYzxWee!o>lcvhm@(-=rGpsks*n6Q`4hmU?((Y7AtT zt^X*TW2%0*(dsJAl)o`yy1KXKAsMU7hKP(%+=+)rZc+okWx%Ss*;zoYuBzM)D*T>sWxM& zf&MK78Xh`>ODbN!m|N&o4P#ysF-woNK#*|Hg9(?jJSl6JmwOb(scVl8wznT|CCNL; z^e4g}=RjKQukJ;tbwu{~ExRqW6PGn2_*3KhMl40vnG$EzeLR(9t12t&anc^JZPkL-VT#{0x*On{$J^mvTp%PFC?msNrvbGdyTzIBz>K0fSoRXS5%;rW%pgERR3qQ)ob z=^7+xy}E1z5loqZxzA8Xietot9x_xLxm&*cImbwMgDNRdsz~*vs^_{%P;fAK!EI_N zbpsdp>cb|KY15v9&7iT)(B%QVG~*FL+&;rbx)#5AlRvNlWO`5>cnh7a*1ev|K;Lu& z$M=V!)KPkEzdpavtB0h^*ceBAhU)TrmxABVsOdP{SQpWSE!>TMOl@UMQ(xqvPU z4jI%=0l)Qow%s(NP~zDLgfIRD7rS%=Y5|*vm!UlGH3seYRmq=v+bst)R)-`FI`|5U z`K++bZJjI}^zW$)a-SZM>JoX6?#F)=3TZEY(;^<7!OngvZ^`(f{UIFr8FC@H4!nw_ zS}PmC&BK!c)-0hezf#H4KKJkVk$M?|STNM?wwbCoA4 z{O)W>@?DT!NEB!7(_ciZsgL2T? zc&1c^3Wu1S{9A? zhbCP+iyYCK&GA-_a8jI|Lj#+5asNGz!Ze*X1BJ&DmMHtKBBl3?8Z2MNP+ppIE{TPo zJ==@kUp+|wNu3_SS{%ZP$?z?-DiGj=Awqe>F*gfqhyapj;hrk$zWfrgIPvTtZO(A{ ziWAZlS?~xi78KNjB0z_YiaBO<5)#b}Q~$X?v=?ockkBLKvPiEn1ZhmPPZ=>-s2%CG@Z-m8V@DU@X$xw|N}duH2w#84SV8Z<4!9Cqh! z=bT*E0~d#%ZeuGRa4!?0NQ74x{Sm`3rWf@`s_fw)h4Tdyeg)DU69+Fx_St4?T#!(f zd%p70I^h%7Zuh+3R-!SJ@X&t7qI-#7Pfg3iLu8xv!y!QuRX6I9ln5y5LEJuqHNC9I zi5OpF^fk~CMjPl=RX#!L~`FcQ${*M8qd!nXuSNGivW z;vFZ+>njJ6ErQ8v0Sfg!|?3*P0d_; zoXeO}^V`KA-x2BosBpSCnNMYZ@nK*j!Kr~=$r=WhmfJDq;ei04pPOPl8jNHLXAE)HOTVI_MQg4pJbT!?~n+7xA-S&_pZ4iJJ1If;L9+B^%;JKt~Ats+5&;c9tnBX+cXl^*0 zecd{O`2Bc=D_ykGwRG51QTVsZX3sFIcx#ic3~ooZ>2KRs`D|Ca6tiBPp6kEvL?Ef0 z%kCzvbD>hVfGGfIzSbW?y}he5ZH!=(u8Oni)CsCy^A1qpu~Hg>v<-D?RLz5;2B-k3 zsE;4rA4WKI)q{JC;M6D|TpeY-^AJclX4AUm1ZiflzIr+=u5^Tfk?Dl}cWon0?-fQk zdCp|&)yO+Q5XZw&I^up1YM6K6bn|9c3J?PcK-_^f|Hsx>Kt;8FZx1MP6_tw!NQt5# ziiDEVD5!LIN_R=O2?C;Yhf>lY4H7CLf`D{7ND4@I&VL_D@9+E0x>sc_=AHA_-p_t^ zP2`X8&?jFMTj)`D2dtoK0~T7--CYwyuF~BNey?#n7JM8}SwBM&l%Eeloy=S;=i6U{ z3!j2TM6?uAp&l@uGsG!&08}Mw2!ixrh}54#@*8j8c0}V_bH!{-TYAuYeJ1FfI;IQp zcStD*aJMMH`XqtWbc4#-h`!7$uLRu!BtrsJj!_Q&-4*M)AOa$r;j-bqw_s;oz4mq0 zMHbR&h5sSQX*P-@6p7K0>! z7C7CLt1QEha&)lgK(g?%tBE0%1!%>?wKu@PjLzIeDeoXViLZ+U(uEfl&+IM+Cw+thc9uuihA=TJ7z~OcM98$uWD21WOg`;B7kwGrApq-LI&_< zkuU%tpm72}|C9zrVb{#N`U@fx+7SN{pkgF17M!?jlv1s)B3Oy$+0N#S^l>&3CATa0~??3f%NQ^K@H)%j3Ac4=cns(Sh?x-^) z^e=-MGX=r4Zq+}uc6gv|`v#;0B0YQRo#2+M7F)eRD#O=171RKv00V!*Zu=7+Q#*W$ zs#d5KXe{1}AK=bxGb|gh07^Zp7kU7YU`CMA;-!TUDiRVJs_I-Grw*hzBDBv#yEssQ z?JcDIZgH%pkaVEg<&N1z)6>w@EP-#3Q;pOykr{QN75s~$NDch1WiY&XSGskPM7yLe zyAt({SKCbsDNpCnTQD%RfpdUF~zsPs!})-oT?(2c+dE9 zd5hm+!m%QE^X=DBMNN@st!JW%uOP5yk`}ZG0IN8Rh`6{sl8X!{1ETMwfx?xBn8fy6 z-FqNrG$D+hjq=t7pp3o){hXE(>nw^#e7yyHQ`tZPfkyq>UIK63if9g`vqX2!10*B$ z%|lRSNLhd>U=|gHg`X*AYi5G8`Bwu|Wjly&XfbDW%@Cy8UEm1GEs6yZ)d-$~)WtcZ zrAH@N-zkVvLd*iBs0HMi@#)ND3#i+5D3tzs>x<+^Azh(pps1b{(sKq4bzeXeMv}2I zuL@-M)`I^m;NJQ9QXsVub*0vsPx%fGk(29yPj)jz;6m2F+_W7%lEDip>8!TDq(L%g z^r}KHNhHntHJjoU8X9A$SBEq&L8_1-u~X1&vI8h{#0Lf~s~~#iK4Vyet{W`ZSt`q! z?X|$bGf0)4^IbsSK?*&e-1rfcRpA~X1ZR~V5bHR(39^1rdx-VHr=ty7n^i~fjli7d zTZOb9ArcMS0R1jRq9RW_HjyAZiu(@ti=)g_@()TgIqeTM&e(0`S5xq(>7ulo0~QGK8ifxy?|DCIMo*mKXWogiA&R z1Y9iY>uxrAw3d3cwD7)&$anLifn=n-Mo35qfs@C2AiyY)%k$$GIgv)%5Hgd#U^6@0 zQ4J}zpdb*p6apWB^L@2>+bz32AArOZoXyozK3HAIM7`qo!X0wjM&_4`i!Y!#76&ao zHq{Ecq9qOQ)B5s5zTA0o&m^jp;pfip--Cw*ATbnx8hou;7X;;iu0e#)a4+N-b%2;- zhF%5n7D(jUWIVvF0q3bq@N0%PyCLi$K>8F2;|i}BgQirG9v-stDiYQrUn(JXZMes({H4oyN|lpVlKceme994X-~*ugE}0 zrN3#;Y{hk0kz17CIf)#Lxdf;q2G-+k5Zmu2==g3?oQ8lGIbIhitVQ?FZS#^!9uYCI zHmE|#2Bs?*$cREl61|ZQJ3s)#-oj4&ihkH6161*6z7FC(Gdqd0|AT46m$VgL7mcOJZUC{Bpm`|MdIH&kk*w2fX$Eu!G)>2kAbAAnd$}R z@pCw&;gr^EwgENr<_36{;W%yf%gM;RG0iHui`23a74>t|9)Y(c<8{tI?=(VC=>ljZ z4g6niEq2J!N1g)tq(`f9F|3srZKk<2<1s2FbynLglBd`nXirgLXu1s?$UHCg;+RiP zEp8s0ToJ5Ij*O4tv3um{RfmBR+@cB$5KA#A#uCOa{uB}tO(3_6%{ZwZn z(x3(jo#n|w2m`j83S=!`z6rxm;AnTrCaD!&!;MR!&9W#sdAYKc9)Mc3JSOUdT}LouJi{`Y#_m} z!ewA!W9t~6LZJLlmLf>c23ufYSQQ*Er{bm%r#2Ep_sSH}K`Xy+>_~sSKbo1_W3gNN z=>ard7Z^CJu)D1f!8>LG5d+S!o!c|tAguw(S_LByp$`t6{%}?yQE?J!2=vG44>`Wa zLPilcHBh7GOJN7|erGPam{byWKV=n1tKq1&P<*D>;?l3WKKTh7@-(gGI^T}Vqx@v< zPhwEN)1d4c4X#HARedX=u6RfGkC=q?P1Yj1y-ZNfD8whk1tA4p%Ls9J+UpWb93cdu zp^mJ+{%E!)2Ab%cVtcKqpfKUjJtM845K^}+EeUaDNbd-Y@Ox zZqSN8(+}C`!qp!`eA6f7)$$ zx#{TCdlc~(hHG7+pPimhO}Rw=_ zqVUdF6JD%z=X8aPTm;PVWFei~pzeiTI3X5F+5rhtF?WZguj}8U@Xt{{%q+RMq92)V2*SFt)~)1b+pCD!!KDw{@34xy9shkQQTed-RF|TB zNr;w-ne(2>BmgJ}@InG08JB@YfQv}n=>zf60Z4(=&+ADmM_OP*7x-Tw_V}jo&-1*4 zAB+Ig^H&-aDOrY0KyvYV4iv#k4MMQPD^pOnNbRIgftP}JrYd(DhL8M4tape5O+0qy za83b`#HE2$jX+{6iaC!^(H$264+fGIjMR66K0+5u5K|U;E_|X~?^Nd{^dxv7c{VsQ z%`$jMpDZKb*r11G(AN{m^9<^Yc+|V3ZKO z*ZS;%;5GPPb$S_$XkKV+^`L>^1eA1v+=vFAEQI2E5b^#b5X4VGq;fVO#vp?FAzW$+ zmiHI1TdQlq>DofV!bo^8vZ=Pf-SPsQPXo9k`~qR-k*7e?IQE53lze5Tz6^>!`WkDO zpVNb=jaU*t@vfjshx4&qVwn87dipP`OGvnqiFkHsWE8K81PzaOv4WD0Dm{M>up^El0@!bV&O zztMbWf?(I(9`i_N;VT*~$rY;-cdwu@BVUSSXEd*7zASn8?@efe#G%>!RT>I_>W_!~ z!k@M1+(O4Oc@2nN+H=;wTdctBxImf5%FTgU6X9V4@N)!%q~gb{HzRewAlQg^CJ!3^ zwWYkW_%MHWz;*E(G;!Q;Vqj-4>}Bl*N7qwU$Q2NHhd9{|o+{P5WS-oZyQM?7pk*K* zzIIjU9jDSwkIL_F`p?{1jvL?>pd`Pt`9seDdroTQdI}cjr=)7(h6hEdUq{*HD_6Ya zR11fT8K+vihxB&Gj4$klDAk|6u%0I1K7Ze1QunzAyoX53M zd6r1R1k#}psD8%`Dkzu%W+%y5JB;=QNi#frOhZO-i}|YiJ1zTbS=DnD{+ClZyVQ9eb)XbIYI z2zk<|r`U)7K=`S#k5fr?v}A(?lfXt`L|H!aTA(`Oos9 z-i@y4i^gHTD=%gX9bu;a`m>EDx%pk(x$2{XONFg-hJIStH_3+!{)rOfVhfJ=p%JF` zl_@oc5#opTA8N$8dHDFHr@iKjyj*X-<=3s(FoZIQVPxcRyE_}2`jKd6u{WfBt!||VzTIKYFHdE$VJPM}P&p`Rm;YRc;smuM7O%#bj{t06w+W9W zXV_Z=W*if_@sXtPJl#Nn;Ma5KT&KG{!p79Ehm7HB`R0^7v{Kui=^uMORYdVMk9iN; zBJW8}`JWf&&i}YY%8I)5I6MMnmM4PYeVZ`vd#~m`B_oGoRGHGomf&#L-7mL(vwx## zyJIQAsU>5t*0Q|H)c;mVY3D*%Lv{6`!G&rk`&;NR&on+*G^|d7Q=j7&C$*Ka7H z-=&|8GLs;#N<{Ge{MaSIE;gx`Z6DM&Ocq*J#_m*iaVS;tx49mBs;>ID&1yPNEH8iA zD)!kfS-3mSzc2R4`Mp84)rC__HrPqj0>t!GDb=CXgtv0NtoeKI65uuYLh@E=&<4qsn(^-65we7S9M;Zf<7n9?9(<^{jxN3aPip?r zl%Ku4x1QOMPADJvGf)DV|B+q8e&Q$#hX~uQV^?)Omz_K>Q1U2blwa{Z*_8qsc4#TB z@7!=fl3_-}qt}zItTk4d4GcuVimKrUfDnZWK+M&{r&b{pr>N4JW1{q#Y&r3p`Xfh; zKUc^lPu^)oxqgh1of51yX*iMb?eS~UZpH!m?TH~9-@wBU|Ib{DeJ)%m<{G=0DJ8>Z{w#n6N+js{OODD8Qd`z(l4<}a|{ zT8n&-J@xQ{o^#>5l*X%JMl(ukXV#;s2Lqy{+y3WlzdltZj=KBwmYnQ) z+m|epbz^8o3Ax*^fALqJGeWuNmgO6kEUWx`bK-^M9lKjN`lVCTmP-?%mxz(hntP9c z1VTU_Jf7AeG#{rCyXL;Ja7ab32iLFCq##^l@wl;z_eUN98VaFleVm@yjG-$T=rnvh z3iN`H1J}te{;iJ=T)}E)52z1@LbbF0XF-S40@EHx$9@G7=lycihHa~+L$GVR(1Ari z@ygQ+0VFp>YE3zs0t!FqY7jq_H~ElzwF*j0E2h5UFjV{NM6w}uZw{YY`A{6K&oHFt zkrW@>DgKJq9l4KE;+Z6dA4J+-pF2Y6=`pd$FPgO8sV8{9!}k@tLgkoO5aNlc;xFpc zXxo)V7mT(p=GAWmR?q$%3UEXn&qQhweCP(9AHeXKTi~ME$}2-IeYQanxf-gq2o1JxZFD9VXpC3*PRJr^cEEzStQ>>!tBkCf;TwArwcU#(>kSbh$?V zl6NQ`=)VS!7!<9ju)78VaI!ov&lc#7f8lIL-LNa!|%6j>-SAFd| zq))+moH7ctNc%AwdP3B=78@0ASk$-eK3EPl`owpoX%!cQ9`HdPg^K{b@c+K}zdT`L zs;f40cHeV54Y3~Qtm?f<-DqE9hWvUVF@`1NS(?GN>m`J}%vNacq*_ClkcB&rADXA@k*Rr>bB%AKp?day)fJVswmL8Aube`v17UZhZq7t6Rd|_f!@5@y2nSADgopV{kDy6+R zYTlU^)kPK)d3nm?N^G|MDZ*17;~|I&&v{;nU#_I6n3nhyQ;WR0vN!vLr)EHFzTN`)?V3zsv-h7~_TJ3DCfIBg4PW0cW>fd6wbeaewMqT(K z>5zuZ=*Ktj6m)5|$c8zX>R7+MkXRHnqt3Kkc4e*CM`vpBLSnRx{Xjd@rC+7XE)VUd zqnYg9w{*LmMpa1xc?9{KqYtGZ`P#>KeRfw_1!Mz+hQu(w)$VC~sORBz6|T`Eg!?{t z1O`uAFe^15)ozaudZvH#CdKlL?;5Ob@=8-ja2g^mXlx|5&wm}93`eQcBbQPh5qHko zKZ$9vj-bSId(1>7C0ELrfFpoNhzDS~!BbnT&Is8?LKa1{s|`r8jl7;u!B9ZF>c2}Y zd`0|hUt;3jP+_dcGO9936LIGFr85EaTocdnSoDhSwcu7pA4epdRpwce>DO%!e(O@E z+mHU*mhfVbJc{D%JKBm;hmc)pT+VzPnUH``T1G}YVCW+o5lHg>$ro_8PXB#+u$3Y$ zKNQN40FW)cF5t;d`K4nt?`DDH)c1H(Znk;!+8O)rf|9KU@Rjh=C#A4L6O;O0senwg zVu$oUykAG=_}Q=wp;dBmardk|12WrxkcfH+UPMYMLt?=~89zI_BIGqZxDV}utlpY% zA-}Zuc&a8g3LUZXYRGKBI!ec#EmYLFDY~8%@_dq^-()k%`DCtsH!23W^55H~CR043Y=lbj+eijWJ9N_6i6FB?vNxAs#z(B0=P95jd!S1O9V1 z5s*V}A9{?>$ej2B3jcb)SusEyGMYN&@LFncSTct8TfD%}>EK!>)VWMVmd0>BU0%>Q zNmg8(0BZGvtN<4*1e_i(PKLZDsEd32L0ah>a5PRue*XE7?irMTMlECo%`ri-iurj# zK3f8mCv$F>?ZI-v-v!>F$0nweZY(DL`X@Tkhike!LN*f}Wm?SlV?tU-{3xFiclR;v zBC)h<_!7iV+e=7OlP4EN*Gi9|8pR+I2l5Uj>UPI#xD_J_+2!w&b)mo!(SHubu#Jd5 z&d08S*sE;6joi*xy<%F8WmQ0P-cl^QA00_S3kWD61fgLf`qq1G_}S<3JQY>}BkljnR*BU}${bGdQln)V{gmUQm9eup8d4zY zszl)ok3-KDpf7F8p15-U>z=gh08Q_OP&SSF`Yj3^RL(KT+KMj)Y75N7@G&jGt5rv} zcfWG?kBX9k)>SG|Ci_zr?1)t;;MvH|ui2XWMp)#!fgbkUh7t`v)tc~#*o#-4LoUZm zjUrU|5FKyn?b(kQ9r=Xn`+L;@+;pe+A)oNRBo5k?sQ9@V>{4jq*6k({nzH z{Lg%6D_n&)W_X8}b6HUdVX$x-WaqEYV_Llg1{*hCj4(T4M3j8PBt$)1Y5 zWf8TH8nMAuf*=P~iF4hm_?o?f-vgYbj-X63A<_++7o|cT31l)TKt}=y(DK-+8@1`M z1%Cv*ECJ+QLZu)$vk(nNclGKE<4O@{Aw$=@6>B$N za(digFs^vOqC`C_4)ZY^q9G*VFn4H5-M^27b(kKcXL{y68?b;JxUkPZ!Ep(RT|R#! zf!Jv^h7vys>1|TLGk30~tM|ISWquc#^(}CD($4L6@R!@)kB?0{FoiT#4n$u6hyD`u zuW+&(J+IOK=FNsdqDnL*jzDdeD2mg#R8^~=rtQ-~U<^+|T_U#E|DdEv=Aj@0T(^PW z2$Op72t4J=Y1$%%lM!ArVBt1DAhYaZ;M4*Pa2n0a00RV}?XY!@2y_EAMV@6>mh?YJ z_050!>ctXKuqn-o2S&f>)WgDNoer91!!#UuZt{&)>AAvfC^K|_W|GhqJ5Y+y$UMYs z;k?G`=c|8PPwoHVZ1SjsUg~5r2LIj)x%_Fojp5!&4vc8QJFM=A3v3e>A1VgJ?Nt6% zOr4jMTi%o;f^=cE;6Fy)n`(67AC6=$gRV~9txPPl9_wfocv3bD`+)p0B?EucfPSqh zp1%m=leQ-^38frTHxy>=#c&`4U=L6s3nf7J9}6~bD5%y{O_Of91azS%RhiV;Ybo(a zd~_O?V-;26a}B?a()2`X!pce+U0?=)J8>6zh9h#YX z$0VVfLMUW9$FNoy7B3jlzBKJ=Z$$xxIj%_Y(N~)Zk2+B*v~k8x;Jw5?MUiDyy>P9 zTd%kPYC%Gh%{+oQ+n^v5tc172iRcf+t^*kV5PwU=#ARgrm?||(8vmU)iY$#|(**?b z{`2#1gWi*BR8PcIlUXzFwS@-ph5H66k(!-J0m33C0??V$E*n3v@Pny2@l#=E9Y2GY z(@9;HzX)y3-9_~O0or^2srv5b8_0rod=ZH#R&~^ugcoG z&e>(1n8>SdP37%0ysfppi|qbDUBPd7S8P$!wW zu!=Q43zgfuS=QX5B))RuQq;G#vx7c56PRRVyMidliEJevs3hHO{Mud-Bz$oX?d`s7 z`rpuQ@ZPg4eqFu4Wpyrr`%v&J)A0(dwO3(wEkiE2Y3833|Gj)7FEP2+6h9+GUHob0 z%eNHvH0O*o(Lr*FW$2yfB2~LXB7YG0{ViJf)9BbW`!ZgQi03fk{hPSe`Zaz<>qkNE z3|YTo6Q=G*%ySXduGLQ%1qVBY*~Z$O)4mzhQ5WLh37!^{KU1SY_;Soqotlp}u)6xP z)R0YJc*AhyIk&)JnS}4>Le9O7y>RA?G(m9ArS#v8%qNeuxxg?nBu^Ku0v=6Z+|V5b zZhYCZXg4=4aW*C&OScBzg#xEeoI!8zUis=L97JKy6bkyjNGF$(&&2s)oF*u7Qua17 zo{o1xf_868ult5vSNiTWU1!9-Tsrui!Md)nCo!u2r&&_He}O@z>*_;%qM#=V91*!F z3IglzQdD%z$M-%dEPHT@&xaJCK5YIZXm&EpRnf+Y{ARG#)Rq0R$Zh`XNMC(`4c?i8 z?}8~~WzCC6Q27e6*mG>FGu|c6z0Uh-YUy_l(7&U6DE8n8A3^rUZ6W>qHJ%(it?hZ< z`Hr~$pozk9V$W3<$?7kqzgL&@arC+BW`;W&i(ZZz@UY4;9gvv9GJoDG3FX=}NR9pymZ|m>B-$DQC&Oov~{;Hb<>)5VPAVQKjp9!uH_dy{(|^@ zR<7m6SU5 zBgR!=Y%_H|Y3S45I!m9!(cb&l1s!X?Z3CmkHHw_ueFi2aGppegjC3Nny_*pe9CkQ^ z7ArqUsLo$GU(DE+x&Il@ro;n|Q0O{CB3c=h{4$y3eRini>9FAm7YX9<jXR=9H-$a-d|q_xqsqOr(aA?>NIY4# zPQ?$)H$1t)6TDLS*mdEp+Aw<7y;vAf67qZzJvbm=3U?w@nV(`yd`n?MS)R+Tj;ow0 z?sj|I`&fuFIdE+~qq&e4H{HUqp#Fux073zYoP1%9=qO8JZ z)}U>`o?C6=rRnrjRDGR%B*~qR0k!H^AMmD|OGB*GnEg_PRgXq)zu($m&%HuA(!KY& zdi}tEM&OG#0V`*mkoqhiXOM%>5VLa?b2rh0FE7KhEr8Z54@0~~;$f?#?%LLgy-(e~ z4mmhpOJzyU)lxf38v`v?^D5dTaC2N&pEKN0vb;PX;eWD#PR2`=0o7%w3O6up6}{o4 zG@vBC-`sscdjFt%y4%l6QSVF!dq-8qxSL{yE7&)$lsFELyHi+h4~5hh5#CaiDU+QX zU))KjZgMfLZhVqi|2Zv!qDcu=@q5MVZI2o8zJB-2I5@HKTIS_fhZZaU&0VfFTfK9s zX6#W)j;{L+%}phKA2Ex1Md@#9KEJs_PU38vR+7!95?-3w5}bEZW-A+2NBv-z^Nr}0 z6*S&ktv|cB@m-d8h#bS9W6Zb7eI1qOvxBzOq*~<-+(u6cRT6pT5igAw-E$rOM)0uD z_uJ>RTh8bKn@U}0!Ts%zA2@tJs)2`2)knHUUA%C#73)9eEpuWbHy@Vk!o8G^WW2!| zx^3_Lu)5MUr}%nC+Bii%-zs-9F)`jAp@tGTf1+ydJ|@!;SMw*S0=dHF^3c8ju5s=PRH_p_)X@p1RM5vw=` zl+xYB0e%~$YWa!|{oe5-OuRQw_rG?-aqivUcY(gE`{zf1KW+57{EUkGeUaw!iO2{0DO3*F7h^s!iUq zaEcskr>^@_JXRVfPp$NH4M&|=^XoKRtb9_~V{S{wx8##BEN01fb=}_N$HA+VE%$Il z?=6LZ&mL+*i$w$egYK*jvX5uf9&66_Rbat$!9v(l)U<8?DdwCe_64?h3b zRKCig+`q>OXK=%s=ioV=sIqkb@o4_>XLb-WV!@&Wh8TUJ;P;gYd~(VZy@nY#&mDPz zImzex@tcg6s)fXby_ZlFI=Jc^GNIUW-L>9I7>Q~YkCHW>xwFY6#6gzNy^al)GjZ|! z*nIn0?e#k`in$NoEEtz+fm?m$ID@g$*Fto3;QG&y>}<6bZwt~`?GEf|f1nsV-ShhI zYpq20a}32O2~o_qcIrJ&d99DN_Q@gcj3xJIJRSbZde_jEN|vEa3|X$rbLxC-tLE@? zl1z`#3svILi$$38e@PT=aDzoj?!El4JE@~+Z||TVWH;Uyu3gW;mV1FSs6<(5X{O52 z`<7M1s5yc9hmG}yMrb9GZQ^yjDgpuy^9X+_4Og{~`P5q z$0TmOgVR@k-gJ4NcYY}YbcmRvNLq_36t9Epb0C~@&K%whDT{LEp}dq7v3>G-28DOPnX(_T+yt}Z`{NupwkTUREZv*?#klfK<`R7g+evB zq~8~8SloxxmFoQ0Ys6QbIwf6HZLl1Z*={M@)y-D2cWp1-E^MaWTgaZnA^5{RIEOwI z2@A3Gm18rf{~E(h9`@lbG^{8>ZC#edtLn2bmN>0A@bI*1+?2cXgVgxTdn0579}3wg zQ5c8nrR|-pcH{cKdJ7zE>71NKIqsUi}0!u!Od#0 zzOK%**_8YGyL~Gm7>5v%DMPg=HU2s`GYC0sWB}5Wf#O zrDfe;F(0VA!pJFsUoQuvb=yeXxMfsU|MN}ac;!+;*>LRiLk7`3O7JUrQIY4@%hD$Bd|XbDHJg$^xNF*dfho~UZ(*Siz#Qu{`R0l$z==2bUl z#C25+uVy5En)Z1cUe%)S%eCRzEml68pA7%MQPZ0f(LA&L-nyEEGS`UWaAQBo>fRcg ze3=-f%aLg;6L~(*K(4w?@|!zAB9`}OJ*gHWJj!_89XAUPZyC$sEt{Imo8T~Aq36TR zs4`>7+#)Bqq4`bI;5WCS2bYeXIb5B=*c*I2!Rv)RerrSe4n+IzEYFxjfu?y^@r$ngpOq;roNooeRRv4Z8HVU*x}QBM{Ps}cB6R9e>(R=|MmT# zRuuOkN-JlS!*a}6qnJC(w=obkj6f)}9|09NxnuJhyB$`zxQ4piU%MM(6&sE)pe*Au z>pG2}?F(4N1AD+zQz=fQQU+x}w7s|-H5`PoQDbE}?K8%}vXXS29!(4~qir?1aod05 zSq=8Si+4`%@Jx2;tD>5uPd`0rBKC4^U@@y<+5bfvw$*#tt2#N6_PX%ZJe$T-4=Z&` z3*`m&!O&mF@qNiO!8kN=XaZ?5GFe9T;@;Q-!wboi_(Z|U&B0!6u|=>cEB)r2nrnW% z02mAo!9~d7D<}=PTUVz@`n;1$L0?1ViMqRvuk_EJqbfv2i`=rtaJXz>jnEjy^whYNXqn!LW9__#U&FU_#? zRe~FOSmEBXsb?!48#U`4i1$qvRj~t+<@_ylikj?}k8?=w(0k+p5woEA%s(rC*v7#n z3Wqh7!>fWlRRG%|lC`*Nk`)g{SJP5e&G!C5v+% zVA0K&W#p8h5@AHCp=R`lKO4s-d6bQQ+{<wPtt4 z!e=(dMUskV;PGcpZC_+s z`!FR0_sZWR0=Vr3URBU%pUP(L+uSLkmaJ2!UP~3XI|r0@ z%Hc`x(o>n>nMwfjb||k(k~Qj^BYK^qy06k!e_`6uKSVY*o+r?Kk>rYyD@L~`tad_~ z@bjGr%cyVOK*f?AIMxpl3!93M)02>)hgCsq3q%fe;~tKN$$i#%RW%}rMp0JvUi-00 zU9mj#X}CqRx!dJt*S5I%p~eMpT9p!0ZFRnkm}NkbyyJ=9 zUP)uRtL~v`tzuMW$ZzhJwb`SZaG>@78Uw!ad}9vw3DWJk74zJj;^=kvPuN!02xR)9 zA9sxwm+}E-Il+32z(o)Ay}okXUL4Gz$RF*YBC3u$Phlc)y88wFOn2;*`-e%i>4Syq zsCz>Fm{|fmZlC(weIcSrYk5i(lrEA6n+`Y1AN-;Rj()E$K#siC9-i^sN&b7+T=-^B z&|P-aHo4ffU79N@DB}Gl8fS3Kruqm6anLjW9Q%wj7^|jw>#uLhuArMb$qsZ-OXZ(^ zOC!f%azn_`7Oo}dp#9)|U9sK~Sc>H%k-+k8|C8_%rQK<}t7xv=21TcRD zbOK5oH!9PR3B^AvDZm140nC_vm~Xu9@o-HknHVEvU&RPdlWVXg)Vqiyr$H-DA#q$zF~>DGU}Ng zzOLOAdN}*rhd9hx!UW5)CGA?eZfY(Co^OK)$1K+Xj|KZ$9eCAxjzm7%a5zM%pw z$w~#(j0y-Qgje$@U;oIts2f&Y!(nbNc(Au`5BK&iR`_W)HPg%J#H`nWGO1^+*Hj3m z@I}hXetzg2c{5#m(|u)(gnT|qtBkf#lHqLhUW8bD<>ATCR!K|Z%|>)_XSL7ydH-<1v3;!x(s?JRatPe=RXX zA@khmV#am*4_w`kg?LhbR^trTnU$~)4e>LweC@14nUHtbm; z*L;;-3HpYd+O-SEcSjNM_;d2}f|Uy?GV*D0-DX#C4Tr#Z`m%f)XHbFtJuP~>Gmbdu zNnxMIwh=}CrgD};yf0!+3-yIgCP!0v+~3qKjmnNGExvN#2Y`BSEs*h`{zz-V~Hr|N?aLL z!^ys~v;8K4vdmawtG>bC=jR(Uj7z=W0TsB zS-xxI=$A%}hGk4@sART9RrvAVCG+@?XNAOa$!hsIeMy=AxU%8kyUS}EYZgle023Of7`P$al>}EJgln*ij z6;V4Y1yO%nH7$Lvx=6)2cm~WY)OH*)dV(>OIfQuycUu=Nopv5se>qRcAbN-PL={hy z;}Eu$P;~@V+2sni=`rHOJ=*w}`5_SeW^${+KIxHn`73%_JRV8&RD$JNo7Qj2&uuO; zD1seZ!Pgf_Vfz$L(ZaVaV7eEVO^33)w)*y7;QpHf5jBv(9x}TVk2xbFaeeLMiNq|- zT|G6Dq#CfK@qe7nEpCatp0CjvxMNmMFw2d3{&=6VTw*`mVuNK0ysD0RZ>=>)Yn4H3 z1LDv?%d?)`()!o8#|Z0$`j@7M@>=Yj_!7dlf4_Ohl$7~+&&pf+b4m;f{BQ>6d8sv* z*S*=IPP{xqKu}~J^CAxjn~}1Nskiyk!2C3ZdRJ~HdHeE7yPog8CWYnr!1`8JndQ9$ zk>?zBAo6VUdTlqpy|8@AIlkciM2emd-)+|4Ja1Rnhy$!V6*B+3D9oL8$X^UGXU(HC z#!Auba`X^thdctahmg)fQR+JCmARkeyw|0>orSdcZsxhU6qP#;N;T@`0TVy4t#A>6 z<-vA|ac%q4+ZOj`E^Q42fNbFJlgdl~cQjg5B>8n-Ij&B48I&sQ19s(Ghts$#R^aW6Vb$5#$uCQTi)840 z(WS(4TbZWwmBI<}JG;=qh!xFEOaf@AZf&^@|Al4jV*f}Pz%rbD_2hgA0&JrUSccLq zz1NEHlhBG+e43A7E;g5rzrfA%l}(k`COdJ1^X&YRR^zIF(mDb~{0H)B+5J*NRt`*> zjOfF4iK5!p2b)H(EEBYq-PmML7q8aCPs!Lp((g#z>2z%35ciHtr*c8`(w4Z!zEsdo zIuxH#tWgALjPlB68a8t#OOW-zqQn)df0;PVbUzx?HG+KUa--4t{Gewh?5w9thY?LC zipTI^l$t-I@L1ic{{5t9Ha)0D|52SWd(@4nH~kJxskk*RTCR?GXJp=$`@eA9Od?3x z5!}cGDv>PvG%YW`T0_N|y%fb3xIcT_79V9+!G(6Kf%lP7Q}s_8HE8{&a&MZba(mJ1 zUO}`Xb)p1dt+>rhZ`mP?Ne(AEk|%#anavz)&4;_lQ1iqdg#E>FC^jU<&VO~N{MiDW z6``IAhSvg9z;OSzScoXWXh1$W0+kTa1!T`hFD8FW4HpmAC}aNpNW8ya3uvOSW0zLA zQ;V<9ae@R}fUc7ZmP%w~k}hy5n#mgGNP+Z!<>0=aw$}ZuDF47(0>=2*?kV=PxLL%z zIZeRy@}1<_Fr4#-g|QVV9z_W){G=n7nNVHe;V2~k25e6_f8|=EC%W8tUDi3Mb@Vh4 z(LCd!$G21GVA-_ne*=9oM%6QJ2!Nqp0EYUN zwV%`YH983qQ>wPPnJ(Rc?9;7Evq8r+89~;G2QzLW@0^phasbm~p3hTti;ob^Ah# zgX?X0Fuiy=28NL`sy<$wVHTfyY$;~7W+fEgXv+Ye=%+L>#HwAZdq`ceewt?RJUc7r zznJNDDc_%O@-amEKtS!DmMY0ZJd>iDHd@9%*+Fom;!Gmjm`RTkcidwB^1RRR3Ip@0 z^gRwZlIfoMqC<_rn_)kNuYYh&_bv3w!BGKE%a7qN-fcVJX_-69LaM}#|AX^9mD{%) zH<+cbaT25((CH$~Lz#y*PI28!Mckm+xP}tieQ}fC>TXZ8caW8N#qfG&PCL3+i}8nK zC*qbdhdn4*)JUN`Gal_ME#F{_BgiH0ba`{Szt9`k(x-cEX=tHECJ-F9JK=jH2xK2> zPstE)qKtY_TDPZDi*_m)#{g2#dyyV9>-bU7dWO`ikd7ez+UzU5{!LvRSS?i%`nBfH zRuA#Lf#Ru7=5z1;6E$~Pmc$eHIkmrg!2%NlM`gFS0n4;O#^h?MOKtCwg@I;srpw1- zt}f@f_cWjPaiNMe-RGq}XAV(zOqvY9qUeVqgo;MVp@oRr%R=>Yukc=c8$9g6@lJvy z?3q7{q6j7EWw04|9n*z35gU82AUXDb4|Ei4_*h1X#!uyUp z-=>>+TJd$;=7!ayKh%$=SeSVk#qEH4@ zQPAHEA+d>x!-iKeKT8k5mMznv@|7p{oDcwK(^^%Lg?I%yn4%1XE_Xl7&=Z)hNL6a& zp!ypSLSwAX!J>KT$UX)szkh&$xk7NXxf=aTYB;BY!fJ^e%%mzPn`KTU-kDzg?d_l* z>aHXQteXl6yhLaefzrUX)d9NtdkIEx21QM61cVTFsF@?{MITl4H(UP5gtPZ?)BS`g zY*l+-Vp~b|F~?fIbf1zRdZo3ui%WF>nZ^ag^P+C``3QiZ^b=LQ>0ALTTaU4=m|Qxs zOdk$3cZ3}{kXrtDdF3EBU@?>NlU&JCp?S&7J^Cj&G;fAaN+t7R<|qjO(`{Q)X#5-; zsMBq(|IL5@hMMKseNrmk<*!?(dLPsjGlT7D4E}g2RUWFpEDaoU-rl}HsOBTa@AZ4w z%{v*TKYAqV`itluxPQ`B_SKg6q5f*p2iyL=IqjzERPXmU??T;p2l9a0zeHU)Kruhs zCDdrn#Ex&i3f|7z5yNE@N zx?-`fM*ofOhpGHKLsORgx7IBVFx&;|LuvFd35YR8P?i-%ANu|7jZH?(LM`j_04ax0 z8ma?NDAg>5ak;0&>5eJLo$U=sj4IiX^=;kT5L=Qz8}hRHb~J!Fz0$(74d2X)0Q9Un zj?QlqlY2J>8iMF}3tkadi5n`vICVp8S{L)!@T&F(AviqKC1X^QE*0wL5~nwQz!4L7 zxI&S`&bRed_pSUjqG)gbo9`Jh+=ZCy817&96FNR70y(>PKzXiB8!GN8chAoB=DX@k zAD6fho$>kM@<>z=zABZL^P6?#T7pGx2)&BH|F-21{XU@cAd)v;_F}_A>{*f z(bTH!xAsYlnh|3Q5Q~{%;fw1A_8hpql-G;2N$^ty$5qj{_Mua8!ybk}D z(WMXwT&Zgh3mtZ-w2qdJn4depw#ZLF`BUU+;eEdiJj(7P{UPbu@1i>i1TGXR>cktG zc|Cqo>b9m^HI@CLu4M+c?{HrHx;APe#QXE!somXTLt`RsfXPcJZ1*E$RTucV_VB-v4DQ|iFM-v+){8T2+T!yYf|SbaFPE1}7`Tat+{V$b*FkX9;|xB>w#x41yb--g*=I0` zvzJ1H`o(y78LkqOv|66#Vi;N;7nZ;4+k6LIIueSjoAu+1Yc@*!q$+Amrn%ozVh?y_ zRmdMOWiyACc?>l~B285iQ zC->KTD;lr%XQPy(!Jplna7lDsk?4Wpj2q`2(rxR`mse4%H9SS*c^FM_UL3N^7|fC~b8i%lv#LruT7ROTjS))FOu4>a()zNJm|@GL71C$HD{F zXo>32nH9q`hB4cy^OlnuixNUUavGr7KrYdP#G*&7ejuSLP*QiCxoX`h<3fXOVlco& z?PlhnS~CB-Lrp2X{H(j&S_y?|)a?5D=eM#e3btr^rM6hhb_D#rUyTe{YiFV&A?&be z9dK<@u-RP*Pm2*XrM)Hjb=LQxadQfz*{2iw8W52Z;8II2#TVbrY@6~?w0AKT@0V>s zZZ-CtnLicH{wEZT(eL*DiOS3iSN6<9iQ|E`3vb9NT)zS;l6N}$o8Yh zGhdQJ$C_&bXB=>7h@w83Lip=;h%K;>&N+VHG)mUJv^ICLf(1*F5L2 z$6dt#3BS3btm$vm-fHpuu3FHu3U(ze(F)Sc#7w7F++%Vio`jg4?;Ur~Ut-7ole=Gwqm84z6J#@V%{GDfyICPE9;IPMS#AQOw7nMG@){ud%Z=jJ@vK=XTfVesO-FC z1!W$pkuZe5$Fg#D$2-Z{8dPP%ogNR?K|KBsER$jlIJ<@JQK((soX^Md9Y!b*x$fm#FL;m3HQSY6`-YO%wF9PX{LlI- zH>qg$PKA4aRR)mY!e3(QGS>IzqpbYb3g@xoE1Wmq@&s0E%Z5AGfiC z{Li9PJlhLX_p~=+953TvUIlL~L9Tge=(_!Iwbdh$U!+g&5ZwE489;U^0tsZc z+ohMRwvT26_z&g3y>gSZ=CxBoTSHeaX)YN8Ih{SK(#A8IGk_<4TZ&YJWWF?8$c&S9 zyA#a$^ibSkUrW9ln$Ev})EDh<%-@530hVy8>n;VR7Ch@~JWH81wKnbK4G|Vnw`^BA zH@n?VND4{yY(@}Rma%SIJh%rEpL41%ef~ukAIrLh`;E^YclP8#>7h-Ver3Ud!=JNxxI|A({QlZvRZU=+GN6o_p-0@R6A%u#cOm%ciVke5r6hyr3$32n zt8_oqdEG=F#<5+p-r(^d6W zvWKKTwh2VfY|orBM11P)ZUmT3UI1moegG;-4yOF$(8E5h4VeE%)B~*lqwBllss7^s z-%?bRq|8vM6j|BfQbd^**(=J(%E-FLZ77vd*_(uvnY~p;Hrey)+L_n7#&z%S+4GR>n{%v=e*B&jpyt6dYyA5o@6py0m;%yP@mOhLEt%W?ZhlE4VeK;hj#@lwdC7Z zhOuh+yR5#U(VecD);a_3rb@kb%xdA_({QQ7hd-L$rVn8K;C4#DLAB1R2HwnU86Xt( zg1NrNU8P+8g0TtvGX^ECkIa4tS*`5@4?4Y1J;^#}zvXKGJkX_=>AjYB!X>(ha;RHHXo5w}FO6DcH6?|W9) zki3>mRIToH!V|ZAaRnQk$TES_VS75UUF#x?+^wWR_)MRB$uA0ZQsO`<9u;%m5*c_SvD9T|nV;6w@Ap&~rau?8Y*M+p^FfTH zI?Si`RqqNPUBi*;eG#E!>(qsHCcg7QbDQXn_n&)h&f6Z3w zh3^o^sfa>lc{a`6FDYdI48K@=SuG|5o@eWwmIMN@K3i%7diMhYT$r#F9QdD)0|6 zKJM5Mz1lBHF?#<=AMCAJ?MJh=@P_`9|7|+M>H}-6h)cIR-VNQN7T~pJ;IZp?<9~iT zttH>mGmpkw=W92rL_<2UokhxG_sfVsXUVywop%F}VK1aAS*XE8(;%~%bMn01^@+f9 zVwH~|jz4DTj^cVpn4DOrbSl4d#{g^#o@Ov4cm*mJ}7*^QH*iN zPGn~X>1S#$Yint96@cneak!x1QIir0e)t3nx}FKAyqvLne#aC@EeU|g$+}2c_x6fF znnPW-+@-^-C3sA;Jc>74ig(@ULto$FGT|%XuHboEWvhU$u@uWw$Eh!?!AIsI$@6*n zw)X|Ot8?NI4d^H+s%D%2tPfr%I0z{<<qPrvgsR%KXM0zVJgjws0xMv=9*awDp zY!0QE>G$JQrWB(*QOs)ab@J5y)8I@Ah3>%+lxy?35jT1vp)cOi9JlPD_?Z?C+E3bM zluKP1yDKYb_)o}6_g^@u@fi zdaSuEB6H;fGZfzm8J-_|4el%0Rio;64@IONB7OgjKhAYv?a3L{Wv}(JS+n7~hKznsKC_HJ<_|p|e2Rhz zi)-S*wxBz(RhSX)iFqN>n2nF5Djo#IScpDJ2Bu%BKcdWm1U<6K;O6Ud3VHMe`k6I$ zqf=mtN(#+t5mnTb={L7GT*?@VGJK0`>`2Wf6aIe{5?r+}b#PvvbAJkPNTwSFVng`;&N#lPmx2FWxphyqF?pC_$z@RRa!zvB(_^ z522e9&<#CZ_S<57>ay$o(>rN2L9d^O2V1rh%6oU&w>Oi#G_cC%JCVc z8efUooDW4$P1-LW1GGc&RJ7B&sVSdzU|qej=c7}YjnxQxvX0Wkk@usy$e!CfRqQU< z`wHN|f#Fzk9}^A^dheM@&Gx;G#l+awr)dlHl*nF!{7{U&XL+Gb?WC35{~XTM`PHaW zNN~or`4iHHnJT2W{b4P_=+mk^y4nHaJG`tLZ@6))a`B56Zd zjzlu3VOUo_2{Agh&up%A8Z-_1Jr##VuiG|SlfQe8ys3i7Z>$KmiN){jO^2!jX&~W* z)+&*z1G-T0UH#V-qnF6`VjnkIidOizAw!17bHhOa(2#;=U#!P!@z~i`{EEMRT`$vq z1n>E^iT!(q<3H^(2X7^GK&merqE>S@!4;m9gXvZ5=s^>e1O_N86y1@ZU94&$l1SQb z+C6*}=>VkTNs{VsyM$J2$ThozI#~7+>NQ?tAOL!t5)k}o*F$}|L6)&e18%O+bCBvs z^)$BLk+sh8lGmw))>{v3Zw;*Ns}8#ozhV1(cQ%(@U?saj&F1fU*m0blMoL?ccYb|* z+3a^aG^aqBWTi8v?o)|A-$&8EGQU@EsYAt`uRoVremz}4Q9L|TH)qJLs5Hb$l=JEz z;|3(V2eqqc8l26-ef8%wVsOOs(dP}Ww5D4_7Hvb{aDUvtQ{zQb2jj;337Dq)kxbv= zb-727L@7OfrJH_g=T^whFFa_haj+ zkE5HUZmBKp!8$9#AZ9c9Wdn!^jj#att3 z4I5xi^xCpfLY)VZqUmCEzErL zZ9S`BTk+V_%=5M+2@#b2Hw(@4;3@IJ_^EAOnj z`yG!dq5KP$%h7yH!J?=t?0_RWw);SgP7GN54qHPE z69A@D()W?>4IwKDIwbOf2^^g9P>i!br8UEfu7u^J2 z4g>|54odNFg-Mw9yVDgu-52D0zXqnHh;36j>*HiTKtSy9ZD-%}1iXnuH5Hwg#iUvs z*bSupVo`OmV<)V=&c#&udOF=DLKH2 zpi|uxg{%Lr`S0kYwH$U`h@sOg>Xb1mcL7fHLFXyO%3L+asS-(!QCG#{>yGGQ>O z$_%Xc=U8^(`Eiyb)wJcg`G_>=aY6p^g!{W!vmyMzwV0%aC%U8F7SFjY|EQv;AA?7f z(S?O}+DgKBpk{>1QAqZbP(g}#nc(9(rOwLrE9duyPWBwPyC`kA7OF0R2T3R*QLYd6 z1IR191VS8o`Us8_j@=2e%eM9!5mgM7$zdDEpQrb$2k%CC7fq6pyMwQORU$wdd)w^t65o>5_r8Av{p%BsJAx4FD6C>=c)F~MaV2)@9C7?|RpeV3 z5Fa^8ll!n6%TDWw-vER}>*$Qc6C>bjy@rOim7PJlZgw^G@ho6aVR;Oc;HKNyj?i7Y zLSSz`T5ulU!V!P>A@s!j^$F>mhdl8ZoDC{%(DH*N_kIM6i@8dp)T{~aEUK<8)Q!Wt zSJ~^O8u?lX#$$WN;EPP0EPOPb-uwU?e|iS+K@M9(fw}AT1|KZh*7O5{Hhx7?=vV-Y zjQWa~G|Mtth+0*1B7j2Tv~my|BD-?^h6h};*b~z@_`I>iwq@VTt8$@pOt&c46lZaB*8c331Am>=~EOLsX-}CTxy1B@+wRQw*OBzMShn zL}AMK%scqCReqz)$}%!=W0_O2dF~>{aMGytEiLZP0Ouj%bwm(E^Ng&yC&D@*tc@>| z;{s$)GY5D3e6B`Tt2fGakk1gBUIW|Wub(Ntefv042;yhgX^Eo;>D{@-gpl!sg^N_50#btAKlauhopBJ z^7_L-=Pw*QeeKvOIBMA&7Yyl0gO^{wJ23X>}!~T`T0uj`&6^>2I`Z|AKA9&50 zugP5VOlC?(9aidbzkAYVOGw`N-3aYAY!~7|w?nB+w@j53DVHvNT@Pw9d17&yopb)X zqF~#Fa3#YHae9YAW}(uH_*nb2^0-KySJ{TAnl3CSSe6LfB@HT)?%y83ug-fOsSY*0 z!UbVVorB-h`3Jvdxw7`&KMkLT^`IC%@YOiGRycTA0Pdr_D-O)2u>M^v_L0Oz**g`+ zNehphn)!Y~5K`Zn_rGU3*>V^XuyXKT&vmT+U0$U_w$;}zkn!n_<^ry(udk_6m?{fO zhH&V|9)m1&MWgAN@bWd+($d;oU&t|iOJPVx7YV>5kLn4%mzEOc#gg=fmVZx+&Frsw zrwVD~IJ8=Wq5`N!?@*Y&?E83YfJuItzXo(d0CuzF#QT`59 zvfk>Hf(LB-uAFq({xPtzJg^-ySr;?lo9^#Ph^&{|tpZbbd}X^CcX1U}1le+oZ=j?7 zn|uY#eh#ea9jSg$I*;RXL?eBq3RMe2EHz_fT1D{i9 zWCD{=fuw_vOZkxZ=NIYyCGNwP_P-9}6%|yipj4g@1d`^}4PGHgdU!!0tuxTGq9-|! zB$LbMeg2Y!3aXjNZluF2T0s|@@EC_#RN;1!MO!dneohwDz$=muxatBffQy4{`e@IR zW#MM7hf$4@&Pl1{4jxM;o{7>jF~(@lwu5!wpMhsAzB%oy*38>CO8j26>2dPNPhgA< zu(TAWS29Z6G?P4zRBI{9pp6#~BaXg}Wnx!7yvuG-lEojoEA4K87LI=VCgIwIZG0@B zh;RGy>knd2DI$iTq4^e$=CU5EtzJ`pT$w}tJe}?Q_uZ>lYROTl+?)Oevz51;Ou6n= zPOeE;09pJeys`7Bp7C!n!BMbEaU*lz%bTpBN{7w|(o+tVCpoJo7dUM96NmmzgDg~c z^J%CMbXWO4Y6GyzV_rIZN$YOur*2@f`qIk%Oy8vd%B1$k8f}oaBJg5n0AVg}pfVlj zjb!;exQKlryvUZ|-N&1hkG(}u8At&K(3exHt{hq;!Obwk@QOBJRDWNexqYNso=Y5H z?T&fH@)>7w#iCz>jKppr<*sSWKGLr_i6;(0vSYGJb5*6~MxO)N^MDlr7`S|4C>iyU zfx~23QLq|NU1bDOu*vU(FD(v=u(-jBGe7N;C~x+J>IBf18{3M~Q%3al##%U-)^&Tz zCA?>g=Gf<*@X+!jw8ha>qhDAZCdHvem*HVHbNq2a#sK_W{I^^A!uzVTarQME-zhljs_Vxv9J&-aq8 zlb8%74deN)cmu4gC`1<+rc#F*onY{5?Sl>TlM%TY*|wanozogvOCBS6r4WvrF;<5m z%{yyd&|}Z)`0s07T$oEDRd(c&GVgKW?>@%$L6;%bL#bC-5eBS?be<#CVe6@u9PHct zEKTu9@Nyh+lFY~UcF#;q2pT#@FfhV11b?HY&4(UYw1PM;zy%)F!F^V0bg#mqMZtlq z|IzfUD3k#V4G8HWf|A_>JnCY@t89N>AyRAW61&HMo?}&VqH-6!h`#=Y8$Yh}!*;+ooMwZ!its=G#M#us;u^(Ze#!0Pt zhZV6Y*;J<#lJ%c?!O$dIfRO2qS5BaZQWL)}x?jZ2h81zQ1a#SSoI*Pao;(jVx9JTj z+sGrYiVh~L5tjt|{mHwLw1?0=v6wzkn%Hp+x`0g48DjL^7I3=&phS>DruOW2#TO~?@V35E~mf@k+&s>n`7&KjZ&)`U`{T`1A|wD8*Axb8B5+*t)=^j z^05x(lAu8>GhneIA7M;M;Wt8ICV^CU0m*esm%~uWQ;Mqg$_Xc-3qRQbCHpe7vwwvF z2*o#$jwE&Qv)sNB`5KcRQ6h-+vHkquS#g7jnO8X06`0!T%?3>>sP+_G4e zfA9B&90=eorGpS%Zml`6n53oO*>mk>&LA2Gh^-;VJk`hw7fOt>FUzgPLOG4S_X~=< zZ^lRQtREz~j*EU|2Q=5ZBhCb1(uJSns@!nbPsVTaf(O!S>`b3FJc3&BappOE94d6c zkCGZvJ^k0P>*r=3mpMIe&_$y45~~VaEohUt64d7gGGEpEG}&$eDdNxv_M~aiwmz1Y zgyGvQ_jXFE(_qDtPD1FTkoE|_R^7O&l+D5>Hw_go-f|#Cz&K)A8R6i^Dh| zAFFR{zE4(e+Qu(@zfPJx{3cn%UDLq(*E87{9q4$@r%`N-2}p^K?67ewnAg--YZ)3* z3I<0rv%l8o^R^#e*Y{d(^>iU!Dhff~sF2+P&%U@BJ`d-wzFer{sfaR~Fd@kpMnx~w zQ*l^O?zcZ3U z=<3MZz|Z~-{rO_Q(W#IiRu%AU$rSF9eD)L6h{X~85IPcLx^;bTIZ|X!cHFWt3w)k1 z6l3%`v>_^A5cL8Ql;-(LQB2_C13(DTpEo#AFin;_?>#EK?AsdmjBsW}Bl3CUts_v8 z;sL}T%fBpDbVf(2f6jHuhciVdgpohFH({R+Ln+kXs-TS+hEB`+@X#u{Fk!+1o??Pt zDp^C5Owtp-ybrgu6_ak#LcsRyT7tMZ8yYF_W@AdWF^01fQgs9|+iT)P`Nl9wgqh0B z;d)CcoL>yc>mi%>P$^b;loii@xJVJKBT>Au3nfid6HbxvB=Wrgr zN;JEmVrOrnQg(1bRE)3Q94!bI@;#iyJW^9Am^tpXZFnDpI6UD6ieog{Fkx-ZViAwR z;d!#u1@C>@Ro~4{!7Zzg1tc9u2g-a{Evr_(jF%ibQoVE$kc~g4Z^{_^j@)T*CKC)k zR;%z`OUcZP*#VG71PYmHr7o&%g5lyK8*fGj+JNOc1m&@1DsHVfrE0!CC`wZGYAl(T zg{0K%_{ETh$Av20B+G7J0u)v`E>E0DY3j2g{@ei?r~ZB2jWGaVqMf8&$2Cn&VM@}P zK5N%6eb_I;Xa7En{Ivaj$6zdVo1-;8!AeYdh>B4H47^TPaWCd>-wRxFG~wU+u(?d( zAbMN@Auhmqy%241qX)gb4&~!}<04QIIpX-Yxp8kqAkMW6e+FYMpyQ2kboRU=RaO9_ z`+(;F$~qd|??0m=jVqCp?8HseKwQq%8dyBN15!XG+qXfwc6m@qN$C;#Mg9Celvqx6 z_mzEU_Csx7ejS4TNz{KASMo@88~$buS^)4y?;85C(2`@Y3G0{|*cxF#tOoucOLGYT zk6$K%x;wKK{eH?(Jnh5?jmMFJc^|N(k8z8qX_|DocKiCEkT|wq$r~{;C!N$|m%f|h! zGr_O0pLZZ-OqQC+HdanS0nXzMWbeFH+Y>Vjem(%im|eNPQb^3Zz4OZyjmAHT0=VaM z%`Uca-6Leqia?#>A$c<`07>Mqtpy;1v#3UStVNd-l8PMqSPfDw$Rzw|#2$eT#<;4c z4HW}+v+NT^WPQ$}v3Y;quzgLPoiLzqh|~J-;A*yJJ1s%x{#km|>gatHO2IjOU;~qr zDTFKu^RG`c2hA)h~eQvD6Rv11~06>dyU`0r`$=PWxqMX#AaLe)rv%g@plbZXo1iNVxCy%oZO z73goN>LlBAmt!xzs-scADrlqqzjRTCKX1lU;k^ddAS9`CrjCt}j()PtrevT-VcM6X zuTGhx*!v~D*9L7O;A2+4&Z2aojhy6~d``wD-A|BiZ(GC(=xh6Brem-CAWa;wgRaTp z=zIP_paaj=zdIq|8>9_bAsckW-+|R+z_`LAfD#f|ypu3MbGveJ10gB?1~@y++g)R2 z3M2c?+eXg9n|V!i!I8Sg1QZi2uE7X1@2{~s6jS}~i{<|DGFGFnU&7GW50C?RFR~OT zmcH4Kpp(oimmzp)v+ub-*Y!>`U5Gw!M=5`kQt%LYe9y_@3gYkI{FTW%OpyBkXE;D8 zck(5dSAS}U<{zR>*9Y9x&snfZ2gsM?3VtRV)X!PK0KB)T@mqY`XMDL$; z+du;ai~dDN2pEDW$vUi@o;J!;k&y5%LNcNMq$xGq3b=7n=~o!Pwcwhc749UvK@YME zmV44t(3$1?;{ZKx@Ini}mLiC5W?u0J^BQk=xz`D8ubFZ&Un$sU;^)4!O|Mg#S#G3z ztParVdmXhCVqn@-`yw{+5qERKi`S0e>H0c4pQY!;m=U-+c(^wgJZ3r#(njuRly14Z zV}@bLm7`K~ITCX@KT(n9L9aVCWM$%)UT_m46bzo0pj?Py6+4K-dfkGK=OK>}l%Gk!`T%r2>rpmRu31dX%ge1YzZ&YRI zffwT3!CUHX@Okips2O;GEZ2Uxv>3NFi_cB~k7-|y$BuK?=f$sOxVJjT zGrVGV)fMO^`j%h9;xVojkl^{7b`Z>cQz2OF>6v?i<-7O^h{qm0!HsUzsl38pHuo(a zCkbA)HPL7zI;3A$#6v)35nvZZV|q>jqxV`-kt>}2RPN>oRyehYkhLV-k5Bj!^atXt z)khc>cyN2cV}nTSo0_(OD2GsS^uWyd!B@~j!%>O!KJ1W-Bs}LdVB)|HmFr+PWd=x| zca$DP6DQZ6(s`ZcFCKm7KKhh;i&R`DhXst%tRsimjHy=R`LNSk$$Aw zO*UV~XKXPmu#979j}bfTB~Ov~Yy=(TR>Qf|!8wm!%hcvomzvL)*qTl@@BVTx_d&x4 zE3ued@G1d#V^33hWAwS>&m-bB0|hqb78a?mVu+d&YRivCT0a6Iw0%*`5TF%kS%N$* zYF^`EW-Z*yAV}jqUqGltk;2#ptRPo1H`?E71f{W8IM5Z6P{bE?h&j;=w)B*4?#@P0 zhgA)Y@zOK*{w8C_saR+AfWSbR$!74B=#WdN8ahS5`x1W@c3C&iLXCx&`2AJIG=>f} z8Z$tBbh(s;0Gjv&^z!l)zLu+H9=Yu>lQ*CKyZ8QMu+obnoeMQFFgH!Fi6F{p9MFr)Llx8 zJ?;P>97Ju+W(UI;O1MY1dWz~A!+76j5i?1*D_d>1n*A}ecbh?l+_dy^^rff%%m$~> zLl}kfjpfz;u9xnN`DfeuUlpp=Z)a`YCs$5NgNP>aY)`fcr-1j2N^)oalRP(UOhbST$!vS%CIK=Fz zEH~%&L2 z*`nd9^Qjh7BD;6Yr!3zRk~`pqVo31M1}|clVLd90gTaxvPMJe^;?~n<0GK(v{iFf2 zxj4*}fNL!s2j95;Op%w6GYE4U9U1eRlp6NW)SM^h+TB55SN(3V(i>hr!ROFFFY3EQ z?R$*L*!_>R-G0J21y4_28DJL$kw&GO6w1y-H%9d9o#V=apbF5t6-j?tmpgl)Y>B0F zzU26B7ScVG&?USLKEg2Dn~j`k3znRWbl)CC!hC6nR)h91h3RBRSP|@4NS?cSg4E?L0*3lsq3$w`ajo~0bk!`vuUZ?MrMX50F}&amH@2g7;bwJ3{XQFT~oaD zgJ#N+i!fyb#fNSJoflumIS?;X=ALl}b>TLky*y~sPJNRe+5Ew6A?utr=)ngHS_wa8 zpbAv528KfiFRo8T7&u>o3n=j3eSAHMf2V3T zl=4mmwa6}n%-;O3gRx3AgzS>1jEp}O_8Fi`{ryX3mNBNI^Hna=K2sa3Rf}Xx{16~a z=DP{oLsNiFT3DWH^I6X`?>HMs+#ET-hoZoShS)cC*}AyyWY4*!-^s28uKo+wFYygv zW9=wLzdQ>1RONoZG;=pRya-Yf)$dA|8+qNfS1e_>`&aUb6~5I7z*dL@Sdmm@U2oen z#FpUUk^y_H*Dxq|;}8^*_#SP?x(g(UX-4_a!}j&yHQu~I8}Rx_tOrQ|Oy!;o%z(J7 zA;%H!*@yMx=48(H8u$b18F?O^I@&GvLI_ zu$vUrr;fck<@C!uKF@o5UAN5D4(z_{Yv4TTkD2#*cS}yeG_f= zm79|rU1_kBCRh}c`TRfuNF%#>*Z~W~pdl^P3frD@$E_rArp3AHcRiZnd`U9CH?*NX z75ZBdpkBx8J^YAr_pgn(<4{&c$NSYNa?O}r!`~fa2(diu)Wlb|vx%z3ddGTpx0;!> z1P;#azIu+ldGXr$A|%IDg0D~cW{X3Rt5oteu!I}PxnX#*(GzcOTw7(FiuyjuKa5#t zPMbbGc7W^jiLb7QCA!Xj9+OC{wPx85zxP$WB4{U2-)7P4!mE?W?{wna?#yZe~@8^+)v1dMrzOwr*vtNqYPkd0K#+Jp##b zXI8>c9~jPZRPcEhehLe7nZ59v72(EmNvUL9n}3`~1=@foH1;rRwDB??zQglrST-(8 z{OWF9f#ByMQL1VAVA$4l021kj^fsSp3?twqr=G&m3{b@F^;a|Djd=N=BSJFsGt-2% zl#AHFlyOyJOZ^MJervITE<7&)b%ki5YtFxn!l9)vU%4t>oD`lo%E?r z5ZLCu;LKjt`sLo&LY9}t`BrzlW>if6Zmi9yGcYi8*xK(reP@=-41Ao_eJ*fe4|q7r z_~3{G!uYmT&)CDFO7TfM&(kZCS>Clsh2*&>c9t{Um>7*A33f~t5^dUdt&9;xSs&!` zn2TB3Jcc8{+yVDoHP2=pCb=LpULGs{F-A>QwPxGla!soK{a2R8B_@|fT#KnCpqw$! zHSiSDG~b8=c?DI`87#0q9rn*4nJ4%q07wdwswk zBtT)c1niLwAD%`1;tCG%qhYFhc7VnVs4BY8Jh(Q_ZG=U~(D4Q#FaRFCPA?nN;@~4Z zva{e;@5f{uxtdpgJKi1jI!N@)qQ6C6iF{QsEu$|#DJU!1_j2g|zk9K(hf$;o^r0SW2?b=hhjA0N-C_rh-@k(0em z6Hc+dIB=vR*hgftEupF#!^CgMOvA(DM|J*AcCTgmq$O-6 zN@8<7WGqxuy+4fl%xmAAL@!5FNq33{%dGe5=9=A@ zE18NH=D@Ve)7928nZ(YJ>OJRq#29RJ6D)sDfAoL$m`=*Rlpc+t`-J?!&inQKi}HI- z=63{WAI5Wjk&PP@TYct)YQlU8^ef(MxSn6Wd&EH!WIm^bQ|?~!nEb6G5XcoQ{Vj8r zU+>#F{)*M#dckD?QzRQZEXunQS4Z!J!Te59!xMArsr*CFO`T;>nne*PB!@=Td8wj` zk9SSk^!=PNI1OSwDt|{dJF4 zO>3AKNQ-q+#`ZYuXk)ugcDh}IJ;vWFq2BOj`3tv7a7EZm-Uo}}|C3I(e5_XwKwec1 z4TrTgpt0aB^w~Wv7AxBF%+(FZ&CQJiMXNi%wvRvp`xnLK1U`p;E5h`sIHPiF9sE7G za0Vl-UA&9pAi$|~f{VsS4tVym=WdsGM2ZXSJWZ%>?wR-Snya*anA)Gz6S^%)`M}KV zY@?sH!YBOjpFx{9j?FMG^v6x(dWuNBY%KUnMa%XPIR{=w8QY_#?I(e~v#}JQkn_<7 zr(>x(+((bH8>DNY0J6}#Y*;KgK-X?eL=V^Mqh>D65}0NCM?wyuDCX zw6*o;6({`Qa8x^?QotK{I%u>Rr5`$xXsV!%Y^q(7LwGXSF7`7Tvv^#iC5R8-^!AQllB~Xsu zIR<%On0RfQmf+)=^#@#&Ux68sQkUIXWeG0%`{irlrULQNctp@6txikVVOdm0lb`Rc z<)8O73Pr0-Z7-&&Axv)bD8+8-(9=YGYEzeG|AXt1yHtdJ9c|!S2xC=i8zX7t0N_m9 zE$iy*lW$*~YtOCPjH&8>&rU#BELBym^8>miP7jr`ju7NC$0*Qqt9i3mseD>=bMd-K zne|#};bi^PK}f#-vhFGLV6Ou0;s=SoH=phQ{!(^HQ)Wx}9Q9cYm8P+^LWE0Dz7mMI z+Cr66`kwR}S;}PHzF5O+jD8a|_ZW+=Z)3e)Ig=W5)ya4gmdGD+Clkow^j1+d06F<(ysA;kcq$W7d zp$^>PFA1b!7r(Mi`K0K|jtdUnUclI9BLEp@iaQSw4IspLUtE?l7A`LN$x_X(I8Paa zZBig%5m$9#f$OYnd!wM^27 zKb@lY$ia&mq1V4P3>vZM?O<7)yHd97;3lB9kpGbs(^M+cE5D9I@!-IRK>1xsvj@HF zt-0$@!Q5xVguO~FN=JVAl1d6p69GZInjWG7^Qc?IZ`8{!^c5InY7cp>vQ0LMjpb^S=s+J6HHMin;mnVGsj$x`b1i`u3QnNi0PS#%Orw z?3ekf>wi&!*V>|#e>WLJRC*2e$JG>$Lyq+=?#)G2JM%$?@WPdF7OgeVw7WPF8*#4-81pR^#PeD?MtA|hbxlj2n#b&2yvZo?;aOuV0D^V5(@6-9!n0p`>K$_q5vsGKV`z{xMcGiP@Ht3PAG2MFF*_kKXNey zT-LX-;T{X{jWCDv_XA8dU0quIy)n_zZvcO4T4%1PsEC@&YiphGBsP({tVy|a8<-&s z&=%2Wt?c|tN$+%d4~^SktNrsTIdZ4|SUc~lrcC*;aftllvRoPAGeh7)ngwPKj*$h- zBEUKB$nBAcrh*YnC8idTXka$rD?!7qgM1OQ#ND0CQKcAl0$=JC)0uUghzma7(#*a- zMO%73=~(XIcWYt25rb(xKym`(V97{q0#Usrh|Zv8f;XyS(R(qV{<2A>G;FIQxbR6_ zu-7Qe-nnqBsv&5w~e8rHB8uSxPP-=n+gOz zrT3<` z8`aciK#$d~$`Y5H|J#fFyU$H&GgN#xOk-E7d`<-0M=HmkgkJK0I0a5KO5bes%O6Xd zC2tWNtQ}SLuU|K@^GKW>?U5F2k{_Td&mEOnZQuC8RCx>#2Qlcr0-N4CrphHhiPd)b zv6TcoHbV-#EP!9mP^%%%k-hVCT3aZnLoI{jz0I+{_$ltFsi~tNe(t^LJ>2%2U!#qO z$>3JKMlTyX*{_^fxIjtkA5n#!Agr5vz0`=%m?MB^y0LB}9>geJ9S~Bw-yYl|pdH}5 z&4){$5JM7nw;}poBR8Y2S*i7>CADvv>SeJ%WfgL#ONfQc)#@M4f4b+w8`y8;wYGD| zE_uRn#6MBeCD05d8>}}lF{2k&V-PoAPAaN}6bP#wy3#5oKnPm(WwbMN z>3Ov?tY)LP=Zj2;;ZLtIyx<83VaABU2ZyY~UM?e_SFVgv_ZEuEy4CO*OtYqEZyz~Q z{rnS9HC&-6o7v9fqvnLMMN)yaoY)s;3aVy8PGJM^E}PHt(HxF7^u*|Zu;4)^#Ns_u zMSwt5Zwd1X!<{-^q`%$&lIh&c0KHszzg3z|;hso5%UQnF*;{wANai>IpLjpwCLk(- zO%+7orh{=8v&xqn`@Av3Qm%mnL*zIXC|(EHpY~iE;=j)2Tt1We(e#4wph(ymU7R%a zJS_a@1v!3VT{QJA$)DV|J?dKE`X^5nul4Bd6%*2N{%JUn8_K`EKJ&e1AToCZ3JspR zYMd`u;`DYggwGeCYXy9SCYz%|20e%>Gw?ejrR@{dcV>x@0>!~830z{UOa{Zv(5+JB zBSn!xU-m@t2iDLCN*Gxou%MfFriyIw2)su%<7M4rOeS8AL%#SObUdb!c3QLY#S4((5LI(Vb#)gWt** zY$!OGC$6ved*+?=^;z@Yj*JWyel6@mja4?cw6F zASqNleBm{irihsR5OYXKh>(cL3FoQSKmuX~Am)@3`xC8GzF0Jxw`!Spz=tq<#6tM_ zL{RN_dB7Tq7dH%Q!=^Dmm>GVuHZU)oTno@W`?33x z$1n-Gx`GQ5pf(=Hx4E|c-*gLY`&*3<5GH!sqy=Py0eXp2>y3_@WL$(XCV2k5lZ)R+ z*ZU&tLpp`T&uto+^t-kNqWCTaQ4Y8#&-%!{-NbjF(60VNt3@p~TsSoQj58}D>P9#? z%Mmmpj+>f|sJWTa^)wKO`C-V?Dl(0mulY=olu%rSBvJe!X6f2E@>v0w=G1yFe#tW* z#oohs!E{rv>__-cb-y}@zh1<1B&7}1+Xd9F4A>AZ+v>>^ttYMd^IN+$6bM|Gts-{J zgPx7ELCgf4w6oA-MJVyucU^T(1~Dght-pjbLL8Z)A8%iDv0_WKOSw!j`UuGI8c&K@`P#;ff8|f0f|WRbXf-W; zt=|%3zDzZ^}`-edA{}q2h2n$LfnDT8hz`Xev|UH%#lvY3p`h)&l>(skV8q@QO9>Eho$9 zyf2CV5(ThyI8%#o>{dGGWz$UdOgHe5#HKl8z_Ad2o0bik&1+#tZ~2>;aNM~#4w}xq z4(z;D51a$wcU7NVK2qHc4kqt5Ym_2acl{b3FI|oLY0QSM!-sA2tR`rGJ*hLaesgGJ zbl_9T`!`d<@;Xh&AzXxPK;P;{+u(D|Rn%0~%Q|r2C`&l@3?$9BD=O#qiUq)3#`LmV zP5!+2i{9%gmJ?NAESgAtmIQ-b9uIpLP%z+9aQ9{KZCf86fcddic$14aVwcM3v%O3d z9-gZjp1vx7o(y*Lq|I1~V@BX^$Gq8Cp8ZBR534viMVR2$J&oG)y{WGVf8pI%-QN98 z1d=uRO7A%ANAHVn^lw<3PYBMscbV~nJON+;Bt`6MYws$Hoj=jCuR+GXe@dx-Wzes3 z%@V1{lBr$Tf1kp1+TLS7qR1T;@Beiq0=YS@EI*MSJgh~|YaH5Jd2fx3fQ>)3^Ks@{ zl!C%BUqn%buf!h20~IpL(rUnX6?u!Ik~k;e>ZOg3%^-LEU4^{4S6Z;RJ%c%W)|_va z5fIhQbCtfx6WxmIOFcJh=k=x^d5A#{xm(nm2_ac~6>{g?B6qjln-1AE;$7vYP-qo_FH?BUHO`OFb4TB!TaBYDVc2sAXZO>#~|8jvJ%-hngglXTKT2{O|* zA>DH=fmQh!el*H&#c7CY+J7gw1>+UC9{qF1KAli>PHZCwvT?*;AWxHuff4New8=bb zaGPs*W{Klx!+;3~pIf0S_HEaDrT(~afn9ckQH)lK8SjPNVBnLGBo+IA)ZG0`NynJ+6Wm{nNh0*$JiTNM?7ss6|6=Uc=Cw@J09@a;$ zI{9azMk2tCB^`(8)4VTye5cv|wlX}0Vq@EP^^3$zyUf*`Bke*;@$~3*hZ}RQH@BxA z^$f~V8`%_pSkH}#(awH5$f1u++6^InG)MZ0=mOyKK_HD)3m^R>Vo%;#Z8mgO1w^^M z^Q)^lhuR&fPq8_UJfWvUo#H2%AIgV6&^AS_-YYE%eu)#=)E3H@U z?@;ev7qs=7Tsc%B015y1mz2j*R{y8WJSH_|5Mpg8vT7Yl)>73HSljvNM-G zew$rZDLEW(>=O7#`I1L!|C>=+ihL*|5z`H9B+%a91gj@3 zBEQdwe{CoEecx>j4VJ72_`a54o$Nq;u1vjM2Y30OICdfKSr-d~P$BgSD7f%WjqHPl zx}c%9Z-h%VRJ)^dmvaLpcPr6W+5X89;4Sqi1!sO!R@>KKM_xKlg<#uPy<=O2?kJq> zby%MwndCm0TkNjR*tIAs@bX0hw%~H=qn1x&px}b@I5a64q$e`c<5lo}14H5*h>Itvm z-J7D_F|tD(ffl?TuE5f*CS0a_2da+`QZEXLdsvi`>-%jJl+<^<;2>yt=4(QB-#0Arc>qUp?3bTd4IU+DH7$UfBT18k&4YuWj^BbBJ5!`xr%>?T!^Z{G z&u^)xQjOB8t*yo;-F*o?HrlnLeXxH^B_p5n=MkY(2|n2`&`2AzNEehP`6ByIPH0{Dl!xIpZNiQ zOs(3(YL_tf@NJ!Q-~MTyTHv1dRX;bA0Eb1$4z-zFv5pwgZaW5|N`UzQ))p9c=jRCT)yIDb>DR zkBwPTl+(Gmi#ofYC6^ex6=F*{UvfohqWJJ~n7@PX=|Njib}Jmy2r88SGA**;@oW)w z&vI!gt|f|}5cX>RcnOleNG>4sP%b0&1Kw^i-Dx|U<>|Y=`3-RaxYaajgskJ_@joWh zZc(6UcXRQY4l55(cHzPn(iZL=BSMU*J?U#6PjS&yy$GcA3C%24+T*JRnA?nuyBye$?3)f8m56;m6(LO(;0=YXG)tF$F zYicx0vgO@wfiv9hI}e8N8+AwRNKIF-?kScAut7;D&}>Xf0rTN_*lJw5zCLdA!l0xhTg3%bdkCQ0 zD@F8FY#@uu*2V63GbmbQJ~f{Y$-0>Pz}ug^Y?`lN!cJf~f9)RS zPUIw;%XWk4wbiKKkAXdpus6wrsT<)c#w96CnNOF^g?PKJgn*6fwN4|H(q+9$2%7QK zrzD*&X|LK7KEAb@b)^6L04obKn^-SuNC0_)4pt!Pp$#!p{qkx0*4Fct&*?>L>_Z;_YZ*C`ynATFz1 zd);8_b9ap7{}dIKR49ka)WUUfjLm#ZOJ)W88Hh>H^)sj^OgH9yZMQP00HC|7^(HUa zpsPpn%aL6f8=d;kI)Jb&2@rYN8G2IvJ=iSgeAS% zN`9jIi%zloI&Hmg$lHs`mH>B3UQSN{`Up}1Xc8+!>|*v#3Nt&;MDdY!;YOAb6A=)z zhaBza@&IN2#1=Vw$K5K+XMydJ>NJiL!4XgFN068CR0QNc#ppF5Ep@yu zI66dZX!@4Gt&n~`09m&DCL(g>_JyxA6r-||JHIvr>N$@2T~DH9qmVfRI(~@}^1KU_ znj97^frCY)#;f6qeBP-dp&(2ROZW7IbT^pVp=MQ{lvNBkB0&6~YQ}%_yWH{`#4KhY zur7`k);f+m0NBZ7;LPrk{}-tGF6`n1ghSr`eCCTG1^J-JTRB}m29mh}Tmv%?S)KdI zzqA{$g8$|Pw$LO>nHCBL)pYbgrtc)(_E)}?$yYgG^~8#eIGDuV|Lj-yYSafHd}2l_ zHioCNin|Yk3#u%_2KIrI6U2Y+`(b2F`~~t!qVwmNB52$#{bC@A$_4Dxj(>t zG@5YDKr=W+D}D771+%~Z^35&PaB98wJf4*N;K?r5%>PH%m&a4Ny>D+RolYbT2vJnZ zm`ur7iBKtp%%aRgh9cA6olb~Q%8055!cH@0n6L7(ryp>~ zcfu5etiSLB{2RM-Ue7bqIgg)je4AS0Ynl0(9-e^$v3A04c7S&_!Bbh|ikA49vc9dj zyyRy%EP+$sSm_W{P`Sx*`Ax}8Mr&zIS&wXHb=vpsI|@M_r|XIFS}3~hWMYa}RXikj zv+r97Q&`l_jOFFP_loGiNEKgyw**kIZd|Ert;<*0zEaL8=@%d_Lp_|Xe1@|ld%rmW zaH4yE@!l7YQ0CsOWbW1FM&Bm+Dm-tVDg^MF>+64t-X(s0x!5J+>$*K4bm&-!AN69h zU-ifPZ;fq_l7T?iRckO|Nvl*ohDD@Mq~*@A5L6KUA1lr-sI$G>KcrnEz48i|WWA1|pU39T#Jm;Pg`O1v z0O;Mc!+DiQa19Z+8obj`C0ktj?>qYQR`hJ0+-J$cmFA4gN+~}cbEO$}G)pOMCfpa~ zb83%VBT3J;JxGN$fxZ2&e}oegTG3zSq{SpnzOf@jA{~+*5lw4hV{zbS+hnvbjaRoM z&cH9lqFQk)CC_#{kR#^zuaj4Y4{v;!&N+8Cl_Yw|n5>j^YQ2<~k=3y#bC83A1|j)m zS&+{zTyhhK$5MrPV`56gFKl%fVdSd9@52TYm-y$CD%4E@Kx*#e%X>_T2CUQd#Mz!l zF_Jpgnc_xA6*&qmWD;RV%=yK@IIB~o^UJBW48QI_2{cQ3~A%s z!?UYrOYuv(r9%6<@nR^CMaC?8T)JGl8|HxofIYg~pX8}4Iq#UKnS}t_A+FBb(DZr^ z1(mbZ$Q@bez9TjiKq$KX74Lg;ZQ0kc&-!27ZKLGpAMj#{ZGO4^KN(pS&9ben%{lNKPHWTld?1)xup~vl=0;d zmj&u30knx1n@XH!p&oL=!2U?B$8hEs(>EHwOC%I}j%n5hw%|Hj4Bbjx^#DpGVh==E zjay%0gbB^A=O_zB5ivW#r_wHElk{7$=XX7bVC#FwjOA_~%eaUn^JENV@<^7qJau~o zu3-H7r|nLeBacA#iS1_kLP{?$57)tcVIv6iwP=JIP3mO<=Dr4dUAD5v_B>hM>l+p8 zwLgn8R!O$6gX?kbL~Xsf&)^{7g16w{NMPH~cgJFPoG`Hbl@+l7xaH(BVR~_KpW2CP zt&JkueuE(v??yl! zmoIZyxil;GtDG=Or!;6w_U359FIAT>07Sy+9L+K=C3!Ca5`1j-Xe*S{_S81@e z=f`{V*tEZJqC^OP!>!)DqG3IMnN2m;^1=|H=ZPAsYvGr&HY(NsNuee_43>`(2cG(B zNEI6lt2NBS=?D1YfpaKQ>OFlKQif{+hpHPl23zvqVBb?L7uud0%yv8|64$v18YZny ztu4Er^NolGAly2HFCOe7lHnZ1{<>=Zj8@I_6nU&jxY8a{|7+ke3z00`4+|Tv9En(V29=+R8j^TEba;<)v2a?AFrxS3u1>q}DJqu#z4d9tR>A!Hp>vZ$Z z#(y601bXQe<=1JmRcq-lf7xm}uBh8Ec)rXj1e;#)-nkC}i@Q45Ct~Y~aR1M_>hjLq z0w)xt6txt_^aU2TPf?v!Rv&3?wRv%3@O? zPQY}MpUSzcLTg9nAy`@cGm%_i#TMYpDg@`uLO{vAO?UuRI>YOq$eLYC2Lna zV3cD8QBmNX(dO|wDZUWZvEsGW3?N;coGPL1?|r}+Xc{PW#Bkw5SQ)TIPp$06E|}iX zl-OXd`UQnYIz+n@sO&Vmay~x1AHK&*>O6Vx`mfZDJ?D#y>gp9)Er#qpz;NjEX1DVN zX0`YcUS9mqa4r6E%hDz*ajg{Hy^JzbC0adtK)MwGx!0vrBX3U5H(u?Jd$7aG8jsyR z?{X;a8cLG8mZrS32jM_e`A{G%ZbhBndQQHL82o`6j`jQpv+9V&a>*hlZNq!F-e1q? zW7$;Pv7OBPx25{=?(UD-ncMK=)<*umzAS~q=Nx{&ODwlGBDXIhV&PF{Sx+u>%ebLi z+i+og=y}^tYT8?`_R0%f z*!ktMGn9%kbYHSPLf-6$E8y$2FU6kAJsY3|#cZ77tyg}ZxIdmZUC!R0V()1^2D9w| z?6*=-8SJh$6NSZ+she_i&)>yU{M<2=?pgf!+wp39sfyXOj|1+A%7d5=p@MqM%AEIZ zf^;eNQ2@K--Cv|FXcUAUR*m)M-}n8aMgRPr?gDPg+OWV}fOXcK{`?a_fzUXfvjLoQ zcg0H@8+Dx#EJ-8uDUBMfxkW+M-2s?!6}Q3+n1MyzK~J%h@=A!CoTbf|Ubc46uio=l z_so3$WRWxyCY5=S$64@;K6q9}xkcj&uVUaIOdkMy8dyAJzVlmDm5KA z&orn{Szd#KDOK!R_X1^V{9SgN38rnr%>fDK05^A1la;>nk8?=#P!ZWZmw+^dE=T9` z%WO_}zliX>T9Z@gBbS)O08D$m+%Vu%bPP z)o)TAA+GoEc1~+|ORTjXLrIy52r7KH0`CNU`%22nu@p_AFjGgz85S>DAS_RV9D`>3b~=OnXa0gb5#axj%?7biB;5@wOiOAa)=WN~T0e ziq=-7dCM=i%|5?R@3)VQfM59Ho3?hhbX3Uit?QJ6eDa~K1Y%Yz6@4iLBPY66?c(L8 z#VH?oj%2Nr<%i5&f@XhHBthqJ^xqvVkxoPI&aY zh*J}I&Y$`4B(_Z}Y!%0nNx>7B0lWssv~ur%@%P94%6v_vUg@Yu=J(^3tJ(zn8r7Z6 zg!9fEo~Fd>vaIj$r(uVu9Y#BiOVMn!!)&!=E$d2`;cyO6HS6Qm`Zd$sGz)%frupr@ zbn+mu5T1+%_V@RT$jNb{^&jQ<{aCG6AxH`lH@-#R=^|_%+(o3qNkl4-rK~P^1rE{O zXAe-)cN>YH2A-`rws0Yx=c*VUwn!yo6ZzzdEbt30PhxRg6BrIy9H#tCz!k@N2TJ8Z zfgh)$c>0>yb53Ly{WI9tXn7tS-o8Rw^7*pKe|ZT#z#^;%K)R(^00Rg>5|mnrfg0wO zu9+;v?YB&fW;Tyv_(W==FH5k?`^ely)0UnFd0S@br8d zUe*o{74x9z5p(M-T@hJX03sGE`uUBPRP|kdK6EJGXI_vlPmM$LtZ#yb7SUk9@mEIw z$LjXXch?@hy%kkB6uGIyQy}X`(FXhuA&WKZPPCnI+-<#qv^h$|wv~rdle3YIIsZNw zs*YsA1dxcW%^Ty&jo8d5XRAbAbQfLp{(g9-U@l%bfYGCu)}c}`rxb0CNV{g*_Tg6T zDu-TR#|%++ZA~5sO4G2Xi(Hah`gJ|as;Oqhfx1EL!U+L#Z+0~+bE@$?lx6A?>Mt*} zZB2tnB=1uEwQx$@P&-7{MB|3dJF1w?TMJhQ}FJJ+MdP!~8GKj(8Hic-ejPgJ?Z3HxPhuvmVL8?@NrkUsz}xxrng5ch8Ak$*bilL8W+dWF&xY z1M4=+bt#((HwfS=&&tIWgf!wAZu7r$LDp*WE%>msdrD`(-{3tkqD}HvQuBpVhB#J>j#t_@V{Mzce@7USn=T(CE8nqO8EIea zyCYxiKn?ZdBDdkb;H`9NX(!7n! z*gGHkD&%`g%E`Jj=fbjcLe;hp7y4V}iktU7_~*v+g9lC= zIrvS=J=U|Ey!B$$?OikOr2N_#x!A0lVB)=4l1v@3RfjS@Ne-B;m6xA@Gw39FjA#nt z^5HpMQB3r@Vdt3Mj#*whKx$w#VgO0OJlq_RQZ?lFDNX1uL_61WPDM z&1aB1>#StAcHI%`i^u_b7ftXjovLVQNx8X~jAbYu!;^FH>=5Ne8z%E$l>U{O%KpJf zd&8df$z%zSIv>k~8`OE+(y*!Ii+IIb1%JLQ-TbZY80Vo^B&LAQe3v$o2*Z{NtAs=?2DweE)SOg)e6y=EgFT5tH= zaodmm4(dsC{m-tdv;;wA%rCv+KGWo?gW~gg^U>t(Mm`hAt>4a*!lk*Gc4EvW!s*N7 zbC8n(XGsUe8_|ZZtqakfstx}aG5#*4VX5QsR>*Y*bQRk~?b|+x&wq0@xzj$`bRHbv zj(%<3!DPRDrZgTOAt8CNw=Io%Od@f>y)n{~F&i5Z&h44{S+I9o?UI03TkYWt7)10#*1xEhu(5%s^#)ySqqvxTpQTP@p{u1Ha4}`cQ8B2l)F*;os_KwyPyti zvmO&1;ccN_+qwI@509MFg=KwBT=+;dDWId@UWlUONCq9#d4N?e$Ng+WS*K^RzED{Y z$E-VCW`hSo_s7>ZT3mdu!+FN$Et^KedbII!3~uUoA1Tgy zrKOBq>d)9JLh{(CAJYBv%$hosQ=>y+ik-8C9>kEJCN3|9J%-tHa>V45;0hY4C|C2+ z5(?|S1n8?sYwhJg55 z4@#Asa_)0xf4>b8dq8b3)gRV!tX>omRW!{)p#)_?e)QK0iBB2&ilkCj>C-J^Ca%b&kz zrEDEo=sIYAozeKzfU2UcR#98*YO$~NnlieI6%=D9#3BUcMyOcB@U}mB`z6mi*0b(K zapAJV?ETNGLkG(cUod$en)MY}SULG;`!V}v4%!Kjq{S#p$q)s~}&#~6&I@;&?DwMTkQ>&Rf z$6kj?#+lj{rvjsTQL7M*#@*dT8wtKK;I3v>K+#4HACPgrGE7qrt?s<~h}3SKwvViX z-R98O-4~Q9OQ%OuOn{NdAX|Y z`m}qUB;4wYcuH{zee2{crmdVT4i!yHgY4Ga2?^ZaS0kH(G}wnX-pp|T2_Jq$$B)t4 zyitEra;o26AoAi1cfT~kuIr{4qjZ+WINPM)DYGBjJI(gYZ6$Q7@xCn}^?3D~Cnit0 zNA^gI8{^p3v!Eqiek1CN{R}ntP^b(Q(AhQV-a|&`9g~P>Z_YKo>N#DegC5ucS2zDV zxxw6u=m!yz2)6wL788EVR9dNE*4x**=27nS)sfkGao9GJv{a}SwL)l@>22cJ0k-$M^%_Z4+`>f)M(4w@#u=aLgY-;pE zAi<+ozQ*B@aqAmHNmgdvUWJ1*GF7jHaGh!1e3nDM=M%O%VqtH|fvJ(d4z%qvk79xg zePL$DOEOTbXt8g}*k7ZA-p4Epkm>TpH+05vTYue?w>~5%_8{g8*vVY-NTa48ZqIPX zpZtP|%HLlo&%!^YII>6%__&~vGX{10L8OT*z1v~SLNu=p%*YTKFTn=+CTHKE(0*}*cU(;u8%m_pQ#zKO+FYW=O)mE3zFL?>gD!Y zf#5+3)vD+xLzJ<)>0lm};^6-_t13M#|sEfq^x1 zRJ>vCL-}uHkw)ASyS&;p?XBMRL`G7>>E_?g3Na+&UPeWag(jwC&SPF&r#9*a;eib{ z#*tt#VDq}pUh%#CS|J3fCa$izXCtvST}S+l6|HP0wAID>@m{0aPj8J7d0=s0dK;*y zIHDumQT0F)_+@cpYpd8K9RCYo1lt8je$&=Q86K2C2!0g>nV2hb>x>t<7)$H}_*9}EQkQP^saZ|5Tl%;;oV|J4Jh*m;%)~?W3!j$Ea%;r+$ z^?&M!J<__;O76|sx?fu`(bHq-op?a*{HMLP8qvOp2#WVAB&To5U4jGAExM)eZENJ^ z+(jQ!_Ko!*8r;NUO6W<9Gs zCYu(14yQ4`^v??M>NBQ>sIK}*Z@v+(9?MI&9J(d#f?~VYZnCfQ1M|T3G`$+RMp+u6 zemxXm{#Pt@8_V;9SXWV^Zc286O2esF&UzI}8=nlhPjLj^?LynOeLLHyCDz zbJZtlU@_KSCbRVxPGbyzq10*ZEVQ*C^#O*qJf=kH;+R_^-9T^_X!nIaE^A_foAvaCH~a8qS7 zJ)T`2Y*eH(F;o`^T5j5u9@9Cg6qIK3;#S6sDPLT>e&(|j(<>zD)IM@0lX%P~gXN^f zb><|Tzot4V>qg*BvW}mmt~Vao{=dC2kC7T5ja@9|{WJ45i{G0EE3=wH0(?>h61cVjjT(n9EZ9mV@vXZ@fG z`IHUExgW|Bd6!dhw_h*H4nuR*JzSJ$UtZ}74Mfw@5A>SN9bJ(R8<+dZ3VJ_sN;6xSdAhI?|l-K>2i zseAqCW6%>%I^Qle^5E}#I4R)8wR{HJO5CnyI#&14Q5@Ie-}4}F`56!Cv2~4y&P*qq zh1ir1t6j>u-&rF|>a;vtf-cB$r|}AAXYe{muKlMVwxbTS_47BRa&;W*Gm!Ud9VK-T z89fg|onHf3HO?>f5sijo(X+qeRaEPy&bsx2k|)S9EWUwqjy=rK&9W*&od1J>zsAUm zXJ6e4Igw))h8e?qs6coeprDge)EvyYQ4zMquq{mSrJLz#f#Wy4J;Z9c>N)Oqagt`e zT+N1CCFNMfwp}IVt8?mWVwiax!tN0$!i8oDg3Z2QHK9jHd&bQT?<5CyURjgwf_ow$ z*#%vn9oY*E284A{%R22Y-UCHtBKl@JT#e1h0}^2=39x zQ|1BgZ1(Yzq~DZAym0^v`w4QS-fAWza)+;g^6^`)cGKiKmwF6)5xVvc31vtrx`)RL zH;&F_2y^O!r6&tSG5ipL^-PgI?vfO*JcZlR+t{&S$hofZT4`9%Q{ff%mo(w#A-9+U z1jajoN?sT8{obaMc}On#-++zVdd^fA25YplXga{YG_q%95J6;00mXXTyJ~J8a5?gz z9Gj*K{f}U3i$&K~pgfoTUS#j|_|}FF4+xo3ukBL>xkqP?RY)dr;#e#v)bRQ)C0UosdVylb}jSN-tSnP$$Fp?U*En01gr#?o(87aV&bmi{p#{Atf>h; z-Zbs0uV}(iz1D7>b4w@!e&L~f6vKnB!y~X2Y3fZ&$70PAg5Jl1tfh=-zqSWOGtNAH zqQyz2-<67-fCQwV{e3qsrXF6+2LIzP*iWv2KiJhvQioxUWwWk!9be2J>0#&O3~VEs zSG2Z<6EK34LUE+k;l~<&t+Q`GYrVwld)Z65EJ}h@XjmiU<=hJ>H5Mlw&Tf*7h?GyK z9+<y#`Ys8Yd3*M`A zxBwDLVX+7u0nb-iTOS8D)}PVDiE^vc-XKMu^a}gJjK&^o=kXpJ&yKS%NY z*`pf23(99LeZ#MVCQ8;%h68km7(v>fMz_+aXs>4@!DPG@iOMdk+vwZ~a5PqgB ze!l-6Fei4W+774dN~Mf@X>3eOe5SJZCff0GcKgn;ENZC!E-{90WjmU+l5(J5Ccpk% zY@=CN=F#w~YpDGF!P@h1PP}{Gy-6mXCfBHm&ys7%a-C43U<3;|yA2eRIYsj>UEsI! zymH{==zHR+EN1L2bXoCPVY#yMpJRr+#gf$bxgLSX^ApOe>yxC>-_kA~wF^ zZ7=AI{hH2KJ%>J@aIg*)dR-}4>5cX``YY~y$V=3t7~W9Sg88d&$EX_{Zde(Gk{tl{ z_rb)qkIhHBEZnCOZ4yMF>6S@T;)h=^CW|L;iRjPgZnXopn?5S zIN3G|_7ouFx0-Ed76@OMN0l0HN$TFrd-KtaJq#r>{z^`>TSM%seHV-%-9n@ekMYO8 zwMC~)Of+FH7HLvFHnQAEQpRR9P7(#gW3XIf7UtvC!fK|DVE=vY-(Pgb%Gx#tZnWt= z$Krf`ZG-E`xL$=#nCaz~Z2Ly2Z%1C$5lj4c{bcAlISoq-xs4Ics&&^q-(B+)s6_C= z^si^?cW;YgSIyIaxdJ9V(c;jmDnrZ4B^uc`C!XUMw2l08N97^Z2~QmJu?%HbxQtn07|Gq)NX%`ub7-(mB-u*^*U+rMCkZbjookf6d1Ha^M|SPO%6xv z&VFxd9t<-u07yzdhOW1aYuQfUW$3l-dUM_3J-pot!C)D3phjl4s#=#2CTxTS5k6E+ zPaMA`F2Q)d)bT9r+3Nc`-eoOisVnL)5BfF*u@D*eKjXy}6wuAIppZs&36QQbRv@pv9d>l+pD1Xz{kjocoAhhgFC|$$o^mOm5l!XI zARfKqiVtbfXX+o{0eM@Bp>x$`=%R9pYi(lxbiaG-(c9};(A6kc+Hc-IKK-aP4OUHf ziuLH3lEfG{D}9gYvi+UdMovh53UtNoxLEEjQIc^|6VmNdp653JCqrnYi!B% z5gAuda&ZW|{qXO5DC}_q z`BI@MFI>{zke-pT_G>qw7%h)is9~N&98LJ9$C44#iLr*eikGXCezo0zRg?BEKrw11 z#5dMMqR*Yn@A~ZZRd?ArqItJ}VevwgY^-SejO;qBsQ~hOy5RK!boL@i(q>cl6d5Zy z1AbCABuDzVApG$WBo3hK7F~71z8*S5i4bJNn=t*o{jzi_|n-aLV?1yXCBR479m=5ti%nu>H?LeWDha+S*z> zfj^O;>sm8(Uh^%-u*3FC7PdvlaGlAk(^)>HH608?F|jrS4485rH~cqRnZfNJlIK~_ zsEl#&k)A8|u(+i*`}(X`B7u_>Md3D_>0SYMa`)x}(A>1h%b!^2zM%ybhpQXM@*izR zI}fxMzy2&B<%NY{?%iG?;`a8ECklKau?p0 zEH+L%8YX*u&oB=F%hQ#@iPd6oTAoe`UNwKSK^7c_SXv<%+5bfwVhe;|`1G(hoce8w z-MFdGT|=e&(oUxL+Tu>V5ANsTWFwHz!0#3Om9DODvDg#+LhPIMGF6=R1-L+E$imp^ zS~mMPK4FH1#$k&?yP3-`YsPU5gFdSFw5E)sGTe>I1%NF=SE%gQwd`uqfPby2gP8cE z!*R#j%o8&pqKcJU`YK_wscwto76LnDLduPN1K}53b5%|Mgb}BL3bFkX7YAQS!>j4i zsrr}hRkjUBa0YSuYOyMw!U@(*eDQBa**Cz^;XCUY1TNEu&RF+3l>0U2r8m!I$S{7l zu)oFU%|c-4Mz_<#n#7~j z-&h2_D@7U)2|(T#q+w>}vK--bDkYiZX{7|W;$%Xy*7Y&Q3F~nmu8vd3WL96r^;tlG z7S`B2%^EU17IlKPq`>#?zTwG?wH51%Pk=8SKHHI}Mcrwq_sQzLH3~>@X zY|sP!yRc12A#L^;23+B=>AmjytY@G7q19Ez(%Vhbymb}dL8V}ZfhdrL%A#)w)&u%0 zx!~~U*|B9d``AbOeE^ht5|J~({UR;MUM+AF>`jjC${xR;ZREt@ul|LAxv>J82nFEe zF4z75hbB$!J8sx%NLYoGm7^$o?xkx}h1X8CiF-0gR5WaT4;jvq%P;@mFB%-Z=}Iy8 zl)@fzVeVod0?aO@HE2RfBlRS*Lz?a@L+lV|YQ>tcdOU>3`4x?8Z`btKq?5Bfc+TV_ zGh3RKtODil%N@bV)Ikp#X>U0&3&{Gdiw`lb%C4^%kF;aV~ zJ_v*g8L-*AHAMCyixa4t9Q{4-=96QchNzaSW3{US$R%xYE>V6zFrA*>YFozhVt3tR zp-Ow)(radvSFfnzd^K7oGhz_>kOHV{1pZg--_4!k?LBVXyu}dk4xlb}A%h|wL|X%c zBDtMlL8$GMBX9{aafI+-v{7VDXapWZsNzRl?sS7yrANd?BDHD$2QD1wo55wyc{CNtC<;w?l7DLsTt{ z$f~VC#p(m=R409hvb`B#J{CA$EQnrI(!SoDUCde zEUUmeKKLXU3!lou2tx|^Z;qKYAshw_AD~`+@u5Gd=iv8&QnL#L!)I(bI|;}rMeW|A z{Z2gV$44p%T<5+^-J4)2j$d8L{S~a%*LYPupy86Vpx08RksY&dw9tWktEQwy1mIvs z&CbqZhLqph6)0;Fc5kcf13STyR(W;B(yQvSd%*|E7CEg3Ap>?qAW<$Y|JltD>6N%$ zy2UE%Bp6inzbDrCWr(C;iv#!YTLVrX?O{jQmXP{~3BMLG1R=3PSW+YRk=>k~QA3pQ z)N6u?TL?q}aH-HP|EFs(+j2eZ?}C?Hg3-V9>^>e|9WYuwjL1#E8|8&c<|URW1MuzF zzc&!#Fc6}xq*w}e%dE)k9@`FvU;324^x2_Qw|Uf08hE*O)1nKX9OP1*NgAlRi^GxflAQDX`b>!=;9PIC<;S<*}tG zoh|m8>mF)wg+jiZYt)!DB1o#h_xU(1a0&Z@kAC9fL+tqp*@)kB4a_@{J9JLrxb5`Q zAdf?+-2wvOm>-lhJhbHD=JcHVfw4f1mg~csi?hL#ssari<4+cmCq|3G%a#ijHG%6j zZxo_>7`bA>);e0u={}Zm9if-dO#!phf-Vl&76XsX6Hz^w>HfaM>1;z5F3o-Xu<$(< zz=dV5+Z+oy$5^7@0%&WmlgFNMGl-KfzL-)O*vP8N0cfb>imH3Mz z;~uMPLopZAGaoE0Ctn@O+0?n^NV`E_F+ zrr^@~FCIH;&HS*rsrND;JQQlYY3`va=F{KvR&y3#IuxS}Yw)c=PT>JLVpQypq!B`ZEjF@AZT`^^0u{oz`FWTx& zoSmJMZ}i^rvs>#D8_OT5?H1$kK%av$F#U5Ui^zS%Sc(noJhul|slBD9q#?=$(@T);GLTkPe)?Uh!Z_L{Ug03?%n{u(Y`c~0e;MFz3o<58S2uK z3zm|v+dKx(o@{tX;4yh!VwW5K0STlh#$AVP z2sRyTM?ne-VCV%#+80TA0YOypb;kUIUw3GJ+FJe{Baipu06$`f#w*HY&~;;}TO2k-1VDfBMXC%>^cD2^Ea#gv{4AZqaKGqhvmQ{E?5o_5fPs#oBV!M zQ;$F_)fZyUQoMWrmE<>tOwEyh0{Hf_4C-NvTas~8E@fGLA3kLdx?LJA`%C9S!_|^P zw!9$FT(kQrHQ8dc)1fCAY5=dju_S9FV1}w7cHH2e2vu^YE>`-MNAykTz@ktL7`(QU zHre??CXt4f^?V9&?fkDVmqDq5m;}q^PdwzLE42?>O*rGrvUkl(zsL(O#K0F_bJK~h zd*%guf4O_?d9Z_|qtj3Wm0|9ha@pAFiY7pPh#PrZroSnbGL5UJEa&x2zJvH#f3Yy% z3H+^K-P4H6j#|T?cIG+x z(ZB7NXBIIJTA2+HFB?BoL9f{$HzT@{gZ{TXozH=pc9Dq5r)_0jK{3a>zj7(Ir-qgV z@@x^Jty43T`P@|i4s)x4q~bG_8E`Y_PKu)*No@N?tzQN;}2t3BB=z;aRwrEH|oWF<1X^0_Wl$ zg^Y-j3x2&=izezpp@nBb{*=kk1OG1n7)X=BO@8(~b6S_0?>11v4046aHC(^C!daE8 zD-KPbHuMrP8%11&Jg`)GYVYqlUeQk6E^ArvlvA{_tP?X%-A%*u9(@4&=+)d!r`rmQ0SHHiwe$Bc^5Cfe-r(`?G{L2S9Cdf;~jVnJ*Vbj1ane|%Mf&i2gdA+U(ooQ z&X`aQTRo?+7o(Z}|6`;ndP|p~d$IL6Cs3ET;phj8;F3Wgc5C#}?qaisi5E@M5<+>s z8Sqgev#Ibw`=?`4)WxF*MdlPxC52yv5(guQ%3JkO(W~IM5BD8i_t(cxoI~F1{aSdp=*b-6|BdGq<{p2wOKW8P!j!Rn=YH8b#d*hIvj>m>xUt6 zL+aR?_sz|E_Vq0H;J98D)F8hNUUS_3^L+J>BPE$u@M6NEcV+zg{8{_PAe0mB#2yx5 z1CI+kc^D&%h|e;J;fxzTJOl04DIRQxfk)gW9X3%tTM zTq)+5V>77_Z9EFqjWBB_{9+L*tzHm|_$JDusT_&MKNxA<%;U8pOkCwbvr%+Y6Zv1l@CyGH(1;6}V zTMyELayv8_K!2CT{#-7#?R>1%c!KYPKz=V4xAuN@_0kceMV$iDhgja)9oqYCH(jt! ze4rN@dtIlBv+6B?PfSeesg|WZ`pd-JwQ2EKz>~+j9DTLcwuSrf zGb4wmL-aVmivtbac>99e4eQxEr|S%#OTs~y0ks!K{fx{FBGlatI|g_|^O>W`UmzQZ zxr-QH?wkhE?q0cr7Q2mg$%O(Yu-d>BAH_xUZU}#pHd?gt3^HL4J-4!QKk@H% z65RhzK0swB8e?RKb>s^tzkU7CJRzb1$6M>GLKfvHXO$uyh7wszvQCQp?SYqx&CDC+ z3Zadi*2cgQOjMxMN<^iTN)jt#6SXEi2=sUDaH${qy{V*dIL;v3|EaDu7uixw&*Kzz zvDN{toBCMj3c2%2r^?!fxv< znfPnt{=}!Ky~6$l-rCHWFD~V0X`p z+z6laTHYrbfUVWV$La}NAM*`p6p#nV74os^=?v^NbMG{cnOF$eCLF|dj_zo)z2q^U zW)uZItEdNGS4#T`6&}M4J60>T&xhzDmSun>e8fiNQI-m)p;}A8^C1A{f3-T7ZDeHB zRb&u;(EG2f zwe>n8gGH|kr!R{0)~B}Ms*V6l&1YOhdy(Zp+Djd#V=ubNsrbPgT%5f>W&tY%Z?|>0 z%Qp4s6#h;_-MyQo@3JAPt%>%?tqcsa`rWP-zO%(GKT8 z@GyrGn)Zbl8L5SC_sLe&NvS4E3W<5jKzXLo?}EL&k|!FHxSSTV9c)_mA_gUI3&o9I ztKcFOUh;P>HzCR_JNN3Z55A9x)+cs-dHtj|UKi|nse30A^z{AuJ|{;KWt_PKp?W40 zogb$GTU2y$Asw*}KBRJ|rl_b0lNkc_*MI1UdJKmTmzOICU>pvRF_k|*c9k!J3yp(d zdu>83$MC^{$PvMKIP!%v8!dJbj?_u;QDQ>;d5RqLOD%f>PcEi3#Xh=mV;wJMMNYoiX|mj`asb#M)UmzIdagw;#&4cTw`iNk3%AS??JiH<>L#!x&|1J=DG^ z14h!5eIVrauN2A`xC=d57K!p?qAO|;2#`*9LJJnR8?!%GTigAYDjeU{b8l?WVf9ww zpedAFU%6i_jb7vJE5#>u%g{%jk?X4d=)ayg7%N^4+h)@Q85}zp)4Q7jBo~DI5mSn z^Z^3m|2ps#ACj&uf~tW9+8}bBn3GOl4f&@ia_ilk`HZYK!(%&TZhIh22x<-hAk99+ zo&(?a-Qr}bg}4pr!)C}fi7#SI@(5SlKi#@OsQP;^9YI?t@aVjjIkUGWypMNA>tUYK z3GJHuzP`hwqu4YrK=X-{7q@cD54wbb_E`OBupgySlp07L{LS_;mK6kEBDzckdJ6Ziv$%?Oh@YDBQuA0xW?B_4&Lb5w);rw+(?7z^4y4sY58MJdfr$1 zNaV)nf4>ej;8o0FpP2>>8JbM-_W_*Z2fFOCSLgiuU=0PrcYkq^Eorao>=0d`0c=E= z-Y0f#DYgRoPH{ZrRlg+5js~r8^%$veIRcai#HZc#KVJo&$;0i&vA;MjYBILUB)lR- zmRgp$X3yz;@&A6sG{zQZkoUS%jTA2+qHBJidQu*GIepZx3K!uCgl<chcf2shA64@*c|#v4J%;HAyv$XyoZ#uD=H7+-DyCu08$b_r*3;0)j59 zOJ_=@i#VqP`gxYs+G?)s!PzN3Y<33c7sr|3{^)l&LLL*&`^e17Y;6SsM-gfz+xnbr z^{MB+>1*YnKwyhWU6LAjj*&oM=J$2~T+^0|4caGaR{D6KXkS0qn(HBzU0{WwfI8PY zz&29$`Qi4hEk*V2YQcxx+}-;@Qk530-+~YICCu_n6rZ3NGL+cd z^fX$Y(#eOO7PpR6`JEi^V3PEbF`+n(khbF_-<(mKXkxK_bA7|UlSd~{55I|F6iO-n zh^K|7XLxe5=g><2y{i)nCtc@;e@uf2Uf2$lzpl{QwjV@Nh6VlmC*SHVx*YweF9d>r zs-_hPTD}0X3#=~1u1TT#*C&!lx?OLf?dlK|WlnT2)wq-+)eSUbNg3+EvIJHsW)EIH z)GIfuFppT5&gnHcaB^gA<;Z-|!gB_19R1HY`M|~2PG1$}gdToe=aaveoMU6-z1E{@ z)^GY!K1VP>7PUB30 zGDG_~F3Pa7DbxVlUroEdJurm;Kj<<-`YnZ3WlFxL-?&p+yLO7a>haPIhN$(vZD*qA z_=Ky&S&{kf9e^`5iCBgC=6HxuicDPQ&0h}weat@YiU6;8#Aa-5yak<>#R*!P)_^rR zm0;Kv9tU}jnIiNIHDu|hjN0A@Yep&;U=oji%qE^>XsT6~Y1z;>Qz^_vf5N`=?}F)C zY`zH9?{kG;*&8fSmdbPA9m;Cxi7j1{*JZVKS9`JG0y*m2nC#R!_hm7h>lX0C|5Py?VHWt!`mOQeI$SAZo9|f<8f`)tNAasWQ;r zr@p7peq_E5VO-~2s0_GmlNWzik)eQn?aE70O3W+VZ63Z~4W0~d8->>+Kb{x3<6

  • Svo&` zi&C4eEid1EC&9%iW~LQ_x`3l`gCcI>nX*+Qk;tZXOTJ&fj1MaOcau@w?9$us{8yAs zegbTH3>h;q6Z)|Dz9GVU(r2_tFNUURhDdBF#jV16;LGPyB8bVxSsh0U2YY7y2=TJ? zPLhn389Cf!7`@0%(2&ReOYN!SQLlID>p$HlaVf`{7U+tNC>w}LZ}ejDSU{wmJu)DY z>tNq{rF@}pSV&5*>1AxEYQOB*nO0W?RcIh8LdY}f{zJ(C;|gp{D3WRA&^X$EK`q+k zd=$Mje&8bFgfe0f3=Yx`SYwrUnzJv<62MlT@a-Xu2=59qG`HWs8i}V;e(eEp+SytybLH1GoJY|iiu4K6dKJn!rjO z+0|y@Vlt6l4&1B%9*H_#&Lkc$rnn|ExHdaqsy zmq#nxe^1(+9F)MBS6a%)=l_Rvw~YqQ-*P&=={oR;W?{_)>kHrh;4}{?%uy?2pB}V+ z7`wMMIX<2^7bPQ|m+GmnDzQ;jq$lumx(&~ijBMonbi%;Er{`d%D+E22Q}O4~U3sdC zmEB#mdzd9dPYvZJE|xw`!(`4Ymnzmsi#FV|Z2$1V8$%N4r8S{hRkYtk&SLlNW?JLVSPGm5dbJ0C5 zT*8~>d}`X#nPUkh$axzY787r!R+oS-&0apwv~rD=C$^239`zU`rns0@EL|RDNgjlz zMvoY}`mrG)eK&mVIt(M$l{TNg4&t=f34FTmDMSsyZKuyw^t(h0hNFWd*z1oK7CLkq zk`BeZuF>1aIzX6C8m3fshB}3U@_$4LfDW7vy(wa1Yeki=U5<$kEok-jX^ULdbqAe}$v(p$| zOdlPU5=&;!>sb={Q@%KWC{Wscoh$k}JH_%By;SJV8WmvV zI&1f{*s8}ZdXiT;aA#nE(IoYA%5klH@Yw)eA++@+B*rS}cKxbM%w*})K(Aj1OX7Lt zQZ1u@x{@lH8THdS$Pp?_OT&$VgG+qYUk|JyY18d)L-%3EoKB|+@v(2i5h2Rb&!x|j z$sGKD7me&cYYJ_c4{an>JDna)O<5pKs?z&QFpaoD1%)ye88?dqZSD;>Ih$qa0^L-* zg(l~B0Y*jB5e!9{^55;LU-%3Xk^zU7V3OW=or}4!{n*FW*4Dj)gIsX@LFA_fnivlN z5)TAG++f^HUxnqb3czK&ULH365YL+V&HpwdH}|Fe#o<~GAIwtB_d@z~yD$CFQ?72k zB*~@pu%roe^S$x1z@?>AY8JOcmAewJ`Bhu^k9P_mGvgbV1?_xsVp%IugrBXZhP-Ys z@MMn)2ymTEmprMDjLe?P)NZyBQ1HS$-r)83Yby+Um5)8j?&uSG0oC=;!~B-WiCltq z1}vuIx{OBIs)I9^PDEl;s_ux*`ZUVeM}@@f!sCk0qc(U34VYbe>wiT{Q7B&)zXQgX zcI{g%W0!__6%T@3cTAj~qT!CO=e~Bm?_^bL&d@y)Q4$ZcdF%M5WTmT(AiDEB{i->; zI)Ssmc$w>{uf2wfT+EUA>hi)a9bJn@+2>aM=77=|qm#oAA4=VGZIXG{Z$nL%ru;Pi za}#GnQBJ&)8|%iUJvg0!9k4=Vjs4Tpsqz$3f&eMB?9E36bxg^E3B*>7NZiCW*^s0y z->vW1)b8=TZJ(rqfsY}?ruqdMv?RA9*&@8h+@hPKRN)5=^SR8CQ>)?*+OAVvF>@wj z*A@+qU(YYZv&dja=WAt@(M`Tf@vg)J7j^MfWUHOfq;)_e@<#jdo@XM->E%)_;rVlcP zN0qA(XlpOC4f(V*dyK5>fI&3R;pWL$Lt)-XB`5(Q=(Im zKn&5TkhH?kvClrQ4U}7UpILJQ@WGDg^`KG$ynBx(nJw2$i+?jX&_nRu)sCg*B=Iw#udb^e zNZR}NPD`2F_X=2zFGt!vfxKT6&scCUOszuBqkCZw3fU=|9o)Ju#P~VgmD#kONQ&|` ztH9cHYmw{?oAm3+V?SOb%ux?axOS(ibdeOeLFNo)jsFwY&Yk| zZCts#c>lwVThJM^%(==6XEhdh5D>KCh>v_m03jao>+(@UHGab2-*QyGLC!gq<+9K3 zI7IN%^5_nqxB<7T+xUKi`6;zvAl!%u=r>DCWBs<<`cK8o)#E}sQmBu4p=G#RDw-XG z+F42@Y4Gh>l$<6PwD(d|yX^CLC%o@7ebABHuk^+^HXq$`v!R!fha?FkB*s>BP73P+ zA|^h=@5DCKd4Exq7?@bE=N57Hmjs>|tQ zVL!7mUvi|CDMjX_=>dmpqWAYvLJ~MkyOHC0TXj9>4s;L`cm4Q)Fnfy&N7ZD63eDG{ z(10T}Ik4opJ8LNdM*r|0TRY(+p6Y>SyCrWvJczBTjT}LD9f+O7?zS*+jH0uCMj4$X zEEW^6h3NUQaWSDPRyNbiZ~IKGDae?jD=d(__)U$PD-$05o_gT~eF3B~iGG){Q@8pQ z#g&Eo4!Ttj{9KPc$}7i}W8ja9Wz_DFBa{XuM8uY4qMIXcoF|;8N2ly}WsA$TgnC8H z6<;B}e51uJ>amsDaUZ3+qMs1tBv4#?ogvdEU`;GRyL_M+_H4HjOd#AgCV`$RhE%`8oB4{{5Jc?n2=Yue zTj(fzlx6ykpgsC$S{UmE$>QU+U{9~b3o&V8D(MGla4kK*{Q$5^SPNi%1mlB(+w#BF!6V3)| zqfyx8`FkIa5IC$aBjtuX^ycc#7LCdFF160pq|!DjW)Om7P>S{Br*h``wb@PJIh{FbBQfS%y(=? zq3ApoL)A?M#aB{xwq=c?1k<+*|o1@^=yfPfrP7~kEy z%|#Q-M1eaG{FG1oC2URCr(A#W_#k)F;wk)R2#(iUFl!8c>*aIJEKtG~TafjNE2uoi z&8O}eiJ5&a8uul{&; z{=kIA0F63M824ijA7#0aE_RK-V3heXWx%NfsuyfVe|CnFj_ZgFyNR#Q&YDw{WB2TE z*ASLBQQGOSGi|44zPB)%9zKb<9pa%|9+M+6qD}Ht>M z7TcDXKB0Rro#|8IL}&_H3lew4#lP_(&;@SZRoBjcoun)~x4`t{`MC3UWCEt97u#}n!|kApoVn1>{+I6gLQn#W}I zGM>~if9SR8+HFZVTi5J5L^hwQ5PIf$q1CyLla?X^yI-A04|9{pueK6Rod&wge7-$p8y6-mhduYUy9E!JwO2`fa)Txa7Hm*QSH;NXFOj_8|>yC0Y9u0=^q{bYkd*~h*^^YDk z;A97NBtrZaei!SEOP4Cs&+T!uhZX>!(*wDeD`E+TJIysqLN{nazVEaYvkF34robkmU{aS0{yqMu;-qV@fjG6A@^dh#Y)z1ib%+`c*yT$QLs>eo{`=CZq-0+ zX_#<^ska~FCqoHUyczT*YH@=mak29@i>^;|%~vP163P93vWT$5(tt7QAt2)Ws&Xxa zl@7*b6ct!Rn_TJcNCCAR(vL1O2YQ>Y6u^&m=7#PKh$Q~K&Tr%h*B27&=VAIEGEh#L_joIiA9E{UQhujB)cp0ledzvE@>H znu>{bvJMl_l###Nk&3~j5Hw}t-|b8u@t9c3CAl*D#)jCdgGScx*AvOgI z<@`F}$qGh@Z&@=kDs85uqFx7uuPiI}9tDBWCu&-Z*%3n9`IoGaKK7bwBZ!eX$=%{B z7J5Uc)mRwUwuxR07AA)%K3{?;M%j?S`ziUowtsdw>?JJN(&oj{|qmI`q={A z&rke!Iz{5?46grkTtE;2yJXwZHh*lQ$cweuSXKfyq}M( z266dDpU3kUqEl8srqA3m&qPz+6(G~VI3-5Lm6f8Gn%HIeW-xG-erH0HLNRB$ByRW# zVY~r|S;Tk_9aj6M>1)uKF{A$t%wwY`2hLM!YO2q0p>Z4-MI(*NyABQuRV6RqnS^=y z7a5mYnVQ~YKK`MA3y7Nzn>Tw#ia!|nL$G)Ab21I(dt-7t=?ue~Y z#8?Holl5vbo>bG4Bc=noq&wL<;eukjSk}I?(+#J-BWKq^yJ#)7YZ%Ljr^R-%&C|mV zIu9vEcGsiML~BvC^^dr0Kj|kD&zNBxlbk;|XJiSK9-S@wOqe1DTM{b2Oc+UhM;}XhgoA{96qh{m2>$ON7 zUwHX^Hf8aq$#ZGc-edQacNhQdRCELg0{1JuVzE+J+>z%FDJl|XN z+fC{-{-j_00l7ILTRz8Sbf*bpcSiRo$i&M89?+9Y-nTn;P9rS&H<62Y2u6`p=)wJc zq)*5D78PVpo<)i+CQybTB&4-VN8Lb+>;k9__P%3JO8`yM?o%Ta(1(-h4op#yv+~OJ zkoa^N7`-cdi4Gi$@_rHG%rXbmsQZ5IA6Y{I{nwd#N&Q% z!&UvJt;92*j2k@!15d{Z&Ocz8CH7~eDmL-cCI0Gv*CXf#)1SJz$Y0-SOj7#%7X`o@ z9+zdJ{xCHj&4#;8xpXe1xb=1w*CNGn5{n%)DHIaK%rw6gvS9^6uZn+64YJRs^}a$)T=D)gOLa^QMD(wQFk7FVS^0D_0nttgROH{sRD zv85(pjdqb%#XjC4LAZT{bv=M?Ja)$2#z}T1U4Fp4b_15Uynd%>1)|_use@ANNvYTt zf?#(k2(#n^Mi6&eZA0o0LXJ@kaCc8PYGA4nzXzXT7JWg!JGoq8P@=SYY0Sku22G5Q zn5N@Sw9eJeugEJr+juV1c#I?)nP53H1ipA1@k}u%GbFvc)x7gvC*`BqP$RwZ|Mu<< zE_X3J95>pG_NWKrhjxGJ!0!V+DHvU&5W%udf?ce^bDF5)-1Hr7tUv{xE|@c)jKLu8@y0MHs9Jq6jD8BS=KVP&EvmOBXp;VbhBgB*h53w`G8VS)J;D|hY%+<{(Bdp zc8>035k4AYZ?nMTUnYy)0)0~j$6h*eGZN^!JA6J}%C2Be?z{o&WW*az3Y8gHdfnOF z__`Qi#rV1Rs}m165V^UJ2@tpwcF%R5IX6coS0Z%oGowymnkBm+oZ33~eln)Y2_vGw zn>^Wnq;ejjqOTNw9i%5BuM9doAaD+P-@@y^y82zryHt-nogVjIrnh4TVfbKpY#c7D ze2n&LNd|Rw*KaqsBBO@a_6@1r$J^2|@pz%ln=&x< z9k)6UYhX+|eu69&dvmVGu3CES`QZf_shswX3+V%~3$nXa{Gu{=jEye><>y4yMxZUl z(&@(}#583&#!Vi_2?6w{UVm?J>kIe@^)}qzoXxY#bg|1EcX1mvxR3R3MnAzqND8?G*s=5JFcR^lEZCDU16h z%N#~$)nEfRvtp=>jr=3$j1$-0>~}{9=W+wMU{U(QB7KrClvcJKh9Jo?ll3E@lRZ;h zD{15X8YP7^*i&hsmUQCmIFZRpT!BJ~f!2xD1B~BpuNPcE0Du66_Y6u$y-0{D$jIj9 znNQSlG6m*0U}clfTaF0Qw|y)a*QtHI^FbM9(nUdx4i4jtZU}Tfepm#-SSgW zr6ul3#poY$o`s!>z&DXW1D8%;mWuI=0UHTErmrZ$>jD}N9w%_axdD*d0xO@7(%rb9 zs+lN@qnlgc4vYuWy7tAEGeUNb`+@>fP^8e0c6z;Q1NVrWj=)#Ue4+z~NZ1N6?L6u> zN=w=LI!_^;bT;s45{0bd)hi3yJ|2-|A3vnTo9RW*N07$IoVmKrY_hu@`0Uk;?XOpWy|Bd@Mk%NCoe*WZ5tiFOf$ zHRtc$hl_bzpnoi5)6@*BZ#wy}2IutsRrr2YLRh8}HLqa;MbJ@u{mxG=w+WlPjo-vg z=2yHsJ6HF80eCG`5*YH{Ii|z9GcatEv38$8w)k7X4XwZK09_8i^Cu{R;#%LC_5Fa> zuCm#a@aBN)7ubxd}^f#Jib4oY~ryLs)Cy@_bdqc~?`D^!z_ zI36qLVh@x#K1pYl!PZ)su6dV!ElcY)^1pmTZjumY2cps8PxP=L_w#8Vd2IOZKyY5J zHuJRIH!fSQ-KpZBwEaY>uXB8X?NqM4<-asMfX%X=3d}EisCj%tC^G?nG zwi75C?@XdFp0y5$YJDE;4j(oe3v~6zn(<-7*?9W79+;OWowi8~X(|>Q--g!laUt-B zn&3+i0Yvo-bvBTx&tg$=ieUyR1575r-z0q}-nWX~BDJEFDKtZLNq?z?#8d z)dsH`AbQr=_;|)+ZDauu3;+70z?6ua^*DFT3-J@h+CrbPM8E(I^km|ye+a_SZ=?@G z3}X1;Ro+MLDSPhJs4{D}NkNF_OeFs@3TiS_UPGetN{my~QoWwORAa_W;Wi(NNrm_$ zGQWq@EHPvLFuNWv#4p8as?rMYNlcmJ=x0>L7GhJtgx|S(e~7JK1JCr5DflZoP-K80 zDub+KjO1WLI=hH}X}w#GqLbG)w3S-}-1ln|fv-m$>1%5i&(8a?5;Gr0H5WnIP(THrFF?Xx7{?~1d7{-#A`abx(@`Qv}p7f3_PxQyDRn_QIZ`MtcVqtU%jw7J)R*@W@-=JiRiG5aE)C2DVN{^K>= zchez{CjF z$J6uXL*!|`xdO?lr{pZLSf(k|Az%D$G+iN(9ON=#ZGUy=x4=7kSj_yvsmM}J`iTwl zaJ_x!g2Kl1D=neczsKxD2R$h<%&*~Y!I&kG0R)+X0b>MNdtj{UW%|A5xkw2nk9F%1 zcor=IWS-L<|K)4=F8D3MCpd|*)o9yaoCM-Z>)mmvb~+xMV1W0f6d8(Uz2mZt)^A-z z+PdK*h8mlR|9Y4=cx0ZvQ2?|i$|Vh}UsE5zak~NHf|Go61IoSO?28C*+M?@f&@Wu+ zqn{t#AyC4MzKdLbfUwf$%GX$?Mwc~H%m#byqKcYSKJF0!0wDnh!I|&eNbrN9r+fqX zKzG5B*QzfJ<+KA~Ce9(udIc9jdYju;r+OthXk|Hl+6LY5Ka+&)JSEtnSS_w+c!uRJ zz~De1;KI063#=gT1DKaiPgWF&)$#fe1Raei$Cw1M>mBam@{)c|+|mk`N5nIyBKtH+ zkN>F|nC?w!wZ{&Rj>ZQEr+VE=y(ouzk`o=rrSq~UNl0wHtepwtFFzs#nb3;jAZ>;%!fX$0C(u< z!sv9|rlFrsrj2jobP31`fwk%fe)$0+Ja6n3 zUdEfBf{>07P$sB<*-rj{`#1niN#o6Qa;HyjF&x^Di67w2gkx)b{-7-KMjd4u7m!UL zY4$nkrEl#&L#7edxJ@h_H$wrkHp#EUhhS*(@G2?dwTSK)d~Y3-JHVuvKF5_hO;-y> zK{7n6=H;fCn0r@I(Rt5#&QhIK`v_Z!^|jUgOvqV4tC0z_act6(`@8x(OQLj-oh)u0 zuz?*atueVz8BW#u(*?s`lck`|)?xoXUIyz=`zqs4|J*~uW$zEz!CCCruefD@DhPRL zaUCZwF{I@g9ktuja?ltu?Lu3dj;g{XPUsX02V_-!5ItUc)@A2Z=`hx z8`wMzA`ILoixujQtu-I3)h~XDJwFT*op0pXY6J-Gs5ufmQ~Tdfo~U8$HB6% zou0mBetEG7Y@hWfYH&6yK?#_l+TIa<@-=3sPX;cwc{VZprc-9Y37$@o?q-qZJi`QD z;SQO-BPNBS*|X6})7+s$c}c~o!}jm$!GKf?PGId)93RNSHO~t~z z$xS|Fg3$9qY+d5~(?gtTH7dxnSOQ;u81uytn2$Ijbu(i0H*B=+dy3WlJp zrcS#FEDQg=-%p5Oe>YdLV*bZ`!KTXB=`0EOU>xx00q~~Shz6(%VKEp~ivqIl-k@Kw zOE){~Bli+{%BBGdQP0zVXMdEv_Dt=5-NHcU^TwE*PO>*|Xcz?#?7+&|-d?52W&3zcP6%_- zZMk*mI5wgF*1Ohr!N50$1(a<7rjP0HB-;zEs^&0uU)Q??r!hDj?;hDyLv9e>cYZ!9BTZ_h$^~b`JqgCC3d|-T z+$lDegbd^U9v9K!5{o{exn>d|fG>AljBIa<1rDE`OqnPy{|x-i!S}>72bZDrI$Js4 z#;-Y@wbGCwm`*h)^tD|WR0|J1*7E-TCWrFhS6V<V>xs^lpxoV%ZRG+Q!M7WM&b=L%x+V z(icDLQ12EzR9iA9%|*>bp*~ZY^`W>JI^`esk`YY@32=gsK~MZ?AlrftgM!d^{QKTu zt$Ga1WZLT|*S?y2eO`A?_+h(A+Dv@KnJGNX55xS_X114tQh7XO6=xnN5*(;`p}mdh z>WyB@oAjcRq3QLUK~eu^Z02tNZ02Q{gz*W%xp6=)*tFh;BPBVOMb zy*A6HYKWx?H_^UbO0Jem-&Wl)D1S&P5HvFM`6+x)kAcd=BeZklsyy@z4j{Tp@qZ|X zVm4>8nH?|1Fy&o?7`(SPFI#7r7`{~stdz3L0u35k7E*cT?>*ILu-Um2i2!HCj1U4`my!^As?JfSF%^Y!rCBHzr7&_g~rPuu56#@>#i7f3s5cBu|{_Dtn1kh5ha^_X8q+{Z- z1kURJmRp^W`U2*;h8kG@)nRpoWteykHbV-vlaIc_iEq4sGCuly{qHRLT-~&}|8s9Y zHV&jh>h6*nQrF9p$n2Tgw+5kLPB z$y{gw%g@`MHZ>Oqvu`7bdgIa5Tz`ADgG|i~Guv7=%ongT!x2kQiwQ~#b+?gq{d~I9 z<{$_9F#InXT`{lDtMpxZ+ zGhe)wwUxb=k_AJ2olW&$`jc`-{QoZB6;d7iwfrXgY8*LF)jc6We#bn&vwNt)E9uDn z;W=0Kp8c;!MgIhv@7KMguIoM&J+xZdQQdC3^&#e*K5`D=4)$OUGS&bYX#Tx#iaf1Wa_s*s+b!eQdj8VEyT1~8uY`hwW-iXN2 z_^1Ok?vipf_&;@US>O-(DQeoQcc$;PlyYplt2Fec<>5nKYOh7#hWdXglV+WlZaxFAS)AY+9%|P0zvZMIzO?Gj1}8MApKuC-baSt&5fQ3tPR}f=t)8?P)%) zc}-T_SCt%X!ncry0>fG_$>qdVOsrNHdZ)yf_Ue5Mj;iuF^Emc;##$0FVAODc2IaHm zeJk$n-YqlM=)jq8d5~##%=o)p0_E+k+<}@IY@qFY#z3E;f61qhCv^jNbFIY3J^w~U z4@rO(YqQ@+M1biPHT~tLUjSQqu~1#m0TQ;0$CGR(wp(0#*1qw*yrh!1R))>d`|9`< z@_gtLq`~kDO)OyYnz%mjY-NLm+MyQVtj>mto2@a1e(Psk#*Z)XYS!*~_nV>XS+{0U1? zC*+NUO7Ma$?b^g{B6J=epJ0f~YkKFO#6ed zTxs$6#(`2MCS{HK&mUOGzM6Xz-V5SD)ki)KoRRb=-l4CGQS$ud)28=;6JPjVY&QAk zqi;zIyGBi^G`g}Or{h{)%Eu2;Z9zFE;v1}RV$rXbEOLPkPpr7kL)NlS!flHnU-e#F zsP>w7W_L~&amn)E%$bd-qd5H-YcTs7)P9aCrEoU>d5_^JS-_Nc?k9ThXXYlSb#`>TEBDp7 zr!qIu_D`7Hs}^-9>uQBpuU=Wzw2$|sZ@1Vf&M)pBwXK`ygi%G&6*bABF_D#@zALpS zUl783zDR8Gg_lkI-5bG0hCdXrSk4T9=&b8}E1MhJGUggRts}L6&L`zt_wZ5sI$OcE zc1x2D_n6j}TpaYmzfeSY=BSus%JgyuS7af$qWYEcKdgNxzqRpZQQu?_Td4PsXlzT# zrgXn;;hs~zCukvf#ijTNX{x4&aK{8+3HaF5c6!7-pXO1~sO0NTF7~0?EZKQHK&I5Dp2s)Kh z738%2xsQ*JwoTPPozYg*X=#H;Zz;iD^-hLVr!48ntfYG&xd+zKI29drx$2B^=mboD zpI|aps+FXi2uI)pc3~M#B}r8moE`QbdllW1){^SKv@6F+hpKexkXr(WZ)a!pk6Ca; zZW#-dx*>=Q4*lTIbQS;g@+L1r)dM9v;mMY-!vhdWx8I>*M-^~F5uX~VqWFNYah;Kv z%d@Wf#U&(bx1+n`H$HM03%lQF{Mw_)9yYWwLFRx`+lbHiE_^3wGy+kTDr=yK2Jc@50iyy*hPFo2R?nuBr;kM!7!>%!td~^u8})*lp}t(H}&Z?`;tV zeWbWDv;L~M{-KZ~pgDd0M;o7*ZP`_>DE`M8GI5lKv83AQ*ti4%QRBko&#{{OvW^Ji zEJ#0jXG;#utg!KugY`S_Zt*qTTd26200k+|?tCvIcW;+Wq|>F7-&vY0CC!&bUv9IhmKdr2K?;nUR9sAgWBGhP#ih;`i-F!ozF-5 zAK!mq%;=Eywb}PfY3wrY1yT3==guW&bd9zpB-EdH$?`iyu4TRb;%m`aYA+(*CsB^AOm**9_}xRL0VyV(u|qIfW+=~Zur+e-v zRX=L*55qT~+=jy}q6-fC?c?_C@7(BHpjdW#hiv5QPv+aNzm5}$gswv9d#VuSi# z(fe&w3Z%kpO^wGc@3-EIPXbF$P!q%0S8nYlJ&2`&WHc5-68j~ONk`^8iJc_`I26N#b{EKsgUy_*PBl2;;7sFj;c=R1!7 z?W?|XG*fLfn1#pHdit1QOVJt2@X_|?=$B|1L1GxOH<4Xg5wN$Ykrj57V~-%To~Pf+ zbO)O+pAtOxqVmLD?4UUTgDA<4AQ)aZfMn%Fm+w3`0* zk6!ZbMqZ}XxmPK{`Iu3(O_Gvkhx{vJ!EIkny_ZFtE%4ryR{3A+zEztyS9{t$xP5IU zQ*mpybw8iUj^-0#BJJa2-`d?&C}Ap<6)U0|KVF)7+tt-)Er%sN0BD6j8(PKuat2@E_Fl#f=&c1?|Fk zFN^eD{DW*sJk}Rpl80eJ=OU=y@pM(AC%%}aDd5MaXam>q)5gk}bVvUIoj_u{^ix;C zUM8Q_eae+LrH6M63AOmKzBGpPcZOwq95aVBS79X;EKRd&CB<&|51v25C-1dNkeuX0 z$FKSaj_fb2G40oCb*?6dzqHpXs}{>+(j>F|p|>|k#6oWT4f<&5nP-gpf;3H~M&|`v zo?Amqw7H;FZcqm(@v)2r69yPzes>$FH-19uEGMR($RM%Vz}01c z_4>$Y_v-gOS(42aD(vGpd%#u@;Qat$>{r$RJW%V2EOt@MF(?T;$61i-#x!uSd-LuI z^ZZB5Z?g#1?~u6KIQ*{Si9jM_`W8Br9iBBDGM{8=+IM$o2Wj2lu*nwpscRmeRA%iC z=a^DFn0&n@di*>Lg>S#>A?Q1x_va3rpb5&nKFMtcKhaFPq@AWFlZGk9ZfKOm1m4ie_3Il zc{X6a{T}J#lp}T1dgUd(xSJQleh$E>L0<%~k?q3uw^IIXx$dhW$n6wh^iLd&1RU%b);)KQhg{^Kb}1yfe)#Lqp!I(=eks&q z@fQPjKKd|KkPdkjBgQ6xnIJ3qW;%nTt3v)q-y<_4OF6O{9J|{?PUa6C+M>3BC(&jy zw7s`x?O?sd(kusl;$zd*40|wnrPd>XYx3mP$Lp0j&~{cCBto zI((Lb&(53g*2Mcp<^G8xDt~iWF4rJW+TmDjsllXn@s+YSi9HHGcRYJ)C6*^3kcdg_ znvdd*8kYc5EQU$)@&$pH+VUW3#b5l9Qz+^cdvP@+7|qckXokydWj*t z;cL}%?(*>{$~{oCKa^yeH!OZ~Ca0xxs9Iyzf}?1*P@iD^d%Bkae>lH$^y6nC8a9L{ z?BgL%Gv}SN!raS6##daK8w+EC4bha2N`wB zH$qX6oF#jfSdzRP;8eAkg7g3vhp_Cb!KA3|SDV6SbVie8s7?Cq>WL2|8V_(VMoCfy zIr%Gdx0nq1F*qJgwN65j}Na%E|4cemfWElDrnFGI5O0<=+WH zC2KwII?E4!vQ3Fpq0tPQE^$5_=pb-k2TP-CcF_7W;#i5+z6m!1bd}sQT~ZkK){o1K z*+yKIkg-^)!hNQugW?lwVT49%jK^TFS$i=T@iJNGnx5NIOh3RYpEECzPHQ8TP2+c2 z*c_L#d2HF7d+FTN0WsRoLvhBviVIUPrc2>jQ70xFS$z-+lSXumcV=@R-H4I@*$G%R zOUEjE?wO-y;XJNO>o;jvWfzRr;j1JU{z=0eHZsr5YuYNi%74&j@G;1QuFeopv}Jfn zXIOKRY;()bBzOpT4YjxLXU-dbSapezLEKMXC*(3gU_w&<)F|| zSDRwu1lhR{S4HIwMQ179vg|z?2b_Gwfwh6LQ-HP`w&PWmg2n` zaLV*WwqhN&i;i7kh1M9aFsX0Tpp9lsNx-BFjzpyrY$O~I$F#8xbm=(7-HN5ZiwQQA z^ygh;`+@Isj|{$jrcZBB5N*F)$|=XLz&r|80Oo#U;Gj+kZ&|x5ID zaDSPh%|h7cpt+v_-1~utywvlis*XD;f99EpgB*@^+;QJ=uMZ$)gCu}wm(~n^*l)fkd0fZjF7lf6nzojUO@oj1jd4W0hMFeKR;Lwr^ zY1C4INhHykoV#R5fCss}ffTg&1!CISoO6A3YO~U_#hMZ#$@-$aXZOXD&qoQ1xrxrXEYJ*J;}M?mpk{l1Qk{S`7tNCjJY$a;;d20xMH zl9Ems)5IxR56KeK7ZHk5x^xNXcapNRc{c2JhiK21W0UY%ScafMdyI(G#|v${qlq2G zxFi2bNCnhY1>$y~ljI4bi@N!p>IySey&NCe<6MH$PN3@QS;kjAZYDNfU|IRB6?| z8NJzA57jySk}%55lMxHf`xi0y-mvn7{kv!k+f9o9N}={(S7Bi zwzFymOg4kUVi;wr+=J(&kK>5{NcW15A5vPycnHp3b^$abfO$Oj`67)MY^vno^Pc!b z@pde_>moPSF}!(qmaxGf!+kzge!ovtDoay@NBU^vk(uVNBNi*lvrfj*H{O&6jJxR! z5+7-c#r$kak8x1ktn+VC{~Rpa!XZZ;)bh1&KbqZwZ_ULO4Z*SbMIjA!*i1z)he~6h z``n&hYJ-RU!)h5^ox<3*;)s~foJWH?c1qV_mqBZgr`)x5TQT>x(ARxBDMm|=xXzG{ z-u@KhvI>VOw<5l|z(7YS_yepWPHOw?BiHKu#*%uy-d#pQb>htdDu-P=D2I!6&W?-X zzY_JscjpXKQ#=hzunHkT4vdn)Fp=`9^7EO(M6Sb+a%A7Q5aif%gswH0`Sefx$w&-k z5Bt}iox$K(RAp{*Y&3Ot%gMjzsNohzM6JGp%`kCIf>I^T}b&8gMv zuo5?|e9G596E7Tb6Tv^)6Z1|21C>CyjIpU${4Rm(rAxj(N^ZHO!_o3>`&_75$S$;; znZ8+$rM%+9kS`FLe%0|A$rBiM^oRkKXCs|QDVK(<-aA(~;#*Q=Vl~~rKFqVmVKkre zaPC7srM);T(1pN`GxJzhe^K!oJ`qgbD>nGb3^nJk=I57gihS&A82;kX+W#mJ*^+_$ z=orP42f8Qmh3G*sfICGZ1(bzO{{TWpP7$2*G@S$jt_N-SYHVn)f`60eLA-8e)Tht+ zQ|XU)sl`_e@b?{u@Xd8HV0hF?^DLWQ1@TzVQi7ij^I{1gZ{Cab(Vf4hSFH}E^?cS^ zwb#M6UKQ_V&t`muBNIvqg=0EL$_~sQCRhTJ!u$T1k{U>dvlx*+=J^fvN1&EnXm{kO zcAp-U=+30xca3Mx!@I&n-^}&Lxm=xFDVNmu2mWZ?UyQ)t*G^tbpc-mBw5#sb9l2N1 zJ3pNV+bd*VhpOcWH|HyLh2oe)=D_Fe*)Kg-p5FPm{diboCmlkj;M}*x6W`tQXk5;qj6DtgA4j(_F?dp;r zN8uSP@jXYH9e>1`*p=^58FgfhQ@$W|&E00fa7u?GzOg25dj;kn^PEmc*!U4DDd(cL9WhJnNdAhP-MC=hm|2`~-6( zdwtT<{$#&9`#`f!)VWJS#QZ>O0QR@X6m$KOdCl!i11 ze@16}oa~n7cbB5Whyhq|eh(nA@u#0Q0=7wpc=+n_Bo6)88J0vn&B2%TPqQ`-8Pjz* zj;-mOwZ0(Rfj`3XF75-ni}jpkzQUZS!PkTL`O+>JA@xJsSv@~u*4RoG|DECvR$~8Y zrXb!vN5|)I=Al&#HpX=5;cw)Hh|PXFPWgwv*?$sAqa_hWByk+LfZ)S%|DF-w4T-yJ)vdOOl-8i!dK#N z-YH%D32fRY#NZtdmXSq%ySg=Zqdwf%M9y}95~M3+(Ywh5Pi99!%1A%0ITafe3`C}5$~Q~$1%VwA4?Y` zyo9vzpL-LivAK8R#6l49;2;`VC60B|BqZ@k7c%Xc{);4|G2PUGzaeMRh`r3GgpSs< z(TPDoq1ReC1|L4g)}?t1JE|o*a${PAWxEO7D4WuQ@8+AlH-W`l*X9M%Y@Ec)a53To z=NAkwX?9lH3!VLX|H0oiCjRIrc3bY z?sNuw(n0~c8pncDp3He)QWhdD2M+w_0;drEE1u;nYdSa3DJ{97*=`tF;wuxab#=r85(q;SD(dzv)7#2wh5gH`t#4`a5^NoBI z$@$yi*`RSOl(T@6XuA-zj9UHW^a2bNy$Xy}e+ehNQzz_|v>r>>;Xnopc+nyTfZLgG zhwC=8G!-ZPJwE}c7IMcK@)3t;E3R0iHkz)$*Ll2$v~XA0kX8q@BW%w!aEFEAm%cV3 zl}&%iw#5Rya2;6M$p3szG*plt%wIhS*G&sz5^}i{D09xcwA1&j71rG#s2+d&ExVj_ z+vgCi@c``5-CPC@fWUk!UBjra|FjOS@7s3Ar4^!-D~=;y6tk=T)E!)Z2~0CSpe;Rj!3F2$a|ftudR;kJ)Yn)Uhhx@*BDz+&faI$%mK%o?p|@NLV{qv ziGr3F@Bp%!^TB;YtBc=KEd{C@Q!TYzXIl7t;o>ON$XdEC6;R-(SArPu5*n~wNpI>5 zDyQ+@Rtw^9xS&*zQ=Mar_n{p2ygh3?seE5Qt;w4o3*ry{!dQ$SEai3Fv^(R+J+lJJ z_ApmF$OfV30qZS<`pX88gFO)v+c`oqkCx2t_*?f+N}459cZ@pQzTfsRA5xB;Dwx1T z_*G_n{wrRn0TKw)S(|BZfzs+E!llF=zFLsM0oAs*?RpW_H&`P(-Lu-FD%KOO_2zS` zYjZ$xskD|?A9vq^Iv>tu-Mw`gBA=!DvmGbC-!z1j&`eZbD>3OwW6Pf9Tvzxvh z*yZWA4q|1dD;f6ev2dL#5A%W42g**xW>Fz)^`>j94LZx7m1nlCH+jUtE<2%*(m2>w z>o_Po*TGfp<`04ix1nmgm|0sS%CFMR%dqZVgyLe&OZjf443>9!X5gmW?a}UP6{ljT z4&ThvH~|;_8pVYmDJ|57Pn7@yiIVOc4x_qCkJT6+t7dtwG{y4Mj7992D%!E{(J}E} zgM)*|`1BzE%*C3Qe?e*kjjk!Ud+dd>1SDSk`s$ePdME}0w3b;h%3ypRX?^>Es^^Z;JCEzqR7E!aAAC;(-PNrWUo|Mp!%NmwB9(f-!GD9!FgxEvNfjTQg5IdPFjD+=dJ z(`;ChLTLMa*<9z*E>s0dFrylhBCka`VW0Z8JMmWQk=(Y8Gp>t_c*u<{RLp`vG>M)E z%6pLDYV^TScJzhHk+g4dKimxs4F}(=xZ8a&%$;c!Rye)pK^?ok2JV1cD5((59L<6} zS1l;x&B);7aC;F{`_Sl=5zg$02!KRtPkkwnklq&PNZnb59Q_O&R%M&!;Q$ent1%|; zE8i^BlqV-NO+q+taS6wdgu>lJZG?*C%Oh^}XlM}fd%Hg$*UP%n>*q_NPB-#(%`&juMP~ekX96SwN;RN< z(}15ZpWDcnLpjvFMH@s~TVNjVS4}sTE;!kU79p+XL>o$WGz7tb>g=O)H#c6Xfn`np zxDVf+aDfZ|hUJmUgKt=c^HVLqZ7vzsc&UF7$pE!j4UQPKIIr39MoQn_f6aC}|LVoX zmyt&`>~ApaiS1tMOZt2%QlwY={D)`y9}`N2BJ6Ih(bT+CsF!pmuOOXa^S>|u^xMTM z7*QB@LqA{Z#GiGeH||`FApga}`6WDW^R|Zc;|!Cwlr3?|$;^@=fme(_UmEkRPoHCa zBvKN1>9cfWV6|YU+^}njlk67z(9YI+c0XXP0&!e=u8H4AnN~`KKN+_kn=6r{x+?TH zvOy_W`#SgOUW8mlkhwoNw9zuH-k>u2oGl2bqCd7j`cq+}{n-nFMnk6{>Z)lGvnvAx zdNu+)B)_IcmObte=7=P;!}Ka1-+1t;5YnohWL7ybawGB=+zCY2ho2PB^?(VvNs3A6OlYkG?Dn_5b zUTi7!9)v7^`=K(|`mpJ`_U6%Qy|B)^WNOp|OVdg=#(C_4Yjm*Zeo*7Ac3|qwb=D^d z2?xn*83uwO=@2TVX8@_ck(mBGBB44o+fSkhCV`kpvYs5gd-twJnw3sbzsdpc+qbiO zi=u{y4IGO;|J@FomlSprOVWr66~_jArLD0JmJ%K;^Yt(b*=iu0A)E&um5p7|D`E(c zT9PNfqqpv>gm!m-fB%OKOiWB{3F5&?u{UnqXlCM@kl*0k@z@q_(&nQCS2d6$$M8$U zkwlyCZ`Sef+=|mmD}n2=Q~st)yaLXZNa826DGr7jh_U;6PbS zYR8-~Rn-J8DY?cDrf7@@+1J~U|@-Bq~$nEB)_l*HVq7X zzJ*IC^UCko|1DeUz=5w14g}RlRVruJm%UehpOcd_*lSIaLa8zL%ecH{6VC^IwJuSU zEFQzPSa%li{run`ti1Hww{HW^X^c&to}M?VgFhYM(su5AHV9BCViT_`9jI%4sK*O> zgwDgroyG|{V_w%*Np~1x)bjs2y=+hQALM_}n5SwwxVmNwg3cG! zh7<@$_)-AMTEiH`*Ut^7cSXk>pX51;lI>~Ryk_1=DS@OJ8+-vff@Nj*?D-S+t8-#@ zM-=*OU|;|q)`xKo_hrgNflZTNE2!B4IpZ_mzpt>%LrUb(Y3i0pKWG0^}EoY2g@v zngoUb+VATb1}LMi+1+1$9|e{8mDDxtZuPDIG5d(3?}hYovpWMp)wI8S<3%?0EDQ|^ zz$yo(KoS&DvlyuAubK0HKXDtImz`JYkwkhTBI-ijrsSWWmnW}aqWB4tA~uc`w|xqh zl3Vs?%GJd>t^hm3o>S)q)nZ}Yz=`@gW`lD`Nt106M{cd%FC!u;S$q8$+4(glvCtfY z(_7p%cG+}dSx?4EpoeqoT8lMmR{)xi6zAt3=Hh2CcS^+4cP`L81i)K$>O2T{bH`c0 zrk;-3>IA*UfvN8|`5L}VN10x{7~2`h%)0jSKdZv^sXU8}xCl^Y`&r3+z*?VIns3Y) z|MBC3^vu9pwvuJ!#-0c2x@OMC01ejrd39X zxm41wA1ay&A5~Cj9GjY%9B%R0;?waiM|BKR?1{=Gf%d%n1mh*GxQ?ktk9R1FalVmX zA(_1&x|4v!Til@;vt!?+?E29Wge`#&I67O)kBqJcmwrn}H>d!T%&;yq{Q8{uu7zMh z8)42jReFB?DLWAdVa$s7mCKDj)pc)eseFoCwg;w2G9ff5UphG-} zsEdwP`udw>L6}}K;t#lWGRH1m%fbcP~P#;4HJK1y#~?4yRRiCCQ1yw+tTvmzDl3zGFM1+SO95toBv(PYwA1( zRcbtejXyC=%F`b2iIFncXPtdLE70j&BkhJVf!==C%a|1ZCXqc}xE^A>Md2Pk&|)oDR#S|h_6&*ng; z!$J7u0MafTzhCDH3YCLYBh4tov{oNmc8bpZ$>hcso#_>+3vHOSVEo$J0-3=)VViQk z2STo(EwV#*ee=-)9H|IzlYnt+Ak}0LOf90R){PAVJ?JGeLVOSW*aT;`LysW$4MGWt z&ZqbBGdcwhk$2lw*;%$jWj&xyZxzy1If5%XuOi;v*^Lf>=|GHzkPxPPat)ckYqZmn z8fW}KqGRK&T2WenCIPDQN|ACVY>n+`rFzlSXg5z`4y4hFr_4>ILoU&lfw%0wP`OYN z9c->$yS7(adILHz%yg=dylz4s>f__C<5`Ux)phL8WyxM&FCr$k7Jxk5D83bPLFQ*Q zjK)h0Y$PIs$)ARDJHC*w^hryw5xYba8L8sCK=wTu542n<)$AJ3a(9J% zZl2Tqlt!vmsZrbrg*qF??h#WWz1e@oCu^$wJOhV&tKd3Qtb(d_Emd09-h8ti3JA=p z+3okXDK$fiT2GXw3=ETX{^LEV0C|lhV`Vt*gbR*?>hB9wz6Z(;22KDcSO=P+PKNLR zwRNA?g z&rKAnCH)Di@m^q_&@CvPYd|ml#-lZL-z)z4a6TO(>$ zOVFJi_qD7`-wURm$8d(*-kd<1?QSGxPj$th{+>K}vKO!$h@-6}j1Ns3m}o)SGbKZi zA+|{KcWIn%a0EMqb-A#gqM)8?^g?M{2F}c+&%nmkfw{5igzxF&$Sm_r>0u$58YIe} zV3vOE1$y`C;U2`Ij|&C^$gzOX^Q`kRe8j6(D$$;WPpC|Pu7M~>*N@u2;@TBKpb;-AE% zykel=ks%;`>OAZ|Ilonic~Mud@UC{3EObXCdEy`u8u?!hpV%^8Ya=F`r3)Mt;V?}! zT`dg;?H2;SZYM^=fQVV^N_xmTJ}vSYun%HecPDTO{)`AE=G%%qP>R}dHb0|zi01-G zlFK*4(PJSt-@`kK_vfm|>K-2?eoOpoipQli4_y^p9Ln+nM-=s!RPR{ieVK2xLCl?A zv;Dk)hQFoHS2&$9J$m6M`-yq&#(a(=SLS>>g}k@`d1h89LG$Y=KD>gqy#DCRQ#>Kzo=Ke-e(5lXK#!R?}X zP(j5fV%v3Nsoskan+7b_wRx3`Jo+^Fjv6q~?=3Evupl?oDqToE#M*b4+zLrp=+2!7 zuSg>U<1Z8Q3z}hqwOnV?|LuO9Ph1>QWQXryC95^oSGwt!j<94DHMGe#C0hg2KDSVp zC$^Azy7Bp01nT)_L_j4+7rdzpQHZuDoZ1Y(?+jt^gGG=m#`jUMhI;heLPRC7u5$VR zg#6H9zt{yi564BpNi-bt`u|p6@c*FD$6F!4@2TrLTwE~y)ux2iBG>z!^lW`hJ8luT zK?s86%`T`0w}21P_V+3)c?&}S`9>q3l&j1(l@8?j=LjRIa2G&ZchBOWIs)_`Z$XR_ zx-&B0$OKp}4v&TGl?~)__Fj0fBEFmIH4JV(L~R+ruJ`cVLLZ<}71DsQQ+0Z2-i1-_ zL;AOGS1+fiE!-7fSMGE{k@&w-- z?kMa%4YGwItNI&I>`ll{ymUUH(J(wsc|nv!=^uFKKSrz4s7DWPNbR?>4EmL}$tRKX zeXFq~!+`D~H`}I$YnG3G<*no^IO9R@#pi|}e^DJ3+B83POg`|19EPpB-yWCKM{%<; znkl+AX4U_za}7(@DLKIoaj<(+){0@IVZXP{72~t2OCuS6=_b7XB9b2`KpU9|U>fVm zTVUL}j9mSj_NHV{SiCy^Z1&nOA7Z5(#QKCTVxLDSzrJ~oFD$a*_#%;{2u4%9w+C!_ z@a=pfpGDZWs{C&%lyUtP+n%CG`8xsGNbgz5O84QkX|`iA;+_G!8Z1XQo9ew#h-|{| zTIN@r7g!`fJBiuq3iDzn3%TC~VpeY$o1P=qIp1jWRRu+4VRRjBzL0bX(|&RI>>_ST ztWs4F;-hGR*+iG*r}#kkxgb8Oe8I6}E0U0R0_s>6jIN2xwt(!W<%=A%=W(Fy0EV?N z#zqk_woQATa+(%{5x*qi`JNSgZ;Nb9e)ybJLFO-#JjamRe`}+0*(llTrMX`nQn+6hT7=B@d#vMFf-vAVz zMbX3rRNi+pi!XBg(uVksr7zTK6mgwyuaj<1Hgg^^8{%IxeCdS?cjGI*8z_)_zUB4c zg6ISi&*tdQ`9|v;80bPFyh(@v5lCm7XA!^q1j)Pe3nBsUtUe!q9VDekDLfuMJB8a}W=mZ^c%`RGHPW1&0x=jM%f+bK?6J zGEy3vbr&peie88qJMgY5md9i9i)1-uXG3@fde`%Xx(99B;`A9FP5Ja6u5yrk`g zGbAQhs0!1_5`40YG+`Pl55a!?wl6O$ES`Q>cENPbVN28(szkJgnyW|@*SBEsJ@&BzLkrOxiVlgCK%G3_Q=z| zf{pD+f!#)I6)qDMhKUo))eH*TU=qxaCZ|f48nS|Rvc_&^}nkPb;h;+2 zc6=dQ801wEjs90L+??=poA&59g%*7jrfdM)oQTW^WZc@x^8)S`D*a1fBE)}2MlXp;D4I_M+(Ap zs60|vdOV~{8b=0qeKfGKv0>q7)E67dW@x+WoWl#ifX(QsO%c4(TgwSBIUUwq7Sj7I ztq4qfPbd`1+xv|2wg`+%dV*pLisEynLLH6L2P|SVm$EPt7_49QE!nKxk6JbZ0S<;> za!1V#k$Y0+LvjoI|vpE~g#3;TEoKngqs7llr7$zzH4B?k? z;7wHZs-&!;9{sQJHjO~SUjllqDV z$_8dWhe&~+Y9sRgKKp|~-@NA<6DE-HW$^uk9?3DcwR%3jb9rs9n@hO}>Jp-kJRwY; ze5R|j(-RD%4#z3Rfgj|^OR#z*0|hcj^)F?>i`rVP?p8#*k0sAA>g;x$VE_tbMx>>s zv91PUPv-ylN+a{K+1a3773+C6Hr0O~sEl3uvXTA}k5BgJRkg<$gNN|!*!`|O4xi)ojbM7xC7Kh4Z}7sX{| z8wQ+JR8)|8R;e6-eF6%->p|UjG3oN2>c6p4uy@0#G0I!8xrwD}hxf-M+Y2LmQ5Xa&I@@_r!;+Bzp0$FMIO^npZu< zyxv7eTxDEkbl0u3Yi{kVUM)kz zx~}->=$+Bg(W^@Ev{T-vp$@^S?sMnP-97$nIXE;b;0{_ zqfc(4%YUj5Ne^Fqq^xF;e>|~!115hr=7iCh_kXX-?*04(0hh`Q#vkS~*P`-+CQ_)FRZ z)X#kMNTw{Sfu3`0R{R z=(2DLsK%y)Vi~wCP@t3Fg9n_B5p`MM!+hd0-WTSQlbI=*3-Jy|fXJCnFk^T42-GRZ zY%=KS;2?hcUD(`6lm>*6hJ21cpRyB5Y=yRa2KfYvm>fNJ>{u_`m+cYn6m?yvZM^Oi-yhX8W2L18 zDMd2;ieW)_U}sxLrR7y^kn<6|;TEwvF1;yEIWB-8$OV@?dT8Z=tx@AT$mb1W5%%i) z4W5Wsul7Yj))dh-bTWMKW%AXkdDIQM;VU~OzzadDw?myE?9vdT`<;T8g-^J`e+ED5 z&AlqD&7JP!d3%$+q;wGOTL6o1aS_!BZ;wZ*&gUXUqt`ID)_pJVkl=Dc3DOAL1Fi~8NwHr?N%b~af zGYbeuQ2=0N*Rx@#mf@&`>OK&StaBPJ7^r}M&{>APw8j#YS=;hn2)zy%Uw@^ih6B`r z6IvxESb9XnW*@j?!EJ%~zzfx=wq7fY{5Q(wE?`HH*F5JIwfmN4?F&wF3CkStb`L_~ zBYvyY8Hm0^I^eq^N9@QyZ~pru5mY^Hi$gb7ctS|-rhbv)FgdwF3rkt1JdPA=2Dqh4 zF!M+A+@;4H!u9>dD%Nt?LM758zPvKcfEjkRBIqK4+}xn=@Mi ziH;|}=oFC%afGH2ADwJby}LHenoq`M?6$1i)ZxZlH^Zj9e{JDTh=Qi3<{{Fu3;)25 z?gg^YNH#rBj`qoMJyCh znB5BmceNNwbSU9ewJQeu_PiclmJ^cypp0ntJTmdzlB zZ#~p?-r){%{7C+Gh7yQQJFpurXsnaG+(E7PQ2r!o-?av4@kOGVt}bt|xU~6)Xavc67{saP%Jl!B5;NRpFVYg1DFF@PQpC&aSmSDWOnlfi! zSfT?VtYI$YH!_{!_lAI{3B!{~pCtt?F-NFrk0O6+AeQ`95HlA3cp_L9ljn#j=Et;u zWtpN@b?Nz2&rd%wcg;y9Yg)Roezzt~Ydv!AdSQz$$n>T)>RL>siJ>?OJ;CWw(4_Gi z0f6E~;<sBb8EDqW)xSKLF)B*P+HbA7{AZf0I>bYLTxMIgl z@CCSXHdrJ#w-@0_Mu4(%XV8%-N{% zT4}rY7Ly?K!dOO65@gdSr;@FJdOn~7i9a#PohT4KdMt=}XJuvO;7z%izqp<-U~5on zSXl6f&6xJ?c^R<$@e$cZ41|%2S!ska^y(u6jElUe3-FQHaIOo$_W}T!LD%L=U4Uu{`xGAeWRqP zq(h&!A;8AUQ%hLfs&3u=?JDu(w*#l3{^;798|)N8gO!br5us{s;!gPcrY#CPm4G;$ zW(a*1=*aOtct${Uv%%}D%*=r;QF60pv6@Nzmb2)#9*W$p-M-^pEl9Txh;UUKel|Sz z%^KYZxm24ZmNFakOyt75JIN`aVHH9ER}$n`4?l>jz=_ejay#|>zh^bjj}`KJ*NIzc z8z9y<8eLr_SB>rotdn-M*`<{l8$SN3I|#%$;{0&kud(#Wng<3Dg9Z29^3lz&*N(gqa&1ER0`fMTxWVDq}Y28Wyd zYjl)>M??Uko_TTBd-U%mR*t{S*>T06DTq3(24Qy*M{3{7vH3^4S0Z=SoApp)7Q zkZGsJ&{sK@3UQh~swy)3V;V4w?I2R3Jf5BTMe84_Obv0E82Ap7=T^Q5qAvt(GZ&;V zfQ)R347U2<{5dmVzl9o#v9e!I?MwY;h2I)LH$M?lgiIxXt_{^*GXf-R4W#ELS`s0Y zUQ)&Z>Qfc~O~{Sbq5w4bOli6pVw=~4_OBl@MN&(%s(=^K?t|i2S04Cr zrvt$7e|&v+T+jRa{yRQ6MjRAM%O0U0XXkZR&Y3P`AF;Hd@GWI;ckCF zVLR(4o1yF@wo}71?oGRsz&EWY-a8~Zw+Z;-S<%eH7<(nTxMZGmqltST+owN|&c;Zt zw3!XW5vVTI*rxY*^CiI}@NvdhWG|qZwdl{)n=6GU0Wk!LRWfE!5LxiGwE=l)gUy-Y zcENw5bCfR{q%iH7r6(Ar|8I#Ms2v>@ixn{WO3*22s3{#doa{jWb(ISfwVjN5R#Ff4P@kJL4wtN(cE@1&b_pT)L#>g7@i zPUR2FUl4;Y$jaWBbNvoekL@KM*DRPKwfjhyj$f+AdKN)m>&ZdClpMgE=SMWo7IN0s zOy(}mD*y|&zW|&s!pfyjZL!uZ{M=fhgMDT@psVJBu1ldX@fVv&WXqm;B!EonPMXC? z?xPkL#9nQ@$?3qsgKi~cJils#EHn-dn4a!K7C4(!{!Ro>TNdY^#IMxhgfWf z|H|i7$uNC@5X0>*vM}Y_q5@c^jt`6N)b%k| zss5%b1Vpk7B-dq!zr&-fW&%xG((M+mf3z>-&tall^WS)GXS8*oGqg| z&g5B~%`HOcf0AO~;l`smZuS*B>ptFlSgh9T^JzJxT@Ya9l9C82*R|XwS~cIS-qodO zp^~9iW9o`u9RA(0s5R1zPi4)OH#o5@XM0F`*rA*Fr`Y!=6cwVJ_K~b0wHNt(OC)RE z7?Ms{(7%<25{a|d=L-;mZWbDEA86U*mJ4Av_DK}@eP_Es>$F4@QpO0}w>1i+mE?bp zyMmDOsZ4l7GS?#WuDX{W(A>Q{XX6Rr_6~A%b3`|)b038v)WT=ydpi&x&&Tk5!6|UU z8-PmKNng-}e8UIS>JL@9f1>bi?*6AHlaaI2wTVly;Y7JSq4r<`xVjLl=4ll!izE-? zuuq!6GD~r+qDw_03XcVDwIQ;MZ?hSE&wC8sWe=n@24x8*+8Ma*p^z4EV$~+k(rl&D8S#SyWW{6vKC_g7FU=ySc~d-Ib)98wni|HA!0Cpjll~av%+| zfJllH3o%5zsE(B0T!A?PBIkTp^=cp+YU{4ua^QY%Z>huj*nQO1Y=_v#m);F%?7BEt zu_&%2()m<+lS5f$q`rxM!v7pst!H|^Ew3zfbab@dq(Z2wmb_fXr7I(6+%0__mo@`O zwWpR?{Q4b%b@ZWaHQd!QtaFa&onO z?)UGLOMfu&XqV_&K+`_E4Ix!<2|I&`pW_q75%cYskSkD3IM@KrEG zjUs2qIe`kN0F=Y?6ni+5Q7P}%Z%8^HQ}-<$G|iU3H-2ao=Y}7N*~?!D;Y6y=%31-7 zL8fqjYn|-DZQObaroGks284Fl4xgYJ{yEEegH{e=V)gnEz1{nRzmz)v(uqH^^fuy^WD6b8m+68|*CjNm6JC$}Y1CaQ4e&Wg3YHMwB;;?mlk zlO{lc6d)bE9t=p*7Tg&m8!e|eS)T99XR@iU;1x|;O2rxdfD05yb#fBW<^27L^*>cN zkI)VdkePpfqok^8?hZ49+89M&1adOlU{ASZD`mJT-DGng>FdazsT#LM> zBPa*e$Zntr@6=hmQm@n&xAW-oQb(QTfqt}Vh4`VBZ6suj(9+nC2k$6Ans{Nhh*ElY z?OJ+@Jrd(4t*=$#mrit@BgFSH`p_l#`4i|$!riYrVmC9M&l!Byt@yo4@`M$lPdgxP zX~v>RN^)3LqE^LMgoN68ZT|i2>>W6}{=x63oK7PLYK(vVXoNaCANMiFh=M6=(olTm zx@`|rQed3VFZ*&H#pD*!f!Sa^)RIlmMoHA92wlm_Hl#I2n&l*b|7Nl~a==7V={X}M zP+S7aSq>otL7EAL%G!tu;xW zpWFdr1QV;9Ro^xQ6(S>tQH#Dq8kvOYN^{7(S`*}swOW} z;yp>62I!-vagl$joXwO&2mjT70!Mlqv+YiKJhX_E*&h`xvdBq;iUa$uma_SgZswbz z4!xQbeT#Pwf5%eu@NM}NEgw%1raJhJ2PQW*D@Px^zL%1v+kmsw*KOxMfI&8mAA*M& zKyJ&MqH02+rlvuHHN%7wAULWiA?-dgsD%k3gkeHFJmrH9j>(MA8Wn4}f*Bq`hOIeP z0WS{`ccAy0r9{%avTb}wZs|}o3Z-DsiF1Z){1>ZK7r5=U%NsiRtoTQn8RQ zbp`2IqrX0Zp~6cd!H^Oc5fL#lsr`~{o{M*>yhDl3zh|W(1D&}!`sF=IvH6^YW6+^p z-TjtKMvjkW26uy2lhsu-KZw2VPC|IHKl+B=wr94^8<1+@f#RF2GM}t=JCzYPv`V?WHp)q?0l|6Qc za18wxRNJC7nA!EtpNi0<(Zcz6rgYq^-jrrUD|9kQuPa*L~BA=_|0_bvw_Ys6Q^9tkm@_Equ<$5g#fo5(yF z^+iLwJ|#sgvQvf>i8T}qFc1Vg8c;Xe7nM?RO8j8cNq-vDSmpt*X^sOKG+4i+!+|nL|J#0A=5F<#}(u_9yW?(@*IrgCGHp z;WFbV>tywP9!@qI<}TG1OBArI=QNsxuKxY_D9-O)893FU$&hQzn(p!$K@F}oUi$kz zrpF2nFzoblNvb&?t6M_chn06nOo6?f(#lwibNy#VvSlKx- zC{B9P5>&+#mr*dCkI*BsayN38r73?W?sp!g@}*>e4#>t8v)!Q8%(J`ZW8SV8IFKN0 z(pBm@GobUBn+*b@u;FA5N&~*37j&jWSe@lVv#V&@N@ZnaLSg~F_6@{$qPunnXyCX6 zIpCkvW^*Npt_!R^eP!DXvo@0TT#`)!e$z2KWWlb^7QIp*9*zXn#yUOn-l>o$>h&)a zuV*CiEPY*O5(eq=oZn2R{l!>?Nbd0}TXo194<;ULW(}jAs`-Mh)AKPRMB^jG%p`jV zj+4xv0rVUbeoFvMN(w~Etfq9hbI2|)pEUq*(~re=;LGLMNm$M!7K2S$;|9f#m*s8T z2qe7Nq&wDC=7QuKZr4T17~Ky7JKG^cUsAdNMYnO8Ao6OG(xY9EdG>F;B1K7q!0-_y z;xe>SUKaT;oynL8IJW!9Tmw=tL7FtI&ZLGX#rS!pR#?|aRxF<<)crt1@&zR|&}?(x zQgh307M|2bGF8w1^{-BJ=CbSS6S5Vsw{xz%rz*S%!QHsU0yschH~DUC;sn+Vfm36Z znfsy-zRG~KP?2p8%yt&R%dHzve+L;0C82pis_|O`;Tbq4Yqu0uSPZAf;n&FE6Yak9 zG-L|a@l+Z_)V5>UlWP;7eqT- z@hQwFGNjG;^yt|}Wj+*JoBIf8C?Co~syAujq#|E!T{6qa#J-i}KD?^;R;?;0fa-!F z$7uHjG*jk4*zUt$%MB57fQEhsc*%rYjlYP=L>wtCJhtKmCo9Kf4v}1RNdh2gn`2T_ z2h{X~6LYA{a~xqWst#C6V6bft{Oh`>bGf^AYa#r2zLuI;PAj~-stDzmKZB0W?O-co zO>&9ipCF7^eMfIqnT-DJ0t|@~7~)*V#Ctel0W;^mjOUPAo{+I%q3(rLbc0(qwr?eS z0K=Cg%V!5sTkWr`UErhmiiNggdWV>eIbQn%w3;6aPYkU>4kSyVvUY63#s>V2w(i|u zgzIWR75XXc;5WT_8*Zz2w13y6FARbBjPht!g~W_JM8*|t<1@Z4qm_2`&LtviG=R2jB*Wu~ z2{H{nhDv_{NID&$S>G2~YVTR$7#$rw_IgDcS)#hg{`UzBK36V|ODw?B@kue5<)D1n zM*IhK3B~)rX9mUqAYegKB4WR+xHUF_yyR9{IW8hGPbyg`Yl_|WWb71SK1WJPuty=` zf*Ck3%kBDtP(a#avlJ2LV}wMM>kXK;*GHYSVs|$B2}oAfT2}GrzY?bE^`M%fA_FP< zI2(F>-H6!sVB-9fy#)Xq^6>)C4k&I?!%PIy&O6b23dhplzfT6Rpn)*ic9mSHjEpJv4!^v$Cq(H`XZS*+tt6{I(rL_spKK@STk zcp)H}DAb3qog5!(6(Ky2C0h462aPJvvo59dG^FfaA>GG>VupO`pQ5Uw!VHSW1HX5p zX_jy-L?0L;sE&k#TD3(YaS`V6MvViY1a%4}mi&BVT}g5A>)zDpJ}7tXJ{0i)VWA^! z0;u&MhwU0YawWDL9_FOv#p!^>_tSRESFIP1X$2o3E2j(>=kJ00D8%)7rU)Z_5*{4^EJ0!(;_9!kin!s5 zg-NykO&J6<9826}w&WC212gFgA4d+5u)s*U{r=D{h&ll_Y3@?HkeLzQ#~H9BWO5r< zZ7Mhl;&36uA&r`hip~(x1rd%~900>LK=1gn4 zO@QHG9Y`dSK56n-3$6j3Bst=uHV3Vfw51O=r6)U?a~eTUJ&Vjue7M>ba~KoqLiPYz zE(L#KDiUG5lXPnK4@`qwyOJ8FrC$7WpSJF(Hp?hQs@{)(DRT!{nhJBAm=J8llOfH9@OB4^Bxc!b<0$gl@69ZY2KN^jHH ztGDZ2Ko}if0C|~Q*w!PWgs}vKJvM^CEedB48DeuEGxS6<%m)~WLPc0aY;1L40WuJh z6nQZU2|I&55>S*UJs`{1s7m{EK8QVyneiS%wD3v zP61i!42Ibga_#AmyYm5Tg8(#*N{k6nB@IMz;JRMTfw-=UvS@{TnbIA+f@C}Z?I!604 zFQPJ$DG3UgW%@_cj*;`fT9K$R`kqx35kIzjE8Hi@iRDxNRT2UR$;b!Gh3W1@hD13c zHj!bg?iizSWqBK3jj8|98;GlwrqG3$9WXCvGtZGHdU=jC3=V@RnHcMoO)mQHjmne^ zJ{#K1Ep(&!DRJ>h49%uG%%(oa?~?b%I#1=Qgg3r#beJ9Q*-Xm*^1)>kwvb9E7TD1) zMMt@(O-}fY40?|bH9VJ4eDOUH(`tR||1^SegslDy$a=TKB7GXVUH}slBUVQa5r_pb zn&KlWZaq=<=gsDg2Z_Hs@7LY|j7-wHSql%i9ZIBTPfDv_KlJy(8F%Q|W z^9u`_P^f6=`j+?#;e4eZ?SF4cNP$wb>wy;Wmt_5KXJ4>lq9!o_?e@0bEGDU9j^U-09cHIM3!!t2Z1N1!MhKOjL5s#XL77VyX~1 zRr?q5KadKOcz{L>7rz-2x7&>-kdG`zn59&R`B?*Bk*?gdbk;D0OGVzlf5pLYs28D- zwEo0TG(o&+4|yW7Kku|z9pWB!4AOhnfH`G-B!eSXqhAPCEg#ZH$xl)U(G@MpAYlBq z2YJDG*ks5karM+^S(!A%<6tn$tB}PrT1@na&WAw8s0+%Gtoqtn`1zb_o=a!jwgq^XUt8MhFqRPzu;9lA1wlQ7xzt1YEK8^Ut&T(Saj;*Q+to zT^4tZWMg<=7%-<#_+|w`i?c`f{|@1~?;JGZ{+DGtPDwLf*h_*5X{#zq%?bE2l6WTB;2_BASKYV)Hq~u^~^^`RtLkD*M zfqtMoD=O`AI_kA$SJT@`XS7H7E*(})eL%-pQ2yH-)2)SN1*=C0Dnb=yb7u=W4;TT~ z(dK~oN7kh@^}0ltZV%@`W{LkW+R5CEtXeW^uCM`bYBL#OiKmlI2JA_y%unw~fjd@9 z*Nj0KT?C&qf`=m4tT529Z4j^J3SKjILG0ecsCzYhe09J_y zQE@DH;+<0+&pWxY_Nl}c{~+X09PgvrErh38PD3A1c%W??!Mb%2pA8%z^cteN9N}0T<)Ho(5bcL5 zW$C7<8U4|L(cJHK5hX8N*?t;2&q;}i{!g3+Fv`NfKnV;K+m6!?C<{A&Zs4KTnLBHK z_uWjc+*aU2-|aX;`5wOc@5g+nHpw@R z9i)CpNEH8=7Wt9yU*21&w?kOb?_Z8oD(gKwuiq`8g>jpI+K6!7WSt0|2?-Svm0fA8+b&+q*2zxA&uNd5TZ z)Vq?oG2;63pRfA+&o@w%e}1YTo-Y0UsNT}IS=|3p&*YE&{eE_%j1S$j5hsZJ_{xv% zqu%#!6fjnix#d5;y<=RPc0nd1-%^bHPCJr6dC`q}|L1R5s{ZuA0(+L8dCkus(m%Si zbi{u8;j3P(ghM<1z3d@>dg;!uXVIkn{4S;z>oY5+B8tZsJ6d-y@A-XPRra^1f9?$W zjagETj{b1O)bfo+^c&?a%U_N>v|lRZ;QhE|E^PG)w;huxQct%W{_Rf|{*Xr}A5V)6 zdqf{L3As5^2JtN{pnZ9|Kr%lvh@4A1D5@NzMEe# zqxSQ7gr&da{5$o(&i%st(>7fC=JBN~-xv7POIZ3|TZZUA_eJ4#{C|CPyA$=lib!2G ziw*QzpSSdTKmJ>=;on;ydG_1?^YXSYUEaCdHOV8lX?{N9Xz5SU@lgNk)JFNWjt6i5 z=O-Kw-doQsb^N$vvjbc%x8tS%47eJfS0&-g`!XVe&1Y5{5IRSq;^4gvJLJxtyI)o} zjubM>4|}omo~2K|AH5>)#DD%Okc215H+CVRdG8L-{j!xPt-AkkT@#Pef$`YQhh_D! zjS_DSht~fn$4CBtP%r=c6a&9rNz`;h2k~`Iv|DYvd+(kN->wQ2sUbnZ!SQ_l-ri9_ z+8UCDcbsx`&|gnD;W9tasneFWTT(0-yy6V!FOPb%bh>|Se)9*!V)*ySrQGQ zC+hOcJK$BrAZPB|yZ0>AkS8Zko)mnFdvx#Y?Cim~*#w4YwcH#G-!$gpHRLW@ zxpHL`pt(*}m>bBAV8GbulXus&h|yDSF?%1;a55ii(dXp8_U3;pR;;kX?QcJN{XUxf z;x@BN%yp*K=+uCY3kC_s_Hb5-hBEw1izEWh9C<5S_qR&^QhXLsDE#gbvyqW8 z3bf!S*Li4|@V-3~t;Gi}-7`Iw*z)CU|5j|&1?c-IARvB+!<^(Lp^2wasM2mPU$uYV zzV~(7=mdTMbIOJ8ihxuG8&n_SYKy3ZoQ8DaEuW~rg0fWR#nBsjg=gIuLm|m~#IB&^ zO}PHOYuef^|8s+JCFSL{un5s_-W&`r{Pezk`*I{!Q!fAMCuAcBG?vT|EgkL-6Y7a7 z6R_I%M#shm3WXG5iP`uP(wX5L%JiG5r!WebH;$NBdHFJX4v_wy|^X(nHpz})L7 z6nx(NW>GP6TMgT2D90;dtA6V5Z@~Et&xW0i?cF$&{lc`?+ceg-j(d90tR<_U@Vu-Z z5BRB{-@r$7nWVA&vu=xOmRaGV;}%LQyuPzRlrXaa$;>B!5c3 zj_N_E=)&6utL3}Z>E#2>?_wZ-Atq?JO;xQ1m>xbz1ah^3gVX8Ep6_5)OSx^ zR^*>NyDctfU_JZ*bQ=k;8rz;dXHcy_LZ89cai-bHA$deM)43_5&73PJbgM{T9XxgY zg#niBtK+{s^6`mAOIf{}k1U00`}SxQlnt)T!nO(!<6i9RTSmE+O%3dM9&~BE7#i{~ zdnb;IQ!Nuz@DcEzCj=3JTIIhS)zs{g5vBDlbb(JuXu?efm!j zCBpHY>M|5%RB|;jid9L;m^*6*hPlzL;`x!cNy&I`gG)EGd4=5j{dH@s|F6)XY=(M^ z?f2hLbe4Eo@O}&RQmusIl>LyN63F&~$I!pI9^63e!-v08KS@s$3k1D(*Lc2x+hE_d z>+LwIR5temITGZJ3^Cf`AXrL5*N_D*<>}|AZ_xx5^O*JcO+1e>mrwL| zUL0z*sGGxJlwdn}@M2_SBqT>Eyxcc$-q3B?5{5L0#e0gLT~3Bl_A7<%cLoNA8I(l* zh3FRONmfP>NjB-0$TTvfqgeD*p1~0%VwW!E?llMLXNSs^?6@8)GF@*82eGbc;$?mK zpLMK{0A7udGyyVgo4b#YO$u_$9@#kMPwZBmU%uSL%NIL$?gQq*m=3p{Kr_4yuA;cK zROa&Khqz9eIAy+?NNG`Qh0FNS8gMI~=+S5AQ$5JeenHKCIuza9tMprQR5C4wgzy1`ND3;AAIg>0$)b*P)Y6hQ!G13JK!YE{&6q!B; zB6kKn;y4;0@WRUm(~w#4jK5-TOG7RuzZ_Hw+b13NPCX$4%f=dS&5YH7b-W#8o@U(=&hz zE~N_@4Uk*8jM`5hRL!b4xIK+fYc|q;hQuv&3sj}DItpK_TaYxoW$m(G{Ym@;`R z5QvcFnx*OqY@D3Zh?V1Fhp_bJ(7c!IuxRfya{vA>1FgAgKx?C7!kUV&uHJ60$Lon4 z9=_!fKaGCUo9MMX6fg;wbT1AjFw-rYpPlRjOJb_i4+ZRMD#a2iF~9Mb`;g&2%RzNe zj{iGs+jmRQ-1_xrALNY4{$0gVmt00dKCX}bi{3k?tVc^YYm4$^vq1Nab3RZuPIY+YPPZEjaPKhrI;sQAUjfkQbh5N!_i zZWg`O@1L51D>W$2`u6ADyOA(iNO%m@Cj>XITCNaVE5b62VCB1nc?14aISjjj;gm)& zIL7qk@#7#6+t#MdSW}T&75=?Ap9Gv^`^R*Pfre1{+rADtEM^)T8w>JJ0#f14OOr|c zhqkI`yp4IIYuJ!(60WYH!G)Ct;AeTG438li92I76co9_MQLf*G)dawa@XbkH!rdHm zxoBD7K{?R=NrtV$8*Y5H!6SAWfdkWKj|U_z9gu+L9mo%L1k!sdmnPXx8+UehH@e}D zTRL>F#LD5wzN(HfM(yf|N6VJ`aR}^}4s*qI3>4yISFM6SPDr;g zy7$A&KTv0Vel*QAjY9ycVFWw5RlDoUmk2O;fOjL8H49p?*K4wEEN)!Cj{9PtEm2Zq zy)?j~GzQYSCMl>0{CFgEIDY%Nw0&bXPee>95)u-%@Bj=H!kzpQ3A=t=uoP$&@%?D# z2!3ndZ+T;r=7aSKZ#zu*E74Z&RdHlLrM$Sf5)#jvCj>AuyTotCyT}{*PgI?fxPCo^ zJY}SX2Iesk&OKnRqZAT?8vD>1y_FjHrblmt7v8&fuMY&Rthl&qF}ls6!tECkQ47Bm zASWi~4E{P8Gp6p1^|xdzVPVx_LCRvNLaK4V;cItriJiBU@j)a8VCzHzVv|%u$IKjy zP^5TZ3ki^1T(U^i{I}X1%?Fzzu_UyS_V}&GBb3sogI!(M0XEpda*!wxhVu?|KD`b# zNc+6f^N`9F;KiPv9)8=YS7_3R0|wY9BGTH!S!CHms#y^Tc)GxFGeBB;{ub@|t3gUiBi$V^EzhaO$!Dn0J~gwquu<&sG^iL) z_(n0E^csz9BF^wzjfON^f@l_3v;Y_hE7i^STb~C7f!mcsDMj3(*~}~R$93deY&`!* zY@Yh?wV(L2HV(8t>nTtUoQE+j5&nSQ+BvxR>UMbuw!h-7LJmUv6)Ca}(mS_!vPr(V zWed!PR3C~WZ~K-uO!$|CO$mEGQMp_Q4-%cz+)UD8;tX!vj+`XcJ9-ut1Kv3C7e^n5 z?7iq60intvA9cY?^x=w;L0Tdw=lp~go=b04xQ9f5@W3rSY}sS#`M;3qK~4psE~G1*p|E+Mx7pcn z2|pS1m*~2~n5s$yKARRF!<?yTt&EU6P4`xJJ#X95+BVcWC7PWAzpORI!5qhZJdg(ML!%lhDf;=P+Huwwm&}u zVB?A6lZOT6FB~#w$zeX)Ezt!91^bXW(UIVc^bv%K2Dyxcq$FvBqquH%J&08F?zC&xNCDPNKv}&=;tS5l=q(VRF9A}Tz#H#H;HrVg zF#z=x6K0FV;}0mI4b2hEQufn*m**5><+8o#BC@xta4dNKClFdb<~;KV=-)_p z5Es~oE@tx%1eVQv#XkUdHXW*s!nq~{aZe1js^L?T1P1ZBa=1Pu#9YH3TtM>nwHr3n zfxVLa+TI$C<$n@|vT@XAJ;}p*^@m~6`S?^_Q0rSAO6Vxm!DmmLIAIWb4f(nq>NKN( zdCceM0BkVsS!AFfRPoQngKNmLN+h=e+GNfsD=;vxGkxwN9vz(08kr=8`$$o;2qY`6)xIshmVsQ`z`Pjzr#Wn(l+0p}JP7S`al z3P2SD4GriQRV8utIPFat6rhpKdWSC&fk%%V`PiY`)z#ID;Thr0mN;^U%lOMVkN7@z zK0dyNY@5{PG{t5IH_SidFxSvDvo+8EsM_@UhKtux8cN{TVD#)xC$z=`;D9oOr{DF`a_xU;Ow{lp6 zW>$mIq!LA6(f)D4g?!18NXgGpnb@Xb$oZKga9%~rL`t!!)yV^RhL?B^v`+R6NEDHB z2m5oN(1%O6t3Yp|=%d+T4GwgCD1&qgd^dyEr0SqEYhx7?3xmhvRI{((kflW7#W@p? z@;(kJY3Z6+B_48VD2p+0X4kG$2mn>EvFJ{H;i4>>^q+htWwMrM)z3AEqZX;K55pa8 z!&Yw{YGwyO9GSV+LM=G|-w zKisifZO1+0dUQck9d(t*8^@*?=HhBMG8kUy(cW@^IB-(lDN=htqPW^+9@0aU7ca38;gh4S?tNF&m72mPEc}6 zeR|W+biMP7p@n^ZO`UxQ#Oa>}uzt#z*mqp&*HrT@Ydsk+sHjbvZMh{4JhZMOJv}|c zcKWs0Q?}35wnJHC?$>N9L(aceD4lK@LVAanN;XpkHG*ot%)N7>le%4<}3UAQ3cN+s4f4@WLH8r=w&g$iJO_b=<$bN4gyV>f2{vBYa34SNWV-lwiLG|uH}>#BWzFu#X1G#||p zNkgsV?0PKxS|Ln(dc|2eZ4tjZAj+{Qc4OAv2fQc!!aH~F9Mi7c?GdBl1V)_gx8K^l z9gy2hEeGMtUe|%z=bMbT#E}f1raHe^#4>dr^UrTqkOJ+9Q2Eg@;Ch`sJW^+i z+Ubd&gu~-r{`u$sK+l~6RFy>|!Hon384#yjhAqk%Hd2eJ2Bbo3#taOnvCgip{bU&K z@=Xpr`VGfOt>~n&Y}vA7re81bVP!=vt4Q_}(X2p?-gR<{LS)Z?VfC2JH$CzL!)<@9 zuOspdm)(r%rR;Tq_3z)aE3ay^kJa7x+i!WNKK-z&F=HVFqiXn>p7{9mRV!njS@yLo zKz@lb>1|jJQYd}Oo`d~w zBj;~aC(AvCopr$2pd623QZZcS(%4y=VGO;Y9lBtTg6bdS?*&WCv};YD?k%T)lxJtj4PBOYh@49%CLzJi zRF!U`MHVrt4`ZEjz;;5HlIr?%8gh;si%`QSnfYS$ZE>OQczcAP102&H1(J`ApTFU= zFL=jV&}K>3-*2MUOZ^y$XNv01%Xnqn*1J8Frlhk;{(8D|KdWh!xRUqpjd=I+^43SD z!&1naiJ9ZSfDowY$!ekpaSYbrlbe9juV25mlmc`|qgIzN`KL z+B2dqaik12Etg5rQ_KY2;m*e;iY6r{b5YfF<50x3>NpjFY!oH@Hs4|{SZ(3aG;cc~ zFdMz$(MfXR;}K-mQ9R|Itr!A_3QJ1v8z#-3>1pGZo4*97xhYy zo+2=tZA~hvG@iAN`q}Ox-JiupH8_cc<*21Vv|?V3(&tCOJ0@-?H2?w0ckkX!=W@VO z!}P!yl)hgvbey~BOJ}DxST7=VD(OzW@fWfIcesPWodK@{W9w*A>o5e)%V|Ax6!_W( z=0udT*`vkmgjsLwqZCL=sOFS(A7J_*6>FHZm~{Hb$3wZ>5s`PnIPP5^YG5QhPNp&F zD*S%(*S48)34_#;Hj#;zyNKXk2Ll+hI{;QJYQN~fz~7qDol4d?0sM^ynPmeuLM}mI zd!KWsa?a|)MF09qY#q~vUw#?B`BMGbWF1x@tqV=Ir0@2vTf?yhp69spfehPm#Ok>rNCi9WYUrEy3Qdai8#(LB6mgzxX ztN0aE@t18GMjJ)ICRu%}6f?ABQLvtjm4;K&je+wl#KZ&vP0;2unCBOYD6m!Mpy3N% zqoA@425}LJiD6_xe>FoR02fhA%mXUHSP_aF0M6#F>RL7l<5A^43X|N?`#+ucLdm<1 zdjF{FJtwDPbtBvD-+(S@J208@BS?JZ;<9z_&gT~O;LN{*<@If-b*Op@)d_S8A~}KU z^D0o6#J!-z4n;|(0;jMfkW%x-<{|I{#YyQdRSV$Zj=0vvD%DB%OqtReK5%oZ!J-%_ z+`M@+SbYJnZoi{9oZXrD)Om1NXgvGw-T9qX**(}H=+^nbRpd87@eMF+nkw))lX`YV zo~HQ@i)X=;?;%Lo>;uQ!(HB&fnS$LAh$ip|8r?|WG^u1t#;ko} zgFa!c78Dlpo8<(@rF{DI$)K|{3WPR8jy!T-6T8(mqw(w=EG&besOi}npcl5)5k(D~ z=CL7#Is|l2{yGnNU(1@0rTCU(+m{ zVu=nUr)FQ)OaA?%zB#Y(EOp&$Fxv0hwIO1w#a zw#)9O%r)TEtP7B!+q5YN?qy5UGKfO^ky{Mr5E`z4-WIJp_LfB64x*Vq*tAD5MHM@$ z2DJOh&j0-_(|^Csxe~B_%;vkyQYiIGcdy>Pk$go(I2$l@mns)8y)RVWJztn>y^nDheVT_%PEiy>8yG9_QS@OjzG zSDVD&KA|tUG98~j^K$tua4Ks3 zT7=>sUPtB1cfs>;*cHts&0#S%;AHyHL7cRG5e^Y?#X4z>u+W~$PeO18>N(4zmI}fQ zlwy?o4iN)R)ytOy(P%{k9u~FjY|hGq6y-ZwsXyFd+;UIGS^ni!ot@q1Qw)YyKRj@v zsX_68@~YXiG`!7QykRgINR-htF)7!ZI{*3Z-8ou@qo)ybKLWFjgGwWV^BP`V`{QkS zoO?g08MJ8m;F@~I&2m-o2s*zehd|=;KLyi5kFKRO?vC(_oCMaAQbaaN#)!89E|CfF z-VJUTz9|Et%T(Z!Au?7Kq;vB!BYA!bBu13d-})83#*FVtuDU9}#=Gpg=|NPBFTwv? zFM(s>JPRQuy63dGzj#UgyfU$|I#S z6r!6f2u;=eT=J3|k^R7A!7MI?U<6qyAjy8-8Y$r>RuEBjt;(ybWe6oo*fi`(&6Blf zo^Z}aqm|%H`#gxx{KJE8?M>}+l>Ufa7T6GPsq`i!r&5C~cqY(~;?-0f{|a_9GWx3z zGw_H`k4S-GezC-2a`3=>rE8 z@A%*Yh-D18;bA3APvCY1-K_$E2@Vw-ITH91*$Igil^8+);)=Pim{c->gM3oVQSYo< zO9pJHH#8iV?9f@&_HfgQy*HNqu&yX=MDb2D3jX{Yj7NCp7Jf!AU*CRHgENv~-jSul zv9-?6WIw+J@nQyi(F9Z#Z8(XF5iWJ&;3}eJ;{EVybI(K=??C*~8^zlS_fgDMuzarB zqNZBEeJ`1XhKA8s+joGllwbQER)T0qcsDUU2bO}@e1+->U$Olwi5U=$kBfUWqje2{ z;$@;__Jx}e)84f?m?9)9Iu8X8=00{XrJ(OV3u&vr&_%57CTwmr9;KAFRNMKY_cadV zDg%JDN6hRjNC5>}?w0F|y7G@^jo{!8spaT3%p8||Z1*YozcwpMmm;8@v55(7QCcN$ z2oj#t2%-nSki5~a+qMzjlNL*!NXwY`nuN1t(0*JPIY!h>{rXpbeL3Lbj+D4xK2C3& zh*A5WJ$&1^X!ko~w_mTnW`+mh)UAd(7&-R!=Q$X5ZV8CU6G#bIf<)-93NkJeG)1BP z{6rl|H{&?%UV3_Z+94l0i+P!){7~e#d+YPgPS$%JP?Q2c!Y#B)lu2ck=-q0_2M#2t zrb5dy*k&<)J?f3KiwmdgtS-$htjue-^-;Y+3cA`b<1T#o9Y_j*S8=5sY+}Zvqs$v- zo?Kn~A6IK)77*9^qBJRrGO*i<|NXDtZKyT3wI|&<7;$Byr%Dt9GHOusqk!9WuNza4 zOV+-ir!CNSkOg@)+)@RQ;_d&3WO!o`+kpe(q>^b)3trX+#KE{lH5UZJnl(ok{R;uU zqCvtk9#Q|ZvZ~5YxB~tq$N`tZcF0~Hwn^NgbT<)|ve~{J!Mgj;qZ|cYYq5=R(^0&yuiHN`!AyLRqeH)JL*CN?UTpdk4HOd6s@1bP&m zI#AAk4t1Ri;G8Xy+~}YC%j(sV=s+4Mgk%qsp1#idf>?^eQ3IzW5OLt@d=ju%2&F%m z4gg<6JTG78n9jpgb1=0j2%98Rh#VR;fh*Y0$yue@eHAuJc0if>gof=GAM2SN%?Uz? z4~rji1uS`+miuKj&SF1KznYS3HZ^?hZCWrZ8~wB3X&mWvQKePIee~#T24A96uBt#@ zBY-m?%U|&ZKizFO6#G65c{1W1j12cb+ApPZ0qdK#L(O46`N9~z7J}#u%mvY#_K4Lp zo4}`g&rK?h)%{x?D3zg5@ii3@%T4X=a}XbHG&EqobXfTiI}SxM*8u%$K2(F24KL3Z zFSI$g(9wku-fq`410O1SVB)KZYmKld;o^D;7Wv$&4Jx6Co?(zXcQ)Q?;s{~XSc zr(%j+g5G!rchtAek$m8`YYy83uwj;NLp4*A5iB`x(>~Q*G`1Z8;I#L8;x$w`b@jr- z^DlmUN|d^Ikj&D=CGhz~8|Mm##DAnS^MZN|# zj7N_3I=W9#v^g09tw~j_YL0FC(W6JjeOl#R*EsIcMo6e*YJ@ohQy-RRc4KhJWe`Jb zdOA)=IXQ{fsD4g$2$db^ykJ;UPJ{L$dJ=5Q7_jjYp_+svs81iE_>LCwft9sJ6ItAg zXe0z8#+OVpnC-8qsNhLnI}F#%fVsgl*GyrXCn($yyuo<$acC}wj&l}<#@y?D+85=) zVm*%Jx+cY z(q=$^fTYaV3J1(PP}|f2cqsd)@%i(> z1J;o19vIv+r%yvedK%8bTO5h(9oF4;lhz^2z%g}CK$+<@)6a%nihm*ib2Iv3kphn} z$-g|g0zjfNmJ4dsyw}d8Xl!;;`Wuv~DD&-4G9RDF@aIj;T|lp$)sbD3gzN)-n6mv6 zoGT|!-YKfPc#AXQrXAwJxn+?`d?awa8n%a$VNllRiiKEa5QAX>&hGBq`ubV} zuv=iUn0KHmnNWull+KPo3*x@!amDm?t34Y;`*@41w$6QSpfBiKX{n@oyQb6R&cV6f ze>!lf@80qas?!h@%*~NbTc8#0ugPK1j=B|`>p-@<00y-@O=TJW91zDL3H6CjQV z0>$>QyM6mMaUXr&X0dj}EemF);&<EcYaMf`)787<++D>gfq2dJ5!fkQHS|?fg)G*9-c; zc%iskSox13W+Btd(Q?cqW*B3#lZ~^=yxYot0}aJ;(?%9ocu$wS07Eub-pn&D*z&qpgUErfLU5pn+!=RaI7I`O>xt$wiNx8cTfrT6~d(jg9RC zOv%U4;DDIL$J82rX$M(icZ;LpRM4pmc|fweg*fVQ%vA`*5beJP%$!}QmIro-w&QiX zAT}LVtrzOPxq*1qa>D&SsgYrINK+$43!`UWzJ0Qr<>7z~`Sc-Tcm7CDOI77h?RzTQD=WQ$FJGz}$g2X(0evOA4LFS7oj z7`G6xRo(>qcIs_1yH4Ezl(7b|n-#SjY;3ote&6N1tImP8q@qmDI>W&>5Yz(8l+gc{ zUJxbg_T+YoBhRq?@;2*@xJktJw?`nbny*!mv{Y82({gv#j**LwY+a72WFOG#oCM)G zypTty`W(4;QDa6C`z#FO(B!d)@v@+(NEd`YBCq<(I+H@;Rm4G57qHaV7vVrAF+3!~ z(?#+zi`Xk8%O-C3aCMadUhrG+exBWJn;jm1OVdFJV-6fXscCk17B6H3A^qtzro=YC z5j#&H5)v^yvi3m=8K2A&9UL4o)P!APWf<~oQ(m|ommT^9hi zE&!{l$sFcDN@3tM3 zbfCq`{&uh#Q)kcGgZPFe%h_Q0y5Zxv)W{X!v;px+-A!ubk4w>mAM&HDN zyplGy!2pAGLq|~OCe{u9eo)ML2F@-e_j55F47eX@~K z1qMwqLy1Vg425p|H*Ma=sbt1Y^DlhD1c}cDdSvmj?V@S(ntOS_=7rf@!o!*!aVnBo z2FE3TW%|;$?#D+%S$u}>AiywLSYdOBwgzdZ2elVZKbv(j*p#ne7EBdxc196sf&|FT zMBo{*yIB*^_4sjnLNc+3;<%$Ts1<5SV+5XII#&fs&+1$U2e^Rf!9 zF#IH=dtYN}yl5@EyYt(H$MzhW=GA;$ph+?1=>wLLvcCwPKOq&6aGEbBoYVdgc>CJc zF61)+Y(?`9{M=>ut;)^~aG?9dp)3I#J_5DWU2h&i!KSW}H;^kUiBFg(1?KUS6^0ie z1=Dtr<|Bx`gie#LwaEW!=EW{Afx3B8^(Ye5X2FGD9Mz1+^Wy`58i&xOCjIXz=Du@S1-j^*zO9U znNcK@GdkG#_&#ms_`HGa9E<}#2GbwP^h+367EW5aFrDZOFo#4%qTQ@HF&<+UnLl`T z+M*Qgs?Bw`Czekjqj68=wn?*Ww6`F#r?tVs+e zh=>#w8!EOaARsjn#R8%tAcBA*QUyT;q{qZWIu<|>!HB3x6Df*RBUJ>XSHS>^NR!^- zuKfaP{&Q!(nLFQn^Ua;S^PArol=GhRoafnP?X}lN(Bh=Ui5oykW-aL4MMXtI$DYN3 zspSK79Hc#9-`XITj)#0RjOzBiR8Lt*l>ueCO0<*obUAPxRgn9sAW8uDWHo3T;|Cx4 z!aid686)L{hdZ|&e2U#jKr)-u5A|~Sjj2MYmhur8Au)b%y4O){I{*Y#h}nc8Gk=I? z1Y$O$Tznl&bA$~fsY{I^y*Q$kforyIJw)Dulwth4EbXJnT+eg%z~qVDgyAd?NgIZo zP_%>^sIN2$@KVqSj@CA>?95Cq+YX!@q8x8?^9!waJ1%{U)uTqnj@q04c?ycF0}zv8 zq>TIpRkweh>9vpnMbZSh1*=YeNqZ((jU1E}9|B6u-dHEZY!kZc!{6L851DZ91-3H> zlgv=>RtE`1QKuOyqc|jq?`^;pSg~@YlFqVm!MxC-fj0*Z9Xv?!-x+1FjnIS^C9!nz z;t$1~_H4{ge~+*;>3lY6h=*n(28yzVtD7(R0d$P*W%@t#SJ_4(>gQvtljmg7hJhR2FCeZzehB?|HLv##ZH4Cy(yZW@QRMA6RH#HU z`T>Tn3|exq=YAEQIxk<-l{z9@B=aS@oJY|I89{*LT7Hqpg{Z) z+48zxUUfcEqi?BBkg6b=UUePbn|9qRE-C9PWA0YP>pR0e} z89qCgc`I@F3iD~7=k^RR#cWr5-BHUC8p@`~cu3^kqi{GjAs8cyWn<^6cZ zL1$De?Qt4)#UWyfj&`~fJCYX!>_-S)7Jz&Ebk&?h(RxL+NMbzkt5>Ep>_gkpnV~>L z9N{3~2%bC}$sz?nG16*jVqHQov|TV&5%F!7^{w0Lnwh=01YSPzO!Xeyf7>P4Y(-3x6KEMrB55HeIX9Oshx&h}%Nh z9-hOkZTveB@zDGcLLJRJ{Kx3GQFmFZ^1go!S}-;+C1aNt-i6`hG zr7L^ZtXidY7If}YOZ_#6Q&hTl{2+Z&Y#f1=t!bp}NKO6tJ#65I=)AlXl*f7N0s^@( zbeL4SBlk6g&e)`_AO`g4A#~e*PqxA;&hx8Pcyit?@{V2O!w34I0;20RKlwSGUeEQw z>BWMhq7f;LXVB-R3QIjuGxjbAWXh;QnUPm|1HrxsCTL$^g{8L!r-cJi-dFzwIqMrU3JLxB7#$~uc2?7g@)rVpSKk=X3j)GXEZwvd(&sLjyAO);zkdH zibXIy(OK9xb_dsFwnrB(2!2 z2jB?b1l$M7oQUKUVIu1?K@33%e>|A=r|Xh6kg{HSDU3)0szF{*DmzFHN(hX$zuv#l zL6rvYRjHV$$wUIyap?0wtkNVllE*`oE2xC`5E!6PcK1NfOmK=qn8nUI!0-c)OTl!4!+014Pa}yy)Z7t%{Gmrt zdr`b3S~yxHAh@(RYpmOovr_fRA8# z{a~y^5pjG#fLDUvi}UYa@qmCfdc_>=YO8yuFrX6R$q(*9=$Nh)mC` z&@R*G&IkOPutU7!XKs_=BS`gyn+N=^AU!t(>A)5No~YBfJq3E$ML#9iivh|9G*FJX zFdTCbYf=i!+fo`#z_RK&|J^o_k*lSa^70=2kXR4g!o<^OgGTZ7f`%94%j~R|p44}E z$3EJNwob8|-xzzV{(N%Q&mykf1-GC6dimQ7cZ=t%qg+;hT%4Q1A-{3st(X&+lQ_AA z#TzbiZnU$>2TjvA%2et*9232O*$w(jT*ymu%_ z>tWh}w!K9PBr4PFCCw6Mq}K~=*x*h|syO?x)%Rt9?ihc{3&Bp|hSpMUmpterazoV)GKvEUHT?Lr96)4*!2TV#M@ zk|m84-2yR7_W`Ag*ePMpV@VuQB5)RSRFF+q;0n5!PhkF;D38 zLEkV(gZ{SvfqCtn^~)U^t)n&~X61BfN5s&$oylIWyW?-ZI#`LMpl%zS1};WE)KoDj z3uLFry4cg-a*4fv5aQ{Ic9l}QerT^{fW`Q@Tv8_rnY(Q;_o78vpgCAdu`_XsGt%Ww zi1zQ%f-5L6o`8*#ZNG3xc3nhFBEl#xw3HScouE|*@O3LeFwDvN%M!?$L4si^SVGB} zJz!LbwWd~ASBpdZ>P|vJLS2uk<4g>NE>qVz*4cxaY_((s#80{5f=p8kXgq5h z&JF9a>Al48j{F`9(c_5zU|A=}>K@ZHHdFA~ZArzvr2J%0XH-nulUr8R>qx6IqHpe( zTe%vI=mZczTxJiA{Udqb$ka|G9G>9U#@EH74;+&vKdIFxib8CXgG8fK3;+yRlTd8< z*x8lsv+q7;@$LvDJv+f9;gur6 z`|^tsB!w0MgZR7$J|+X=zkWV-{%3NQ{|WJT$S2a>Dc2aA0?wZP=w_cmJp>&y&leSv z5GxM2C*E$T!x*~2Sd)a{&9JtQ&g4B%)YIATvkq0+%h2?^T^9>g)|GY8BoBObMG3=? zqgVLsJ>8WIY{;TY-|yY=6^voxEazV{Al9P9kAX%;CM5G7(Mw~gN`kx=Z&`6#T%sPi zn@|5J04C~7(@*XMRKv-d2NM9SK&sK<%l39|$K)V~6DS4u1*M=vgvNQ^!02U?mIMcb zk4EPrNy`q#RMZ=ga&CjtGl>{F4g{c3Qo+~1Wb4V@<&J-J-h>Wp8%Uj+Qqf^yE>2?= zPWe^*Ri98j5gSbErL-sa9)MX=v~$ehP&gTCevcm`crib! z?(GH0C6eMRPv;0)%CZp_@k*f}wS)gmIvY>tSNu-XU=kl!fUL$xX>{P8N6X-9fc6V8 z{m30Uc^}{_Xl@AF*t)EBTtQ!c%@T8jxzwz^mInze4UN%}vS_4lwj;t2u~;l=Wx8vm4kyB>(5W|M*-nd?GVqC~Kch6%R1a7d z>3l-#&a8Y17^)udXktkCj&?3d{GL&eC&A)yrLp_EJe?nRoutU9W1arr2>#Z4}N|KN_tjnFAYKVXAAhyw$(krtr2A% zxpGAtIJFzpo$p3UU>^tmPwBtmQ%y)jTXo;?T)Gx|h)@h!L`_r9;z z^Qb4bXg0`_tl6K-F#V3b9DV2+=#XomiAFSqj5WR;t!?u1u+@V5rMfcGMtUINy+U1f z1|zo%GgJh+NX+#q3DXkzHDHerk2Fu8g7A`%Sb;;vTW{Z^^jkBcVK;!C7jBL;QAkB& zP&cIxHq0?G1Jjyiun~gRl$xLu%%U|C^KKHMDT*Fd!<)lj7M9tljyq( zf_(n;#~$)dC{UD?(_I0~Pf>CJfw2*lpWPz{coQ|HjhZw96D**_=RF_s9DyXgo>fA|>H1jy}*@)A4 zvr_|*dv^f*p^-@>RT&p|F1%y^Me-wXY}XS`p>G&%cfaFwnRcfjhxQ=7aGFeiKavk( z=7A3VRZ6McU%fC!R{@H5reb6kWJjtBi_2-$gr{_Wr8pA*MtI(Rnn_TX9c;$e(*S5* z_Eb_t-h!sD$RLSt;fWj2^X-Axb~h5bD^@heqXVkG#0TMxs6l(fD1Oy|ehecl8=4Xe zFAN2Vy0t<=#^r5a-wGpnrvY)zBTHB<+#ObVCzOQk z5ihZ1Z8gnP%I*fyh_PCDU;kl_?h}B8NW@(ntxF~4NY^*)mu!!Fiao1`xg-?#k!CO^ zEFA$($qEJ0{3Yn5@(I2Fdg!gp&G7oytvz}Ham`7{>t`gH~^Qjaaw?WRJaW2pjCj4qF-SVAyIb*;f}~ zoPBpQiz_#^BkZCHJmL_#j$ytSCTM@JxrOC-Zh z(Oz_a1CH*O&!d%)O--86}*%P8beM^AEkyd;*NDPg?&Rt3qmko{|`tlvH@Jsetq|Rk>en+O4iB5TL zpbgqINtpF0_&u5~N~1b4FU}QUfC8#wA*g?m#x?H4n#9gMWrjag;%J@SW`aQ)h-BVH z=;)zMffp1n^IAkwG>^{)%|(qAR#Q}*itv>#c=OLTB?`^HvjJEE@6PPi)7`@$w zu@_%_eVdGkBD2`g0w@AE>~h|~;+k7f^Cf+Hz&L{SA^-ZfZLh!Ufu`QSKA+TQr2p#& zjJLr5Z+;?oE%Z>BJ)NURWyyYQx^^qSQW=t$mxtpD5k;&t^!+^~O_N*zi5p-c3B(3; zYu{Vf>B0!8eC7 z{kzc0zEj9&uco@T_ENx(5&_>a0W{cb`ZFl0^et0STAG0-#D<&BY>cz~LxjnoSBSPq z?*mb2KE5teC9w00{ct`B5hf2D1DuDwnggf5c?u|!a#2V|^+jr6;k3)j%d_y{dRXa$ znwm9+4sh5sC~odGw)FC^?>*r)z>_0LXJD>(nLx&Z1o}bL41pm!i0RkBvXNl&gR1I%@LUsO16-nBP3SR*e1 zT@Z4NH~Dg4H@-ya5LTPwMZ8|bU^xTg%xfe@pTA!28VZF%WJ_Xfvk5RNb>E?0>ND#}}24l-?pW0e@ zD2Mg020lOkNith(i0D!it$eYF*x?-}AeLuo_|mdTla?f+|=c_Ahga-VJ*b}-K(*iQbt%SFgLakhlpD4cMFw@%!Bisonvl(fB(unzW6NFiGp=U3P zkbD%f4`Qw(vIsBAfPwcCh=@}6V$8AH*Nb@}{XlkTmXAAt`R(UFUhiCXU;8UZlit7F zXKyC37cO*~*wf^C^!@XrGV6gE*HiI2RqD`iR*4)u1Xz6$Xl9h|kAC`7)}5yB0%+~t zmgayXov1Q>LT`sAAyaRB)*9so&c4`)C$y6`Z%S;sI@qG@6!1Kk$+-lGd!O$H7XY(a zkf-ATH^u|8Bz@;^(JcU4?4gm7$oJR<>p6?ZdDAAar zEfx(KG%)tgQ*oYP9;14usSx5${3!exlST&6P!6c|?5`f!qy#0yAL(WBJB@Z(U=o)+ z!h7ML+7mF`J;4cR;Q8+t|0IB7Xq90*81jv%&KHaysMo_K6=ZfCQQv(6%{fV zYvXfn-vQ(Zqa&AeK~6Udy?0e@cC`F7Sdb%BXt4{SwSK6A9`0`xOTMoGSe_edC5* z=Lr6lZzCXfFF@Jhd*T!4Gc{t&P<+TN=XN~b3)HI?px8hKHqrG1UcfX6%Z#X9a=ael zunYyrCv#EM;RhV_Do5om}wTGPEJrGD=rrgHzx z952vJv&@}FYN#S&k4n2lE81dS(=0JP0EH5*Jot(xz>hCzAfiOO1`aRsYX?F=C0g;0 zh1aKSk4h}=F@Cg`@GtYqDG(+C!}fyO3+uqhtyK*LiZXPfi#4fa0Mq|OQ%3|$Dh zq9LkkiV=hl^$d(Ij?E^YZRVfc5b|p0mV~JQQ?8q|=x9)723|^! z^xjz3mwrDx%yc5n5^-w|5U)mTWltdRVn-!mhX$((9T(BySSrvWswHcRZ(2-4C!yIO ztPT8pS0{SET)?+p-4F2`#nEpV(@+43VpK}ak6V>@I`#qnsTu~xwf zZZ57&@GkX0!6N%dcrMM1qm*$FbsQ9#xah2BpoH?o*wZ8`Q4m`^IlfWM1*VZ7?>M1)<_bt^L@*PtgwBfLW;~y#**xZKsfFmuzM#7!xrVV~(dBQ_KH8J;B6rVj^V!fT70(CWQ<{p#pA}Hr9Vb#=({jn@2giTQVTOwFoGMS$CTf z4%@1I4s36aS-%mTFVW<^c*_ZSe#@NYG4NvwNYroIH-neQ0YNBt+0lP~=z{2T;+|-K ztiWhZ+E|TRevl_N-Q!X~LTq#Se}q1H{l|(^!i*`dtNe`lgpI1$- zlC*|Nc-f6KDlz0dFcUg~;wZQg#IH0g_5^uOCO98Uz_PL-9}G+0^+rQ*W;z|@Rc;9C zB1k?agTKWrHX z?4AjY#$zvkhr7Mcwra-?wzp{C%R*l$FW@rENxFx+x_UOaEDd-Crg2u#RrEk3>`r7c zH{Y;~=t+p-96@m?190}@sZ!`puoZ zYgd9`9J^8WBa&Y!A$QQSg7dWuqi#L^GRbPHrz!P*EMhhH%vq zILGn%)+`GsMKxgN_Ufk%uIr1(Ul<@JXaqIgynk~GVNB4N^y#ljz?v10pP0u~4g9uj zlr_Kh>BooR4VXmfPTUz{H-Tg2sx$Uc-QvSvf0~u8dHeo1EQb^-18%evyAX|KY8c$| zDf(nCpRw+K-~z-3z;iJmkw&ynt_8&n8tfChfGe2P1K z-(eA=#71iXnbD~4;yEdgb0-sI=O$!H6xiHlpFkmU8I|v%#GfmlJm>hD?u2FdF2uChMP6m_aFr>cfxD7oe5b1~#P;P03yq%c2n0D3&&) z#E%#x24&KBcFB<^aD4UwS8G7&(3AW-&B=pR)o4AB&6$NKzM60kFbEbjJ|Aw-d5LCc zT?*e==UHq%3hio2vs2j&H8Au~R^%xkm9Gc?bQ=7VU%8iiDr{XUTgu5 zP$mci0WZQ5g6Pq5Cm)S``-8~H)1U0&OWk7&wy$5ALe`U_vEQ2GWJpG&OD!OWCFc19xM+}%iMI&7yD=G(tK$uyPwX- zw3mebD%wVH6nx*IpUjI|YU*MUV@p7+IcP3;#@3jjSs8Y;`#nD zDnvi;jebr+wzuYZ2cwbH;U!&?sp&ELMZ z0J6jXdU9~iMQ9*2-Z*B;B89S_zs6W*1ogM8ggf5$ud`|Nh-)SqOdGNajg~iXXqC9* zlJZx#B*oUJuo+%x6Jf^7k#Ls;J%L@;7^oJ*ZT*p2)TN1oVN{;d&z|0Ijvst-<+J0E;{bQJYio6G#&9 zeh(i$886Fh{PWhF^e4z)DeyBgLDpLukpvGoPMv`M{q`8ing6T;Ws~t^cv39%JF>y&m&m=dcg`yi$T=|QARCv$J%QujGz}=E z)dj0xYhJayIrrOSZIi_EV^zWS{erDg$$9^@^)Lr^B6!{(0lJc8_!y>|Upq3;u!iAU zUBV3h4g1R}8zZyg4r*Gesgf?qY?T*?=ZMpzZI%MfG4Rk1g(kgYmupWztT>o&?x=E# zB!`IIb$yM{&15zK_U<_XVm{Ze(+v9sg=oxL8)}pgoQ#cLt9GCS*0fX&jM4oO)~)3m z!^ebES{%_zrP2OFy6292Y@aTrO^kKA^nu>J3vp2RxhKhNZ|4!$5TLiO<}w+38-(Dg zd#&^MoU18Qr}^9&-~r@C)MLvO;iX-_Pq$HNffoJMpqTN3i0?(N6o^U)T9AsMmTidS z50SxgB7+)&67n%Nm(RJj7eNZ@IR_K_poOYHDSTZI!aU*==z)?JgI`9O(gVc3T~NEa z18YrL0nG&v-LJjv0-h`}e+Gg_F5;EMq=HIyD&FbdNIgJ~i2k{{*~?3q%Yy?q+tF)Q zlp#zkyr$-6^%h4=aF)-2X2}8yNE7?e`t}s0#c=zyWVQz>tSR>pKYAH)%kt$q3mEx( zQU`~cre45P#F&j>FS-%rfi+uD*xcNl4aGmMx%_A3zUSGxia0xj;+HpH7h@8QV0~Ts zP&@F|yeVmICWZEB76OGw42g@2tBnQv<3_j&(G%*2%bzrWWaXZmoGes$Y$@vrBaJ&t zXE2qyM0F&UKbw0GmDhzmpz-xFsR*DbD~sJelZg*jocVShCGdlSuHfLs&?{qTxHHlJ zg26v@X?7eg2^LJ(R1fqxN7v+#0h- z{^!Gu;QVqiCY@3!oqiPgj<)xx+43v`Bpc_-a~L}v#!k$%$qiLI<> zFJ!%4a0}=16viP83Ku@yH17K9+w=mZdoa>5U|>B3iHozaG+cdi>R7uu>*YS`LGRZ- zMff<(QRb`AI;+%BrROOjh|pE#op$$}+x^>Nm%*8P@T!_pSmOA;YO*2l@sD6vwa*LGrO?q!li!0 ztGzW2qydj0b?{XC?ce5;mlS*Fay6HaNi_vAlw2(Zuv|z8!xQXaTRM(Hl=MUjAVUrg z8V%0ELZDTm7ca8~9YC2B)zi*Lo%du?$5qO8N4_(*1;3}7A{LhQxVKdS{y+~=^1E{3 z{BN19?9LQmLLw~4<{nNmF^^Rf|HSQ$5u`v#LVUd@a6H&7(Y*pQM~(d-?MHwK}#L8vGq_M+8Be*+zi`*&5nXyu*d#6BF?v9-)c_4 zw;V)wp^X`+UNwDLJ1@*kS4U+#lfqy^OeoB*Ng3r^Zq68oxNUm2mcWRuCbC1h%CyVZ zDPQ+bX1gs#T}%xG!vH)rA2>!vn&Kkxp>Nup!WV5hnd2R?al)~R5K82GWN_75M(~hK zlZ-MVlm{2FMFh)Hyub01A3eo;BMbsKnUlQf1vJ8(n4KBIiw8nW5-vE|4=Dcvbv^57zwv~qZ+NmG|i!|PDC!^ z#eM)NOegthf+-JVbX*8!esaTPQI)yjm6v=4X}OuTwox~3$M5h!7-w9yuFaun;01Lfz(J@Cd_2in&slWei&SB#I@J;k{# zLXhEZ{xST!3o{ScnN~hp?l|~jnXhIVkV+N1kPG^>@j@}EhxWQSUMS6YcLOa!y2~D5 z&mCYGF$fsJG3Vz%-g$v2El|z;HZU=r3ftv(Pb2%!RC0tL1ZDXT}u2!YA$dbNUGn7;>L+W#CfYdCEnj4 z{6BMCV8V;#*Zp)@etnnr=qz0YxH+r+Kt?YU%@rHi*QNvG_uSEHW1KWXE3g7|7gmBh zZ*%fbn6$&oax^$ZQ3=>?a_tuHeAKf50~|ZmPWzC|`8yY({dG*~d@}EdkTcNf3_f_! zWilmj0~gS+-$>9b@rv=5_+g3j2c@x_JcGyD3{*dI<8WB2ss_tbatrB^T|@}g-!$PH z3b4-tl<-UtJVRh0cnZDvB_0>|;6A5~r9jEerqGJ&W!y;YS!#lq7%iM|M}MJu-mN{@=4Lk}&Yr5Z%-g76 z9)Ok%D0!K@$l{^GhZ_2C;&}m5N7oxAF=v8}ZGY)jb3$9)*%rBWOM+ptN zVZ8%1AQY~D5fvbOY?q#U{WG0K^7##k=x@w`T*kpLglss+spn*T=Q6r;ueGSmrCxsj zl`6rm_T4`*l4AaI9-SRRYDawMwF7%Jby&F{&}OK4sBc8GnOu7XASNP+zl`MO=FXlj zJ0X{|0rsZ{N6GbU1lpXQbSSgDmMz1hKj?Ocp&6iPP@*|drQ_xkI5-^z@O)H)9$M0o z_s(Clh&FB)_DBYPdnv-T%>!E4Y%IPwn4)_Jyb-yC3C)Wk1Pn-mnR-2d<4kY_8UX$& zNm(Q7&PGVRKJYh|K@FabP+lmfS8y;+d-PRr*wwPWQx1%k)>d}i<`}&1#Rwvk;ip}i z$?xH)KYXpCD6|**%Mr)Q1ODv(q52*mFd3LT+koWA6DDYNkOTPAjW_f>UG4|j3eAVI zj8Ohs?5cX;e?MZUZHl#e`|I2+1bcqn@;+-Qef|J^Qt`%5%jqA3(x8{vj2`KQRH1?c zQvC>*>U~pa#Lk?k$2jK3Ez)$@34n*8+BonEup`}`tGPp~Cf75SIuu7b@}gTnr!x*w z3>JEdXF2@-6P!iOzI$wK{5Wfis8pjEBqh%6_zs5BRiq;&qxz%@6}HDaWc;QXgqDq zutk_HbQWxuO))`}A%|otQCuY~Pf{hsr5R$yjcB8BH@9!(E0aMKp^GrR3kXmaL0vXx zxDUep4D3sEH0Vh2;Wrm@bNgvPN#HPnT<=^S?y6%x>HBF}?x6x^*DK)CYAqCAn8BAH zyi_iLQL5a#P8(__Il#rer)UwQ7{jR(dK4-7=&hUE_s(rk!vOm}6Jz7H^ zmfoW10rP0qzzFzuX=!U~6RNM_e;h>@9zSmopf&zVV!d^lc>sM>ALVUIT2+pC^Lih* zoGctT6|)<7HapJnc2S&JX)%Uq-Gd-boEwH-!=NHl9Kv6Lp`nXGxaIYJ91((eG zgUq0AXon9>LJPSSSSP%6oM@`Ou2YV4pr?z6Ym`S!z*)FK>*=FI)-U1td|Ir}$!FkT zEkPZsaPI^JspYX@7Zh%Q=*ce#^gbK>+sIIO3aMVAaqF)Y1L`ODGgf9W9@*!}QBVZg zRlC|xYXOQ=`sK}6#29-LO>0C0fRdCj+ClcdSqHmNNWeZ0Afg=XKLS(_1sRh6d-)g= za;wXcdcN8F26nqCX%8RtXI#4snIp>7O3W1Q7 z#w|AIYGoXI8-Soe)H$1VmRsx0&y>NeQ(R@vtfeaF0?2nOd%+i}4$5Fp*->Mlr3njc z1hZ=0eibAWjD8C$bSK8Z)sHH5z?-!u*`P*$Q|YmRdC(5n9T5#x6$jJ>ty$Y}8*3ZJVWv_Rnyj?V z9Po7-?P=(9%NPdcbhB)nX%mM}_dJf#sa4>44_sZrTW}~xSIVuTUsdy4b&TPuMQ;Ruv2yn58{=(ip{a7{~wGkv>$j##GX=5eT zkC{<0(p8JM+(4FcbhKB8*H?_W9ttPs(s%d1*Y%xsjQ1Q0Mlji7O?mj^Zv?TnC8$9J zcfA6|I(GYxdn4EG< z9!NqB^W^zIaCX;}|N92EzjdBT(Q555&^|r%Eorojp=z52&;?<~qD5*SN(9*ie!0h1 zdJ5m>c5VN5Vr^fy>7WiMV2e^Dgjjr12j^;S9)jDTBjzynp&bAc?*2?Kkeu5I2f*Fo zy=29#msnLEcj*K2A`UF-jgEgU&NJg(!?LRf!4;?Kl?zZi>PHPiJLriq$h0WiA78|z zD&j8oQyNU&i#);ZHkHT!q}Fuf(Sa~zTpMtdcSk${7I$yDCh ze%_e4?_G*0ny}!u93}rn&KLl|MSb0SJ1L|_(7d1!5%PU9rLdF72t`PEfeFHR$wKo!>(;y_feUb=pC@co48UTBMuAk%D|c%Uj_&;J1f(sUdnr(u3|rWM5QN>T z&ot|prhA0D<0J&y2$q=WsQR?j!Odo1x9fySvZCKjWCUvdLh{9<^NJ>~g~vBz%pO(} zFjxrChR^rBgcwUuWy>9m%K$TE4ZVK6$DMnxsk$Qy%A5)gq{ z8nFjac&KpdVn8{XQ2l0eW;bG|w+gbu2U*tQ6{=;Aj}d}oHcT9s}!CGL; z=^+GhF~DI{BajyvgCJ|oTHJ*TE>o7HNmT$X2oaYRx1u?~4TylRCIRn(=v*r+p67ha zOL1n-F``9KL6{yQ<1DE*Akp6i?XyDx5#6{`RPVZ|+}WjwW}iT-Y9rMSBxrQ2m5DU0 ziCR%Jgee$TQI8H9OUD>5WwR64Rh! z%6|NWAe#(f3KtNAA5R)~M>4Y%r#VBI;AEH=bMh>`XQ;UC0^<18e_ks!Qw zLLacS#m7zhZ5F1Di>r3Q{;}`l81Y-XK=)nE@1nIib7pe z?(`Gjs>p8?sIFEkOa}!+mWUH@q-6vwkayxAAB3DBq${We83#h1pODxbXc=MKU5{f% zJ&*6op-Z_C?$6A2=9nxV`3b>z0HzjFEkLRQF|Q2-V)cM0?KOJbz7l>So0=H`l~6F2 z37OJ6XoA&fjfcw=Z*&)KfH;Ga6h-`l7(T;=OyW(HWA_~0X3H{F^-NN3FdHN65J~Cn z>Jc(?ThPDAs`Uba^@1gmgmBH_c4wbw3dmXLQ61* zO+K_E2;>_oC%SC5-z8sru0%cvodu|dV|4sb4?kACuXOdG%P$8XbhknoF|1Mbw{ z)ZBsUq6KK1*?0yX0#gW$9xNcBj$lMcpV(cJdHrFY>~N76@#Vrl4Y>jlPHe#*^dLGG zwfNaYAq2Ldok{!%#I$P%YT?sPAlReA)gVN(xAx0|xInzTE5SO_g>zW0SCSP5gb)uF z9+jFyxwfYvde2<`C;tLSE4tv2(|bw=YKK*K|ITTF1y;V1Dx&x+^TH2|>7U(oKk0CG zq)m*2{gh!B0)OHcKLS~c z*MksXQ)~Zn-m3pX13BO`?Z4`Aem;iX&mwh?hz%3Fa2U0$h$#Zz6)R`Uibcdt7+L#x zdKp5Fj1pzpW09;&0gm6}sDw_vMa%BT4B(7BPi|A+5ZAQ6t(q9o2 zkJ>~d1yXUCuVg|Qs1bIsWHiMe*b013LwP!PkRoWbvx)=29~&@4`E*mW!NkU4BFGT8 z6~egD5w-Bx@L@;b!*VW457Y{ylowAV37Gw@VPS3r*TA5V15` zN49lr`rCs+NY6&Hvy|XrV`-!*9nYv*2nL!fWiTev1>0LA2)c_+6G;Y(pqB^urrq)?En5 z?(Q+^2o^$2M6b4GJJ=a|h~TMLe6g6BRv@A`Vw*ldR2JV?30RsGaY&tnhRfd(%O%1^&;~a2B{U|;qJJ8>v zNP#H`73YYk4ME^#&@*-0A-7Ax-(VM zl_o3}P`LtX`9^fCEL-6vJa9LmVh4bU$>kH;^XjJ9<~k6CZD2o$gG(GB8zd!q*jv=5 zOJNlPzMU{Ah@5`{u(XK4evFeZ`*bO!xMAA(r;1bCGO^=tA_)?0l1-}4u6{CBgCKlAlxbb{Q#*B`n0 zG2puW>m!kYdeFZzigt?8;~;+M_W&7e;;z1texD) z4$tHaCAAWZ=d-!5Yw$s>ijduP%CjbSV$+Pzr?m7kGBp`eP}^#P)|B%i(20HLVobzU z4kRQK)fI?(`6#DjCy@mDl!|=*?YmLvIwzjxRugh2l;Pl)_v4=Pj`cc#Gtvm?eD8%7 zlfQWT9ywdqN8mgHX$9EFXn=Bv765hcxo{@{Dzy&`!Nspg)joQZ7d5rxrjQe#b8o6u z(byG$9qZ%F{|JfQE`ad<6HvG_5|!4D2b=QPXajfJ+SqcG(TQ9AlCvxs`CbNznE7a6 z=$@Js;@!{7P`c{#gNT}<7D73xWh?n?*OHU05*JOGiR~{59v69MWSI^5M=F=-ueSB4;}dFXC*ZvG%PFNN!K0U)?-CT1*`~hR%Ji%6M&`euRr2o{XVADs zS@*m0Yre;<)lk(m7J>JERZTHFNnw6|5k`-vz1@M|t}b%cL}3c$=)D#JZIrzcbgy5| zD`rM1!@di5YAcW?i?`gp_A;^_fzG=9Q@-;qk>gk&IrhCrnL3W3akM%C8n!e+IHa`@ zvz^72+KIAYX~HR}co~t$eR1~5-|)V7F<|NB9~oT(D4CbrV14rKl#1R=O`*?eI6`_46Zw_$cl87XdMvQp1^gn4k#%T4r?5X za%47fX%JqrM4l+*gx(p~a2@suwP>E}tdpLPX;nmTx&s)q2yZbWUlU0gi|~PB_@>x# zFm{ekeXsM9!`gUfMoJi!!}>g0nFO$}5#g?4d^4cO6Ttrz;|(;ZHI3NB{_zOHGEu~S zEJHI+8^LdMM@p9s>_5D{4(TL>EzblJt+05{8svi;AGUXFW<}=h=1xhkj>4pnToWyn z@w7l;X~gK4H=!T~CAPyOqNbHUksj4yJ70Ye2q|Ls(_DsYtBnv-0F(E6h$3H$?5*q> z`rAmIh4{*3BY_GXjI?(8hwys@;9E_AdQsrYBt{yQ1?w&f7 zZ=MCZSol~+z|}ZL3!yNz&AOIMUXC$Z`+y4mtdG@6LhDitHc7GBp!u;2JH%I07OcO= z#RJ4_2Q%c9R0UE1QuorsxO!Hf6`WQG3`G%6CD_oHadt9EUkA~342lqRj;NE8m8-aN zt$)1L?gH@@GHB+59&(9wBvM45yU#zL-$hVi7DrF&V0<*XcclS!sCNv&lAebta1-j2 zLJ{X-uR~c2YNh)l4D|L~z?WH+D2c5OGJ;JTZ8MN{BjyfCSKCCvjc{-jVc;%!8G{q$ zglQ1zf#md%JB1qz&H{$y3QBG^_z(w9jUgk;9iEE5<(_@D+SK(2tp}ZvVQluiu^^x- zS(vfRk07Foe`7dx6=v9OTjab9%_RU*gr3v^2p)u~UkWIvDhl&~dtLB<8I+$Bf&=;A zb+|^tG3!&s$n7k-ossk`fwMb!;O)lAH33eL!y;s`{?lp~T6Kh;l;c^Bf{=G5nW;r- zlbAU11Hi=AK2D&@dq1P`<(FXOM#Mh0e?wMCY-D&{jK^LC9elZmXSfAT- zP{8MVS5CcB3)h4>qBiP^x9X!=m{kI3kO=mcCWIlk;np=;_&78)496eiaZp-sEtES+w9H=Y1#`w_>5o>V%ch=-@Rv+CAYSTT+PGVDx!#?DJc{ zyTOR%Zb9)s-@9LQN{{U+Hk3;rh<)mIg(4);11K{u(r$Y5wjD7ZNaLN_)1|+V z`dwl?Wbb4%_dM2v2$oA98tGN-3Xua7gETLac;zv`4~;u--oq~R(1Y4weTNuV0GbY&r2xBFxBuD_I3FddfQqko0HTs^X~NN$d#QDo$6%K0$N!Y362;r2(=1G;8aD{ypUi)CxJj@9CS|GP`% z2dJ7wqRdQ{bp$+~6ls*l#xwTRGKWliK_MYr=oI6G?72G?pGcc9;?-65>36H!{5eGy z*tut3I-L=~T6e{jtV&BcozYzVBS~ytDoBMVV(E?|D{n+|DT}5DCnvmVbH!an*(X{- zOD0$A0srR!aUH^d4%&LxP8PyXbGBA#S+e3gAQoIQX|Pm8)noN3qi04QhpWMP=KRal ztJMX_mds}CHWPik<5lID$$PbU)#O*mC43I9cjr>I?CF7L;OX8MSL#1$d#D}eDz-cc zhll(OjhFFBO+)NXhzP;Sfk3%fqNLbDS_l=pU|Lms;(XA(7|5z7f8NAZr>0M*z-sic zDn@j!otN&v=%Db%$7VEJA%oyI%uk5+9U-iS`Y}ngmaK9%#kA)@}Qxl z@rIAHY3%2-aTP$Ck7hWw5+OR+PSUu1YzoHK5Py_bhe`-Btx-v8H7P_aru2uz0;s7S z+|(WR~u}q`K_wNNWqnBW;vb@k^kJ&3m#7`ty2IC|< z@GC4pBHcwrWu1v(_4qe8KZ6}@QeTeZs+MolQH9!PakULYnU9?q1B$3*bk)fORU}e3 zI0frTluRA)!7b1Tzw7w%f2``qh}7lGHgkbrQuw~&!bl*FB-#~GIJp|k-H_Y&rmP`T z$wNRjfo{l6I@6qxo2UaQT+m7|*xqaQ$536q1CL}uQkHnljfCEzY@H2Gasym}JJ?Zb z!v*;NtZ&x@{zy^|1h!*bi)L}*X&_);qxQjU=ro{@TcU%^9;|vS#JSsxNRpk^jX?}S5)!YBGg7(KaTIeT-1#N8Qe$|;t7oY30iW9R zB*>_Rck-Ja9J3$YJo!ht?+{?OmW6ZUbW(u*^4%I{O>SYK7da+CoO-C8cM&y_&~0&K zaO-==Fy`ZM@?e9ThX2Nr!VM+Gn9E6@14*9)*4;lN|3V_ehv;k{u38Q6%h^i&1f#3% zB@{5=*f(N~`(-Sa0?16lj)idNK0X>-r9~5A!M;RG-+x&YqOpE9ozZyyB1~wrYz6gq zw?)85>Q+UqOqe2DmuA#zuKJ9lfm=DE({Ms|Dt(re{CqWy1iW~vzve{_Kpr#GsMsQX zqM~l>lGU*eHvWmgM59o%iyBXNhAQQ%nug6fy5}mVkK*6A<9rSk>3c8C_~zN86+$b_ zSAQe=UB(5KUvKC?`w+~2zGPc|*-rmTom?Zc{B|w=f@KB$BUKWP17p(fT4%qpmrV<5 zZtSR+iZ$R4Tq0vHZfj?EwpNf2^8zRu!tBnS&+GYR9i=dIJaFhudwcuN=FD*v8tIcB z>@_WgsQdd8@iPK*=FXj0(AwIHD=f>@eu)6JEx4QO?Pb=I>gnkf)$>bQZRoLco1IRT zOlsNmum5)PV%I&ty4Ln{4?ZMEMQysT)O|LJ+emWzcFXEjb_jdV77c-?a-+pzY;3Hk zs!HRG_J)M1jAT4;R{G?nn3ZkF&1V~sk}5_QHa%660VjhGRf^foXa|)ryB2viC84IK z=4Ok--1+>MQ&Uqf_P`eEPs_y~u$`ehc`0X(ew<*gK%_Qs_NU;<50L2KodT&#bNR{+f4!*^UFT=`l2ilEsPhM&~ z;LA#x!Z7V@rhe1?H=Dv!Q)SSM{at}uis?uiO&mLcdLN0o5`5h|FkoQSFWcAGmkF;E z5*;1=)*OYBg;-brH;D*9#4Q@+pAQlLBWWtJ*!}01mnteEvhY?k=&ob~#2tpu?dN;f zjDTmOxE=8Dt!bS^B_}>+RO;|YLo+kasHiB#0y2$M({w8@FTay!2a~xqu`}3p%!6pe zq&?CrGx<;g>`r|A{QMjGrqxcJ^rfYx$-Uj#oV`n)YB!5E9Ql!)0(mrQX5bz@jkuUH z_RgWdSVgQ96HngddCm?jsU&s<2`@+RLJcoF+T!2N=r)v2Q-}S zaXSOI>Bh*^ozI6bM<@Vi4CG(U1{`A#Qj6$`#lhEueSc8^@5qfJ`kD9EQ@7ai<1~)k zWQdIq1H+S_pARXhF{fKZr7<)#%(02RLfv^6V~NHF7I{JID0Nms9b^%8Sz>SWY;V<~ zvM!Z#uxp=oJZs(6h|va{rw-XD&V)QhVkHmn|H1Eb)3 z#b6g#CZ1)fJ+VY=m6Z!G+`2$K7Qz_uFT6-*10TVp`OOIVNca=yH^Un;LmKwbG1>xL zkt1np!M~UxCb1HH@eSI^HkDP8PwIG)6fV7Dhvnp3vSbOyCvv=b^Tq;Xe$ts~Kw{_#}U zb71?lMP@98;Z_VyO!%xYy*Twjbadf`kY1v)#2__2ZV>D=et{~3%^s6W>YVK3V>_7` zFw7=?l9_s51+9hPMnNN6h=qKYm4^4mJu&%0(r5qu*&R0-179qvuHN1>0^FbhB}EJL zm0#Bl7ZKUE4O>+55Btr~@bdKZgn;V$=W3JRCs&s|9lFXz5ryh_TClX;HsZquKG~xH zIp0TJ=JN6?D%S?5%<(1x?P*j^z?uSBgc0mRGU(tMgbSu6*oC9+vT!VAmm^YZc<-#-71*eVN5Re3!;Jg~t$m)A!_#^b}skFNMHU)}YSk9+&@ zm&e^Bg%Ap-MY_q($;nAXOw3O=q_`4|RCwYHS?#@xrWg5A_UA>u{)$w}P_yK>>IeRq z3Ao6zZmrI5zx_sa%}T%s-c_hrYyb59w41N~Vy_tPD9SZ)KMkY?v{lk^)aKi5FDu|B ziCPka&ei3y0Is5E@lEZ3b)TlQ%c%p$thyUf`qkhO){iFyr(ej_zjFTlv(=vZiNNyD z8*=I=yDv}sx~U&93s(GhnaQ>IZ*8Xc#DDu{dL{llQ`0N)e`qLj>e*^$=Ipf=lYd87 O+Ou=NeAF+x7ylOq$WQ?Q literal 0 HcmV?d00001 diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/x_vs_xd.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/x_vs_xd.png new file mode 100644 index 0000000000000000000000000000000000000000..2b6a09c82001f8da803fe8cff305fb37e8790a37 GIT binary patch literal 344059 zcmeGEcRZGT{63Cf?NkyH5?V$Sp`@&m(X_I6Mr4odnNntoL}i4^mc2(3qL6G^k&!KX ze~`}6McxF2_Pxt!oi9{m5dPQ8GM54f7 zcVFDO9shfGvPBI4+iD|rRbeOoxa`#T#@A$)S5$3CBn?U8zfJp}U%rHI3fz-Wxp&Lr z&OQ6v)&?ZA+xIL@E$*4#)je!yU~O~P!kmwbhl}^*VWWHZEH7|#|KES-vamMfX7P)@ zMj{<1T@}Bi;1E96S}G+9JLwH$UNwdY*t(A1|Y1 zOkRTbL(L4Yify)`-+t+c|Blh$ay8HE*F}0=oy$!U`|@wng<3anHoJR!V0HcAj3N8? zAB{6!C0f->qxmkP0TlDIcYErqzv}b8#P$Eb{{($M-n!-g{SEwm;~0rJlK=b1|Z;-Bdlj#1x-=RAC-`o7piTrmq|3=1tar5s<{FhVzo&@Q?LhpQD|K}wBD-{18#eaq3-;?;SQ2cum{}qb=a}xg*ihqyd z|F4C@LoMurt?}=Hfrx3_$>N1UryF_frdC_&yklZwGE3au`UB2c3$qfJX=qhWey+*EJ?`dfemQyh zpi#i)_AlaD?gl}CfC#jjqyYWg$hRF2ut z11u~oa#~tU1_lPi|L|4;FHWgTetmH&)^@Z-PF8lGX2Crl&JRVrB5QwShMZjRi+hh< zyMA4-{1JJ&%}`xip}ob}&s=T}4vv__L=Ne20m@TqSpsu5>+bF?rK^9x#^Oc9`z$Rj z<*!qbxCEHp7H^xjr5(w!=wZTdx9a_PU%+lmML|hPk~P?8b#*mw_Q&;D%|g3|biFEe zc6RSipFSD=%rQ%q3iP37tE@fOCR$(fR0+w>*+G>ZnHY7)y$e_f||&s`zP9%J`b!%(wRSxvEHE=a}T=lQlIp z#0{(En9`@HW&0|ns7XBD%NV1cYaXZ7s%fuzZ=&;jtM+!vrR%sHm*RNSSj)&7QrR3z~G@Smt%U|b} z9{qTK3y=Hys>48tavyQyIM(JrLJ=2ieHko@c((7M+gDLh(U5Q}&M9(s%)H>w`@Hd- zpSsh16>(kbpLTP9{_^Y?aVq3O^rSOdjxTSp29F*gk*v*{;^n5tGV3E7OUyd5e1d|4 zj2dDjUc_ydKVv)6w79-d>R#zOkv|kk1pbzrTWLR}sOL)Nns?RZ)rTl+(c@Ch-uPsg z4Ag{7ciPl9|6Ka}_iqgD=~+}1GY(mF&KS3wWzn2@TX8jbjpE!i`($cW5W|_UW(h|M;tO7H%WKn||h6Fo$Z|scP6ZD>lSR1+sH+_rumXvYVXf(=;pXNxJJBV$JU`B$z0%PdgNN5psP98U&z{~%GCEw+znK)E zg-Y}-Qg|hNLDc&9m2WTk*d|I=CQeFkBc0)Yea_;^pT@W${c$4O7ACrIBuvD)u28Zj*E2S z7_5(S@BTF)HQrTtZm{+>?aW}UpA?hh@dDe?1E}6lew9D2nrqe8wivbiWj!tze1nx* zQBhG&QISUK$sr%tmH7y}(t7vx86L~tk93Fxm$@YES~Zt;*-pL0*FS#za3D$;h5O>= zL+7pEmbIiLC;Oi@Y5Dx>tV!RWxTq%wPN{vqd9G`JZnu+3r`yVS1D@da*W2n^QJHiX zr+!)CKQ+dMk6S2qdYH({$x#Ng-t?^wW@{bY(j|lXY|@$f;p%>iROv;+JiZ{Xqc<>Y9 z*>fU^X=$g4Cv=cmccV^l^7Ewo#)`vm^y7p2OeCYRgA+W5QIiqQTF+m+Xc-AxUcDzm z^3dSqNFwTifq{G`YSKZkZMzSA?yK;_ zy>{8QRz%o$w|h`Ws7gpktS;5N*Uizz70tD%Pvb!OTJJ>vMxB=BbSYI(=+^}|PZf@o=sChozlA`WU&-Y%dzo#()PZce`0twtdp4(G5 zqP8(twuAZe_vp+0E$SAv#;Yq&si4|EagJzDAxgNQ4cZ8Je4n`*Pz!W`)h9 zChkqAN#BQ?Sq3%ptqoc%WT!=M#YqPg6&3N7OcXD4YXp*!XhRT#lO-$WH(v6xJR)Z} zF#a<)5Jj~z{Jag(#ajC}eUwNjD7e7nzBgzX^pJZ|c(uN6UHJKFFK(A3k&c5ei7=5K+T>v)r=(=p(sS$VZ?>CO zZqkuL^fDq#`mf(NVKW`{S`!=2`U`^>;z?KTy@v#zj#~A4@;lFusif&#O05EZ>MlB8GW(9Z!gZmG7T>R)6HrYz z?_}9<0d^DZZ8^dce_^mC^N-yB2 z^XxEX&+6bg2Fn1^Owa8Q3l7s2v^K)qj~g^6D$1#-sKh-!e5Vmbsvi&6|I&l) zOL_*RH)Uhp#e&<(5AF{Xo>yrRwWSfM$(FjDkeKMJz5X|Jx`Nw{rzKSrM`c_q{66z% zzK!ARpGGzk? zg?b;i`_lE6)`NU^Zk$24t{lJh{)P{5hra7xq$q&X#aMoP|BF7a?FGB#**|icnws_0 zn@Dd_QC+7|^aQv7F)6i6?TNHGO8 ztMH}CXY!J)%$DLRLeeyR&@K%VcD75EN;ta^W}Kr}^=-Q{o*7N?F;<6iVtpcNyFX6&Nre&it8wpHj$39 z%0wPQM@H_^C~HvKciAeJlPg^3yYubKlJotcD0h*#(aYD|7R#9{FQg zjGN-agdDAtRnm{zjkQq%CHnSP1y%tT=pw1pQHE49^sge4N__+;i}*USO_bxZ*MUT& zO5N6U|NMAodx446YpUhGHaFb*L7OV7MWVm2<5=huW>F>r(*QONI6YUh3j8yRtm$Xy zS(J=ecmI)fw~>Gyo$ecJJa>P*RY7qu?abq`8}FcbOu_sFaG0H&I}o8%SsB2fhtADI zK({gqw|x(`ll!7l8UEt*>{QFM{IzZA>BHyY0#-*Q{pl!Wgy$4erK%H&A7r%eq(qs{ z7MWij{Sb(R7C?eCOcu>Z6LquZ>(_qN%XHvbqK$lu5*4j{!pMOBmom3SCy-I_0IGgE zf=sPmiNVlWU>v29K)I?Bn@9%>@8mNISVaZ~e$$J1Fye{c`^0u0d28ew7+3}D48YBA z+Ec>F&(B}L<%54ZAy$E>EhyYFGy5GgsJKY zW8+nGvDsP*(N&KMKiZ_V0$&6*YDpCQH1oy z+R}CWe*uZ9WZogSo9s?$NoA&|r(Z-^S`B|cl4bT&X}p8%$isbNyQrzCJfAQM9zAm5TOH@eMynFZVu-C7T@$petS65$=maar0v|O0b>@0C* z$hGLH1f+W!62c-Ect!3~6_aC}{bcuPe*VEH-0bWZuU*@P%JDQj+#hjbylQ`no&95P z*#qJ_xl0zsV)=hd>fMOq*Z;Ebp_f;}+$+|buX{0h6eaFBBC~g`^b?^ z<&P<<${y^@v4gNOjLQwO?okt!%zjtO+7!eyREz5JG z+2;KyB@TcTxJille}YE54H$gtD|e}76<;L|*9#3z-_Y z-t@AHN|wFwCu<7@-0kEOksldTzBfieVUV$Z6?LSaiOT1zc2|KH7ABt+7kEpu!x$GF=c-1 zw_P+GIvDj(c9;`^xsAfTytbV@d9t^+mqfzESFtk0%g1LmKc>2M>(*Ypg~Q+9K9#QQ z(zu-mOu|mX1$$J#r%Q=s-TNb-azMJawpQZGm7QGLC41c6-5)-D7(cfh9)1YGfcp0B z+i7WO-}CmKZ=h=|9dAqDvNAv3{{-{F1z^D~+S=N3e;E!Qi~%$=LJ>pAJyianbsOVI zTZyY6mqy;38OGN=FL7(E(&6!=yjLhsTlI+xInUo{HQ0X_4X+G9z1itzD3|8xd&9Dr zEVTyc-UbBJu1waV{B4Y`P9q8yk=WA}V^+ojZ4U6%_=cBXs8{djhkv&b&-q%Ej#@xOA77Uw(gWXF~+qBnH=Q z#>MYZlO2F=D*fq?jd1m&_^A}!J0T_}rZ91DIvruXxV(IngX3D38ga?;yaspf!~idK z7TUgi{aO$A>+S3N33Nw{_2&2cZr!?dZ={KgQ#n=q#*IB(T1DO^t}BVzTi8z&47VNA zy~PoNvQ>_povs(%=>6oid+P6B`J{lhHWl>t%da+{y{LC%)!N$nG{EJ=BF_BS$&)v- zs!OAE&CCMuWq)VBjkmx5XBpA8t?KIP)qg3EzUMQn)4_D^C1PP{xI;=xik_3hiQl5z zUvy(NSg-`BI}elEUS<)0U;?AF+f`#F$^9A5?TwR(l5}wq0)knL()?O+#&!ALL>sdG z*zx1y{ne$+xtJYKWgocueA&4KT^n6qGP<6xvWe+6E1uj=(O0A!IFP4QcfnSDsjE|> z*E2Qs2ejImlYP5G{Bg zIQkwDmqK#+10dN{F)%Qc_w+D>Y4HjP3DLK0PSs=pOGK1|Jni7;&mSV|j|dBEW)%GM z5Lefx$|>^fCz+I!3kwC!drAU8wtZ@9QkYf4-1!LfO<#MaA?D(u;c@CUu_~r#Y8ZPd z>FB(*-PdRyJ$lsnK^;^Wrj_H#{>%Y9)9R&e!VBizMCv6fCh14aYNx23U0oWAa#)@{ z0T#dmIOpq&*ZXV@^!0UyzejWEVXl41Yf$q=L9StD>epregJ*p?l@b(m!7T0EvqwBu zGC=&pJJa@z#b1w^EjQL(w{G8Vd{6rU2L-c;I0#1NF~H47U;})e#=>5`>O=eP6dchi zxJQQK5;L%|KYBw{&~EJeYa4PRJ@TT-J`&I4#4`uhaRL+p^wIbi+6?VA?=CtasY?9Y z5vN$|ftp2J^z?AUv1GOEYvat{5R1K|qkf37D+))5_!l~fl6!xC2sq8MgNHk8Wne+i zz(4@uMQ{iC+BWFcE(=}uR7w&=Q1zJtD-y^+Ir+l}ZjeCw?SE=JIt~KIKNq5CV7xHz zt+8j%p3`O>XOcAwU#y&MZ*K>z^m(W_9m~V&hH5eBJBp#hZDY;eC+UPng8aMFM&A#2 z7CX}-b(>WgAI9_AjwlGZt>%3n61+D|Ld8Mas9D?C{2Cg1e9oeKXQi5&S|5r$ouJ)G zl$_t$*{1FCvt%DZxcz>jnQctNp_q8w*o~Byk?{$zO-JYBxdB6jTukd!G?=j%g#>vo zk*MI{2gsePYX4M2`G&1JM6f>>ICA93A~5vU{^fUu~W(RP^L`x;(JWjkO_2b8jTX*b8@^1+3a_^z+82F81g39nbj;=_! z2L&E`C^v7}a$8TY ze68T~XYs|Qr6b(jGM`3>kc+vCZomR&dR2Sr4j!zLr8z-{)=&v}C} ziAwqSsY*KVdu23V3rYU`7)QR+*v|~!45`Yedw3wlb#5dixu*xmbLHwKY7YWz%f|r2 z=>d#*TDdOI-hcLtl2k$?6dW9!?!MucGWtJ9X|JWFmFG0afl04y?bU8tE}iZo$Nx#( z{le+#>7Ih>cB3uic(%NXpW~1RQ!_KS=rbK>?zGzlPZRZ_C@_%X(4j;6310j1F;U$H z=<1wCyUOg{OKy$PjRohEhZe7wZ^1=G`%WLUSWw$r`@hxJrUN#2xQ2K?dLkTi{oS>Y zPdM(p{w-U!up~c1DJCNrab*oa;^V1!s%9<8s(HBhXmCkOLv(z1{QYTYgfZdomcMmt zTmK^p=DmPh^c+Dg0PJ~o>1R)$ergccFBx#KtffWiG?$I3xTy(8??b4E76V&`Sie|*MACd3^sIQ9@{#qO(L;^YY z+GJr1k#29>G7S8BuZ;;i%|1;yI0u>ubrruXqw~f=TH428i{kw$6GNWHd_!joWD@T4 zwFP$ASYHtJ;q24X*MErTY{_kzMquWus_Pmw{}hi0rR&SP&!0c2nYztI)Gj+9f`S-OL>tSwo3?D%!H~nDZ4Yq$ z`Sa&D*Fredn&YoKIy!<(-xL!YOG!=rfRFDXjj{dkx31KA=`qIP4kNZKPU%7t$vavA-9{97!$h`=wu&}Taeo)~MEG;cP zfQvCDB#!HR^x1GUY>xsxcFfXj$PB!(+*32 zSul7!i-;h{$%egrNz`(bv(tQhm(f7wkp4)rZ6O?rp7%GUFsdl996w$pnxm(y`}D<& zN3*l{^bHJ%9~m4RWLHi-1bp%cb9Z@jGfib>WdYagr&NUU#u3F07Q7?JjPusnk-L~W zG&D6S4<1xA@-HnFEh;W%Nzucrz{YaVI)czHW00G@3HbP_yquDr-sku4-wUm^sCBaJ z`_VM+CnTJx3FW5Pv112uX{o8HPPwJ5#+L@q~zp>Ki|H6BPMKT z=aq$4JN!A5nmBay*s*EgFg&1NOEW_o^r3h&DU=skNLz@G@`eVvDjJi?E*?f28ZThy zl1UpkxAhf~P^bhLE*}R6Q==eW(%b*=x|rBz;O~=kLt|t9&yGpe$Wop-ffB#`@$=`c z7)dpP4HN^0z64Z;?FxPU+K){pa%bgvLBYm+sv}_`u2MB=CB6fDF#R>1%>A|%u>5=<(R7G<>wP^8_WQ4d`B)- z6i_lV2Lhe`igI5sLxt+;Ir;k4t6g4Vn*bn)R0q?18ThjI*RT7)U5VM5iCkUad2o!M zfkP+{9C$<&ic_b^RaI3dX`iHJXG@?m$QIg}IXF6&m6tzI`hJSl7^)C1-R6T+$=ycQ z8xa?1>gwu#9C$CLqC$rm*bgZ27a;qjMdH8!#(xjw9%Ye_U`aY9s zl(?uSF@}a*V@Xv0@C1W8K|5%>OmD-H%^Cmj79k=Rs=))0!o{VIOI^oP5Pa^ZO#ASz z$N=1s((HvFjg3~nzfi*cum_++Oke-4+J|%e{EuG0X23-}Mr8k)-C+MPJZuDBax>7W zxQa?!DeDCs%%>ke{;tJHV0@B<@b$gG)}(k@^!l}&(bf;ggoHERe)dnEGiM&6 z&|xU|0k0Gdy{xlv{b`H|fTQ=5CxgC>{HAm`%Ts2T4iZq6APU05=*rsg!e61Z@J}Crt&YD{Y4?{eJIN28xrjGwAO?IZYG{o1l>7HTTv?br zcJyf9TK*6Mx|=&g&%j`tv$M0n`SZ6iZK@48<5Z!Ocwj8)tqI`-x9}tH6e@I6vMTk& z#KdBsA2$&nnB_*+-u5CMdKahrHx9};=YH=koX)cMJJ_78I7gXQe?(eMh+mQF%bvd0rfa zm?iP~ep}SY%SuWwbUGnnL@RI@#Ct#Ae{YP^wIRdcdMepR)FqfazQ1<9VC4U&5f8Rv zuCVZspbV9~LT!W~ZCP2Fmxwkh4tRJ?0x3U#zCT$#SNe2adpkYYzR>8Sj{EoTx2&kn zzw3*{R6bO%Z)TQl)UX+}1^R?RG!M?F96Hx<_hF>I_(^{PfxLYPb(?j|o4>b>jJ{}r zKCEuFA8EQeHK&-UaC_UfZM+LNTZw;kz+@6h?ccx4Hi`yIA|O~)f&&8s^_Ot;?dU1(%G$0K;0Re(81f4WGH5uJ(on9e zm*v9{pSxPlIZWxaj|N>gH9e`GXL)3_E&Uj$W6V@|7(U zELTPV=%T^N$@*9PW;K}inkGucqIEEO8X&w40djcf!g~-Y)Y8(}%V=X91s~|>Ig7OlTJ1Eb2P0kCaC%s@;gnPX#LkR_qD3O`83bLI zvvjy3ZQ2og^iHQz7Z)9rfb>%rOh6N4v>d>QaO399eB+h=KvDgao4Y^^P>l_NRnkuy z0>7*=xdtJ;yOdQ#BofFd!C$-7tyur8cA?$PwC=B=+@*mO= z=TH&tzg1L7G}TW~FavVvL7_2x_Uu{E+&~1b(xzD-aZ(p0%Izr3yo^yW&p0zJO^1R> z=xH`TkAs7QZIT( z4bj7cnx}fpw(z?wS}MK2K`$p73`(dRe69gQ|JCc)sgtYm@Y5n7u=5)?u`4CWvt%!S zZJdw$Jv5Yws=$X5TwTK4Ej%_h)&^EbMMvlG*ZTU_`0l{7=AA01Cj%JHDdYen)nc%$ z>g?)zDHbhTsJ+X}^Q=X8I0V0|YUEsiFDGu4=G0Mn3EQ=0+f=u&OX?k%i1UntOb)q0ANI^%h1V;i ziD>H2xBg4fi(R_3DM=~iRqvb2nA~=o=^_3#907{?^|`OhIKbvLjRaqSTIEEq+Pu&J@&Y`SQunhadPmjYkgaLA3ofggZX0c z&!2>bTKf(maJ0j@ z(uQQw|I;c6n30TTk^vdhSw&Sf9gOeYuE#NFHVN?azkti`u5HP&maV-IM<5{!R&Ugy zq3A$Up?r783?9UE{45WM(uU=hc)4RCyPfv8l6~~&u^aqGKe26#-9+b!>o)<$lfl7g zoXx)5C^^X*m&6IBu)VDh9M1tJW)?F~xRl?a$W4&Fm>X%nl{5~hw=3tazW!%|TO465#T-x8VyvtC2_ltvJ+Nnm z)BM zVJ^z9xwRj07L&TV>Qc5M0^(10cyw-jMl;mG&5s|ocg@~9VVdjHcNhfQjhEp@$up)> z^VU8IDegdWMSZ=@3xafi8uXF$&m_(A5mVe5G}kP+o|b$hq$*!vk18-O;O$vQOK+bB-( zUBXG>aKvOHs1HPVJS1%J0C*x?9z3ij>)zfwG1fAI7`bF@oS2;7OhZGn&BDTB4?XWz za5gk4UBIAkknM0~oC8lKZlbISLj}gVGGJMsu`yG*4t@V$Xd;%jwiS>(#P0?VKLR%Z z)4&%RU^!nT;dS+W9#9Vm5SV_s8$1+8;Qn;sNR4(Ea=OGk&kA zAbTT)9Aknz3(|}ljy5GK?gr`mbj@YxGNL-{^zF?e8>=<|jbeXYFn1btWSu~R^FyVr zo^idVps-&^NNB3dzUK%Jk6f1Bg9i@?Q3ZthF;33wS$2M#ad)e$GxZwj@Dg1HEd5Ng zsmFao7?pBsKZioR2YNQ7wkuk}&r`LEeK86p`diuCKhDq3zd>_XdU$06eIe-3Wn?x? z8gVsr-8R$-*>J)FkbeR=BL*{7n<3mJbpLquTrL7qs74}nVnMWcT7ifw2XJL6O}%mD z%0*B*pu7"+N5IjH=@>Fr0s^>|tK(=gQfBsDydPaqte`MQ(Ppa^?tZda~_HhT!h zA`l5}1-6{_ujSi|95Z#k0h(5y6{$s{Q@{eW1D)srdW_9lRD&cAh0sOeg*bNV)Xg6n zuf71gq9A=wyM6hpD4*!_&`?PKi}BhpBj+aT5$w zIz~qEyn{$)WKrllCIUC+#s05sKQ@|hwyNKz2%ccP6)fN zAHtC=B8R62YZ){{FZ;ekU29<7Y}^khYy=B5=8Aio*V2QZJ&UG&kd8R@z%R%i=y_U_)XZ9zCvKNe6qUC!+6&h=^8B5s85OP|*9p+HdQzHlDIDOsva6q=vqi`Y(MkuoSZIPup9Hn=p5SidQK+df*0Y3AhLV_Z00|6BId?wYnN-dR5(N* z;caU!Y&s7tEV{mU%*EB!p!88KG71lk2OK%rvM(>riHb5qUVD(6d+wCDUoJHx^p@UO za0UfjiuZ(ucD^~)RP(PF08|nR>a*yB@<9+KW_>OUg>2uxY&&{7fM+c_W2g4(R()>l90_=)>=bu(ZA^b(mduvc| zFns-+%JT4TySn4!jUV^g!<41p-u$EruoSw>q8a)uc6$y!>TzHo2&@K16Ve;$9ho**hdbE(=(Qpq)E!~x!=vZNds z9^Q#;NNoehdla(f?7{z4uC4~N{uvV>v~cLPQ!w&h{jrXefmiUt)ehE;7tfyE2V&Dh z-z?zT1{RB;7$&-llQIvYzidVIsy^^wu?;V2KucC-t;0S9872bS&S%*I-~v8_0#fK! zSf~TYox(tJO}+}2l4*1hs|rlS+wkodZ};X;-yoU8Ua=>{NG3ty6WX}JH^h%bRNL># z$q#>*@b+JGYFy>Y=*r<6!(zjps~z?zhhX^gbkRdkw)gEN5+7d56Lf~Ux}I>c(o{#B z0E*0G_1i2lG*}3NI2zDMBOPT{Ims+C;+5Ft%an%>B`X!`QZ3)uLIU&HP_hFo6@39B4i=6tIgM!|9a(p&5#;P&#T#H~ ziv~o`7`F}$3-bmkaOCjei!WTFtns)}ZEAA9%iX!d+5wwfpS%%Ux-B< zHEG=oMl2*fCT4W3J=2p19Q@SuG(vu9x^v|zU;?<3Yg*SeG!6k89HXmpE`6lp;P&+b zguFc=#JFFtIaL3oT%M3fP*tCXg~gA`?|gO> zD1yjU9Q|;?{-e(ThoUj|XH0g;g+XENgWc(pxp}JTd5g|G!Uys-$OH{4XrgZJ1i==< z_I21q`e-CEXK-=>Im|Ld*jQVCkCmc8RNrc{J9`#7?J9KMn4EmDZCCASSvL@B6wuPo zLcvcSmA717w8D@r(ZcwA*9@k_ETaaozdjitWh60?8Fc+w1Z70{6MZ^Ve|C2>!7AL> zVP%EQ4FQ+MwD=|585kt)RIi&bUq8XxgYPSCWn>%SvWWLTp_oVj9sR^B&SJr%=s5fK z??0|q0wlOQQflhPB4+{|LMPhI;|P=k6VBFtWE1gz4W&N`hrtHii5ltHAn=6Z9ltd2 zDbxF-U`a^{mD15v1dU}ySCQkbl<7L4m$JG#>C;aPsZ#fYu}_C>p)3zq?w4^{8CeY$ z-9WubA_OCTmT|MMvsmGNd3kwM!X03pt6wd^Odiz{-0l|)aH<15nh`mvUE)HINANyk;w2n{w&<5@?KcvOr@swo*;_k zO}R+Yp6_&xap2FaDo&|pY=x?Tkn>*unRfd@%|!E)r^mR zC>`|er~lb_VA8W0_$V|l$o+o+fwznQJx$U-)vw8cwO{Fj79*;}knsmBV1)6Ty{ZZ8 z?bRXNcc9jWjBlBqGw&n}hk2|b?#XDAQ}gqZXnViFk3)_4gaV5z0QG$t$wWLgbo8^z#p&zsJBft910g<4ZW?ayBQKZ z>>$V4*a$}(m=A}Ib0yF`VTZ`G@q(;`(n@U1u#7!R1ImjA>eo2O+0oYav7vzysN-RN z{&|c57&<)gw8bSQ6N}a6;CsaO0xdRH)Eob9OHoPRJTp|^I-K3o(h{$jbO7$io`rKf zJd_|yG|m}wtLN;&@kxPHIa?!hFAjAG;)+JqEb!bENEzRtP@YFfi6r6kwE$$meh=f~ z*befWdJ}4hZiO%Op$8DAK`u|v{<#G`iRjY;02*q7)o{jd!vH9TM$kO|!~HlbD`74+ zF0O=51bG*(Bu@w$;SmwH;VI(d%UnpRjC=d`FwP<&A>qo68=s4v7c7VB7#}`*boAuO zJ)qjvTDA7CE%pa?ib{5LbbKO?fkVLq$ADcYLWe?efv~Z|*tN>_Bs=>~ZMUU&9l`Pu z;o$_tae+2V9D&Hn7$2s5LaoAE0$PdzjuQ_O91;N|JN;ClH0*?8`VqR`ZT;ixQ+T|g zSkNH_*jYodc?_}|%CgSw+xLM!kF&7+!teAB2%s^Y!Ohd1HCFKHFen7GOUyvtERnWdRs*E8C~d7WM_e!BXkxb4BgO!g|w(Cnom7+Vzs-hZguZS-2BIlImAh zR{V03rtvP28?}dLl$4Y*dVa^80`Z67qXT9jsB@g592_!0flP#EclNA=o!$J(Xabm( z&H~%r$c&GWTlO(9Bq^1^f*%dfA10yHVOO*_a+q^`zI?e7Vuhwsi9#V!c%B1_7}lON zS`9%vKR1(OIWZ;8OPn3yN3lBFH$6W;=&R@d3$sNh^`iiP|L<`!%w>#;gdYOJ*5w2R z>uk;!s4$1&r#)@{(PNX^P=Wh~2>L-&$2r|^vuA0r zs0XK<{8HC!G@APkY!=8RNkd6oTwEkX6KQE_OKWSVQid?Z4C?Q*SFe`Wm$~3CMj4p= zFb)A#Kf*K#`K#PJG*mU`=IW9%XD)P#i%WXSdGHqDu>yqg=07l-T( zZ~>R$P;SUEQ*TOArXZxcckfvC@2XhQ8^bE1fK}htCrrYLEz*^!0O0#8U~gs-jAG)| z_wMj3IuUXWR+;S>%%#vAU<%%fE2g8TKY~&NsXotnftXpnJUmExKrTfsdI<9{p=86cu8^We1Aq(3sySoF z+xQsFd#}MdqzXX#!g9qGjeupy2Bm~MqK><{q68zzu9*0IPY7j#0J-Iggtz^1YR}h#JoX?9)JnZJe`W$H|i?LK7Mw8B`nOqDjcOU z1nfe0rA@A2r>!_d@eCMhMw=OuQeZ4gBK+tIL#uE^t|k%hv? z@(KDN$O-pRqrfDfP8-Al6@2wlK4Den37nDvKeY<&QgoQHla*|>@(N&=CiyEgiI!Ic zeejPWVYI}AZN%zBAX$@vWK6+$orHxm=@9JH#23k!!;KkR5rdQop&Rc%RK+TQ!4qwl zf*KDah)j-EzvMi+P>S{O<9@oFxRAlcwL{IlCe&9IuIp02wM z3o_4YT!7{DK;+&gaHZOsy``lNc$lD~9k_lyXwSyYx1iQzv&Ym9hPM#2$B!Rpp0^p? zS>lcwa0j@H=G*A-FnhK0o83ZD+$6$deNQv-8syHtk;idyaYpCkZoG_XnN|bAl>@WY zi&w7_?NU)333_}&gLo4Heij50rms3xXr4K+-Mo1DGC{Ep&)E(ziyw=IN|5C?eybMT zOK4dOT5)a$J$bqZsC--ff_j!w87wo$93o*IDTi`djx~rfXqHVE*q&ew6uqj`-Ts|? z^`kxXpFAHtXm-&`RHg+#3zIo$;YV;(@0ZqE8LrvyCnPmT|{)*t*<&}+q`@KJ_FA_-j-_x$!gM7Wsf`9Is;R2CVpL#KMyaj zF2=9hcw0jpne0nGVc`fyA%~}6y?Jn`A?b`4?)AE91M${v-n=<$y+|5cWFX-UAQT!x z58SA>8EHC^(qZVI4nAV{{1EJFQAIhcQ^X9K<1}YnW|D$*$}w){n1|`prZkEK6xgf+ z`Lbng?K#-dBt<{eN#<@WmqeIq=JB$`vytJE zk#!I;>VRgNYnrhyFSk;&(jH@i>1e>o9bhXK@2K|advsTcGIri>E6eg&2|yV`Va)#kHjCdVy2nTQ>a-IQDn7lB|faKX?~dgN@7n zJnvyFji1Z^j%B0(x0N6EMMDC*funz@yEoLAEu|AV#rhu*IapHCl3Q=DNl=Nc&S}_| z2^sG!atsb&7L9C2YZi`f>Ewe|IeIQX^S0dbQ|*sr4e zCPVEpR}c0yZyC1aGN=mKb@rH@C;GE7?h#Ki=7t?CfkT-2G2EnB!ybJav0Wwv;jT9P z{H+XTT8plN3M>zPhR{kc>%v9~1=9UKggK`j+{&36MrP)E;S++8Wm76-Ft*3f#c=xb z9H6Ey$4m094<0;dobB;F&ShyJw9}RU%o%-Z)*Cu#1I9z=p}f{G$AZ%NW?QEkZaxM_ z!ySz0znmtCDr?K7xKS_SGOT+vxyhlBtp zf^C{jJBfnY!_3UA9d<ah6p-DG?B-hryqzkV|0@1r*`;#)QAK*@pK{M2=>ck&4h z*{?*dUc1(}zGB{B?(E|7lLz9)UEsI24#H&|8xkt@lT z%a%2wps+9#(oTv^iOW(Deu&@@5)l+#c6n&O|zCA9_!Pz7U2{tULU0$690sF;}6-CR6|2o7x?<9omi3maP|Y+Pz73xvlw zW-gSKH2MKvfYixGkYsLu=eV^?^x<&)UBY_62`BbwZMIQn449s`l)9jbZ&MpljV(3{ zQJ~Ynd{Vu>Jj#t{8k@QPBVCHF@dKGIz*A>w`nCKp;eT@&UWx3we2?7zp9pH|fpY?` zaJAmuoc0tp#6%bEJ>=xg1%pj-NZ^-3j=ZhTvTZ8%7cY`bx{LDJht7ZeSy6#GFFv?F z2ZwIm%wEx_4r{?+O&9XHdV+G_C%$!nb%FoiWL2`W<8Qr5e2jx~;W#4FnmqMNwxGdn zPzu$;rFPRN-v-NJc1#)(EM!WGU+`YNtW?I8$%6ig0>)d~~ErKD`SvdBDcMhdCU zt`h0V0vjql9bFo5%3ar6{2##Bq+wLHUJFo$1J%i`yE$Fd4bp}jYq^BDxaFi9Dz{>T z{rD^FE!sz+z{Jlz%mlxeSiCa*nBo;F*}X|MU=;(a+5qNn8lp-nr{ZruCBs*ZjMx`8 zT2TRw!VR$lt8t#_|GJaAXpvd(Wuoe!k|x-yFAHp1yhQ<9C_deTw_#)-7WGOkTeJ16 zspM>iAhc2*le8SL`2Oa;ktpj->Kk$oh(77?e5L$FPN(5Fo2;&F*a=wLsf$i9CJ z&FJ6&jGP1O-Jq4y$NY@1oP6?I+*h$}cn46n<-!JNlzduvKr-LQpR2fIXqX9DZN0DrC`mi;XaJK7KTI+c zMd*olfEkX?E}n|?vhEQsSsvkRuzMfQqqp5&3&k$mPDKfUH2MKDx%HeQ*q{w3h>e@n zVV*`o3$N^95Q`#kN%NvmE_>fg(#iSqj~_j3$J(AnKncUNLWZIKJ2!`R5wZQ$v!3)q1v=}bReCG%`>If%d<O zW2Mp2zuZFn};w^+{CZ|dgavi%A7wym!^e zxxDB?MrLMqLAtm$o5qi=y}5$*-o-Nvflwd@M@Bf>TCrc_?e-wMgeg!Sqv|tLdk#f7 znDSZg=I7;kN2&*teZ*iJ(;ZGvNm*9>Gn=k3t7rzRFB7kagoT8%O30QX;GP}q?~k2d z*$W-p^&UX`L}?G;Wp>S3>>#BInVXwqcDwnOXkjU|lnpJA$%82+UW z5Z^ewvV%SHoZXa5H%SN0#t=3=j2C^Rskd!hxe95`1HMq2$<-q?8S zxx^`l2BLpNk?F!Lm5d6Ykqy4-s#Eb5y&D@F`%L^#fE+ZDyQDY?Yc2z5=7YOoJF9Ms z&B3l#A!GN6!#l2xAE+wNunVEd8OO=nonp7baSOiO#rlv8Ie=YDHLl)<) zv_Lo}5PyJ8SDqDopucfh=`dXRwcVQAwsq^ymb+j*|LDFY2>Yu#|7=S>)ip-F^W;Il zUc|0>v-!_YpEhf|&V}f7f}J4PyzHN?pD}a!<5`vofU5*rCIAMn!W^7a@7}<8_*LpR zgd_ShcYlb_7lE1rQGOZ_Fol=v{CRr#D_$fd_9XzgfI50H=E!*HP?|-L2;wu*AMT_o z5RV3lBaQz4{+7fxwsG^dEPj)w`1_#Ntt%$lGo`YMHdcBzo(2aWqZ=9?_AcF6XL#}A zMa*w(LzjbcBRE>Qj$;LinRjkJhxdpR^N3Qv5SWJwK=^I_gb5wj{1Nh8zeXbVKek}N zp!N6j_Wp?Od!~jU?sryVO;I{F$Hy4!1(1s`qOBWzJ&(Pu)R|@6Y&2$_pyqVglR)gq zoSp#YZobfpdb*E>hK0`X&YefZRS^k!VMuWIfs+@3kR(h##J@&#fhJ|ALxT%MgN+8- zDICWWA(lBc(ov@gQ-=Ldi3+syt$LtC2;KGa*}l=vd_F8^?{bagd4%Y@+qsUm22Z;D z@C>qJ5mM|Kb8U|9?rtn01qn}rN3Wh+dso{deg&j5JTiMz*Ddh*QKOv`mx)De@cLW( zv44;bO$3u+c1NpJ(NI0XN~2hPZuYLPsPGb;hvUUK8@Mt6aDR8@(#lFwbL#t4jeJiK zLuGlGluBN?L;@w2Ha>6MKrt~`*{Q`;~;+^!B{iTUj+ z6)mfS3Ek4(e#ke9&v0*RThvorp-ly`a7nI zlMb`8ZpWdV$8URkapX{6xyxL{R8XL%_-`%$d1OvIe(tcJgY6Rb&A3Mrek2>g)vtTgn>$--6@z2p2FLs zTk-G<+u_3`4AIK;_}mf>9745%+;o{u>db`D4id49O6(_s3$4lMCU!buHT8vI_)E|S zaG=C;TC4Dmjnx?n7$m;qlTfh2Mg{$Fi{6a^6Ht->XijG!x1$f_IZVgsFd-Mg%UTBH zUrj)0dGesl?A*OOIQk%(+uOyM|Fu)Rh!k=44Q7+sRq2Yk1S^C;*rgzJZPSCj@ObgF zzY&m6P)-9mQ8<=jq~(u^D-&xD^n7=AR$^WJ^0Kb?aVR19Fpw){0-75E8;kuE#4`4* zU6num1Nc{VR>J40@Z1H~5PbStt`0EHXLv?s;kcLkTcQVg91QUHK#K|w?0A8w`9hOa zD|UiN>8)&$FR@Pwf|p&pq^Q!-0mq{Yqnf7`0bt_S2s*kxlv7!{>Gk{S4Xh7@zYR7O zwS!*~pWh^Y+8i$plG%eDkg|!c!fk9v!3g$&NjW%F4R6*z3NI|~z8L6?!jn!DA4Eay zidy8d^YZgoBK5b@c5Lz>*#1D#^b^oe&HD3rMsD)|P+{t|$9Naw6a$>zqMP1z{J89B^jedXg#%_2g`<^uaR@232_j&T*^CTp% zT=DKOOY$>}v4VN_*Z6pf6~Rk_tdl&Q3T>g2n(pj7S$4wwQD%|}U+-8?srC;w5d-Y@ z6025k&%-e=jkX)Y1D{2_Y_#WF+hIR^@YBbyU$4*FVNG+Vp`l@!08$YC*nD&ToUE+R z=)1>N_kV`cgDCx_CO$|M2JXD+bWBl);n6!?2RA*?;9x+R=-o}{mRf-&VKrbKP5Nw2SSOIY* z9W-OA$~*c0hp6ig$9n(YR4SuRWlJU5A*+l;Wn_?auOobH%o&oI%eTm__Z5#q=7Ijy z4#9u}8UQkOf}-FhfP93t8eHU!8#kto&)?UEDghAqo3J%4Y2K=PQC!T7l#TvX>Fc+v zoevAclr4|$a94!Q0x}($9kw|v)}kx@IyiU@IC*1iJ_aE~!OkUns)=aM)p410yQN_|WtdAe3qh%?P^VTFS=&YCztJW%LF0 z2I~lu!~cJ>To&!6r6r5K8^?8e#KOTvA;XWVV&niVC5h%T7k^X(T21R$Q0+P7J@^1` z9j<{Un^#%cDl_zIC)gz-#TRGL!8+XQuOy!f_?dR=lhoAh9WKqN8q{=j!rNzWh+8%k zl}_St*A)e42_Ux=`zQ&_=?>992mhK3=d3>?M!)~4rn4DdI~y!^FN3>qc4jQ~qpKi4 ze~y0zQnt%e%}b<_^fTR2Fs4)f@X3=JyhCx7-KTw~`agI_I#pBSgnnQkW*C}{dh&V0FtZlRz;K4n1N3QverBqs7r zUnwLftLW%*zKq~Xx`Q;E>v2;RkCT;qo^VVsPvXz*1rFHrF@#9-Kngnu^soVAkr5lr z6D>;6f{NF#lD7P|FHrm*^ID(@EzgV|mF}fk`F9@7wkG!6fm+CP^XQ79s?C4j{2s*} z>u24kkd48HAxCtt{ilx~ZQ)@R?Cz0r6TO2CXz{TF8%y(6YBd)nW8w*Z2fyYgt&B~e z{%;H?K2;bY7d6-Vl{Y6yUL2n0(}lRot|4C7qTu7ww%&k6a^+8lwqGhL+CAMvS6;~( zn|94-QzrQMe`z;;LHdbG0mO(S{m}xyCI%&lv?XWs-mz@)Q|-VsQvwyp$gmv^rit+< zD--`VPQSh!Y(OlCqb}mhSUfw&3V7rt8mX^6JuAT21K34}FIEj90AIcK)jgzn^6;;N zq8;SY_=2>ai_?m=?d@!chtKg|`17*ea2&{({NTZ0(OD>?E}*NkMohCPqpc)FBm~~C zM1Bme9Qt!;YxKT?MMykaeDXy+e!l4!B{*N2-lB4(I zfmD>h=D8D2*49BtSM)V%>gqk19C8h8j7>^v@_w0s^Z+zh9E$lL!Eo>a`8Y>PfS*6a zWTWVdvr6|-QtfP5=XZ%K~Yk>&>&O%sYGss3)96EG3%p<&f{%MQ%oe z??d#RvHd))y;gDkGzL&zvIoQd_>ZkrdYsz%cYJ=|aVH)wXN?1*Z=tQGWsi}o*f zep^BnE`i>qqe~!hWQou5LdDKrxAl!ks1v zuw!tOyMOq81@p&!Q(Nw6=FMs37^lI~!J?piwE7Ba>*5;Er>>taBa{|>8t@+bdH{R_ z#u{hOcfP=5J5>9@#7#$2h}+wNF^G+WLxz+9EMkWjH-@zhB#y4ttyzsr0QSiwU$WN- zrlRjFp7c5+^1@;6vUSqMi!0S5xpNMSZ$&4`Y$3`_gGueZ@l}yP%Kj$nX8h(GqhC=N z5Z9o;eA~DM|0_S%x6Gs=aKR5U3Pkm)PSQvrUgAOulgbnAJS3RBva;;3)&&W6Jvo8E ze~x=K?}l#)3K#uf9UFfm8Zcl)@fGCMT^Y zWLkCsmE;Ir1%fFVP~v2)1%pCES62i5`lMISe$Hvr-+K6UOVe1tIl=f8h(gXOoxIzZuJd+t=aySY7Ny1sA} zU^;)dCbazP@hzFdF*m9(@rCB5rO2-pudmI#+L#$!-JY(3OFwpX-Tt$Cc4HnImEp`t z40y>kISC7`V9CGyH(k(pF@V1=dF$tSbz?|F58+-qyoM6Vq^iCPutBX)cYvUg+Udg} z>Hw`V;hdcKt{u_*6!arE!b>g2==?5v374n&d1+oNlej^Gec>&=h^Wu_MR*S1lvGPT z6(}n1AGR|@`En75psF~nVx_P&Z z0))VY0kP(NcEDD}4ryZf<>l2TcWD3qps&q>2>1lvlDi^+uA8n>5VHk$jJu8ujf1;# z`}S?olC!6pMCm)updW)B>oux8$>({M_i;l)0!#x=qUi)I*Dk{T4~D+5KTXN&EYep~wIy*b>0vH8Hka*8*fOP;at?@nMYf1U)=~YNVV*m^$PUsLD0z%#e zgaD79Rp4WQA+hIiOQ z-pWr$6KxHw@>Zan2_@Vqlzo`@3s!a^qoD{h^0Lzu9^*!@2F3*;0*FT5c!|42GN&;L zP>f1D?yZ!5hdKT)jcH%oWnGSR#3Uvz8KK(OY0%ib1!slsk(5}QFDx_Wb;mg0f>;SV z*(%J_h|mG804>7GWu)*nm)#QsEm5TS{PJbX|EvbbpyX!Ss%X|$+6)_j>W)MfVah5H z0jg1e5T)(R{JeI>x5S$_+0QS{IzbS*0_uoti;_ZW?M;U7Wn$tqj^UCuUUuf)=cH>m z?7}Y`JE<+!^;#1tUNh`433re&4=Z-vG&pl~O%Pi91}P=GIW!sjsuEB#(Mj2ONVav4 z$T1eFT0iaq z;41X%$P?5~Y@!njf~j9}pqRRZ5x`XifyN^UO`tcW{z!-)sRS`L1i5j=hXqT}6Ia>6 zBvE{>7^pO__rc8yUfDnFPNbtg2Kzph*N*cdN=b-4Xoe?kNQkRkB6 zH-@KswY;yv(RQEuVOS-nmFl4`#icb86c3e1BtG|DjTqj( zj-2-{ARK)~Aj2j*o=R~DUj|yv*%`oSl^Ay^FHSLoIuZ`1Fp<%bvIf38guxBo3n#z! zjZ5H|2a5$_{ z0fz=g(fWVP_Cc^c4$=u2t#05{RC`*Nz}s09T7x<=4LOa#w0vFH@3ZSK;MkEajF2&@&kP6`AAd(no0_c#OITo(%;wtxC`G^TmW z^Q=gIupbQVMFswmXa8kX8d3_o5V#4YMTya+Hh)C`qUL!AstF%UJ=19~gI{9gRgO#9 zODNOsb3!NA(15vAm4I|}RZ0B&WGxac2FEM`Ctb%Q#{x~Ev4($a63bqw_?N~1v>um% zw)nAkb-S z_T<`uCrc=ki0;I_i|9C#2V59ggo1#F5;sBgu{^-5M23DtFZ2R=-n-#j3b_Ta&?I`7 zz7*hF3or-$*Q4Wcd&f~Ar0&E~5J+>6G-Y**WPl|?kVN2;Kf(BL5@O1G`QD??`HF%N zwPwPCqk5ABc+)ocKjmwPdtO$HY36)@-h~x(ZZl&xFjUjZnie!QHN{_wxwV=mrTmJ=8NIVa$=+as@lyIwTsfx-n2 z%#+hEu$7&Lq=Y6asIRdC*E4=B%_qX6Y@)Az2gjjbI-)fgXJ`!EZw!{KVM<1k@{{G> z33tACyR_D{qEZK&MOAIlU3ODjF6r~{oowwr&kF&%66wOXV7j`}d zl#~{=^Ew(_`kJejO*|6a?CGiui~>H?3n^D{K63s) z7(UVE?=l*LHjk17L!YKZA(iZ-S{QHT&=4LcP~LaWqK;-Q#x6x%2!8zg^equ9fb$%L zI*5q1zP(&i)j?!z2sIR{OSF*Xds?Bn55l`~TqzcWUStOsOrxD{~*T>z4wE;^DWG=O;m+5!X1^wz3O;bM#gFZtE zf+W>fqO+a!bGwyg(YvUHGRLeJibfdP}m3NFZccW6#@9u7A1Guv8S*%Z0%oX z?EgzrC6kgvGPyi0)|g)s9quUNkXice22g2_jvCif*s?Vus@>} zx3h)0%2z@nM*&~Sg-Uh{Ohttft~AD?8c`^l*mfOb0)PV_?*li2?OYA}{ea_-|M_*4 zuF!^r?YQyt^Npx!B>&LG^B%=3Y3*?kfk3P^_%dpxdciUTHJ#AOsi}A`iyEegH|%|v zi|4ner;7#|%=tX9w=si+iq4J<*MEl1peBuNqdeP*0{!n1TR+ zG=I;UJL6rHh0vFCqurIeh7w?aLoLSrvxC4vLqlVOxBnj>K){rR#R1Qbwj|^HW0t3@ z6_FWmC|e}^k$&XGOJ_hn=fgWOmCze(NkKb$ZG<;&^8z>{;0$jH_nR5pj`Vd!*eEkP zvJ6Qq-RhEt+OMFPT~&%HkXZCt)}X(_qu7LJ z=l6tGe=Y~ST{-NJ+6 z0}02;7y&_u7rbf$zTP7*a+x1Zqgh89kn-*VE=9TR@)%(OV_*2JR|}n5YI#vEMDRw^z8e%Xcik^R5SlFA+SWtbf9!CbVXl{Z*mWz{C+Xb6Vgfg@4Kemycy_5#iKD3_=$jh3{yKkNcxF zgAu@SIMItis0pZ49ce{%`Mhu#&#}t$xz9P5qGCf1#GkS(6&=a+-);@>7r;=*_g&tD ze_cX_CafS37ikgp2clvXk-M!<y~f}mSnOGR<(V|edPQ8L`8?_F$1JkZ>1Aak-a+FvKpo%PmoFSi0XinPLY%iYuNCu|eYxbP_oY0%%=j)paXw>$dv>A~EU?w>J@*iaq zNJ0RG5-AI5gy4mYsoF(U=ZiY5&^pOIX>BnErY_+96NL_;ybmT|-U_dWXL&iCGU7B# z+bp|x39CIpe1UZ4v0m@O^*4T8G%zN6{^g5hmb=cku1y=3Kl9yC8kt96)44T(g+MPb z@PIdR5X47sZ)ZSVYJ6%@!)RVb9U%9-)wJ$3IF%-6YH(1KRPCepLCx$K|1PO1#@jSb@1&^}T+HWVK zIAc+`*kI&IOnZr~EpX4_z5MlK+;MVr3@rOGM|{tHA~2m>Je_vk%Ye8MhW7Bo!=%g#}Zf6Ht~DKHN8Lx~RY1L%2GI$*763d+At!pQoCAFKo$xCRLx%l^(oYrZ zwoZn0YT?o_Hc(+iEXJW?$+O5GKQe_|);>2=`lh2;$EWQ?toidX&hLyxct6lm9B6aT zP(4y7{v_@&k_Ay)d-!{JNMV*t$Ii|Ue1aaRLLDPB_jTMbr_l6lsoaO8)!d=7&+5AzC(KwnthvDF+5J=q8?9Am_hC`++v+Dy*Un zzqD7ssg<6DtdT}mR#r1|H!Rly;H$;jaZ0(oy)W5vLFh0IN=IFh^1Cd*DAcShV$v*; z2h~I0iW@)+r*C|GQyUP7!c;Bb%(L^0TtFT|Ag4n4BH`JugL;(o+7)~b_F9w9D87Rw zBO@cvl{|&Oo^RhFggK2icj18~<-qgA9t@B1ps)nHUvrb(aib)ZzanNjnPHpwwX9Kd zQadrn?dyz*r5}Eqz6R$@FY@NS9o$xaP0`fMOk2EEIgh@z&hOOhUV7?$6gGRvLl7Vc z)OZvWxbT6ik%`HSpZGOCd7T0ZHnvZ#shGBnt%u7fup1bk=`(>eklkj)zXGozbNg z5rn@NWDKI7tgn6g@F79o>3VUYLXh3H_lRdO23N3q7JNRG{?-~EXk*a7;uYZ6UBs;9 zN5FWFIAdvNH_W`rLxN|g66wYf%JA5aqy%?*M>?b zK|#TZaq6oSWh+6o3&{{j9aK?aeU>7%Dqd}!t!#~i7cL^3Xm(4^!&AtR^5W)21qBE2 z6d&vA=MxPXpk0zSAa8;t{nc#oArGAJNBB9=1{oB)*(67j3bcNYkc1aPC{MNUm$yf> z+CJw5vRkE_-2XN@x{HH-)26g{($h|0;#U!+L%3m%F! zzxIsd(CVHJ+~d%|lAG5J$PHLNCt2431{kb)uR6Z}oeX3)37z-}YW4>NVbpo2n z?cGa!Mv&Am9rz{jpryyy2z2a7&35 zBrixmOyt$wljm)j9)DojfxUU8nU6u#$*t9e5j30|Bz#6Jh`}AmR%%E$*x7JHa;xj1gKTv9Y}WGb9-^l$;e*R@}PQfYlvlY^7wDHY`+G4 z<%&}GI#k*o{<-=2`6oRUJ+6g?U4+RfxqzStC6+sfZkqbtbn-M*^%h6a&f_hf^6ChF zl1&!|AxyM9vo9X{Wq&bBnRTCPb{Go{SgD)v^4okxwFGSdPEb1Zw#Uoc+3`#}29uNM zhzJJ6Avu(<8{ID86b1M(997ACX0(3IM*a9<`JzOjL=&741$sQnA98d6?OO!IZ0- zSonDeSS$2#>XDMfV-Usqbxon0Zyb9Imlp<V4J(v{MEaYRFwOl@PLHjUY}kdT zEn@x}jXb8C7g0R1h?*H>xnIzKeH@$Iq7WS8_PhbZSq(VyR6F;@Ir)aydr3R^>pxuY z1zw=0JH^Xj<`!5nX@DPs-Pf$=-tg>Uk2Y!=O~xMT$JDrjB$8mjv4B?i1;Wo%ax*(8 zMY2$G4pYy!Sjhz5P!G!CIlTd^_@%{r?_Jbt86#8Pqv=Z}8OG z88J*VX+lj;2JCoL{tGjP-Gd8ZO3Kq<=U*Zt&EFpZFvKY=B{BfNF6gqlI!NKK&b)$1 zr-uG!Rj*KWnY{0K4_!{#tvA7ELNS^C!02?Hcfc1!vzWbcb;Le`nDN-xHX@;-${`-< zcr2!i4bgvp0Wt zT!!p7jHJ7W)|a@zvo?wNZ1BTgF#^qPj|+rt>AN3ke_y-U5Hig&5CV}Rxz<*cpw*WEpO1FAyuc@AM3IICV@JDlBsdL9BUyzhsuy&YbZ_svkzjLo zBy;BznoeUj`X7|3cX(zC5N#HU-Ft?iHMR;6PbYK$8&RLB5u$}1r$~m+ob2^st_?n} zn{=b%=Ux5Tj0SX)9~8jm8c&3yy*Du z__R-?dBFKMkHVTPHpr$2IE?P@r}Y|c*BzErYRsL!Vas{YCm%`04y7~IZ&d;A2r;Mt zFYqp|soR+|HK5w*4$ZxhZKx5`IxWtB=464Tj}SRSLC#&C17~ap)`Q+<-_X~MW=zwa z_%eWO+4P}recQUjsMyjc%@DLo(4lPO*NWedpigEPO}BP4Vj86m<4zo(Llrj(_Zt>X zx{l{l1`?(S1_kFP$n2|$M!n^i03V-5p;G8~Ju>VCCCW3Lo`IotSY0(!>t}!-0)PP= zE)xr9Wrv}43?n6XHe4??#Y-1m-Zog9?H+<#qQ;A_z{KQCw8|vxytuf zAyyT94*p+`oPy4huQ-T-2B69gKXEi}ykacNa7Xak8m8cGyEZH_VelNnH_rOmE614; zs&{~{*+e~a)iLnUk%!rBc~h6A#NQ!Y>T84q(EQ~`*0Pn!y*DPNs&C)EEo6t7d}aff z3lHJ(jWPNaAhwMPcTy#!jm|X4JU!NNd0}?tm?w)Gfl?OzW}&34w=B_#!5R|laP@S_ zdhzE686U#Ub_{6(=ItE{Pp-;mZl_{J?(aPV4?&tzl+&P0=RpaqSfhomxUE46qoW!;K5j_auIlKRY1mc9nTF&Y8~P5$Hu`s7E^$@-NoXbXWw&n! ziDx_LveXW2)Zl44bRgS$w4D@3)tx^Lg*%5HeXQ`*f)eG76SCNgN2NI4a`Kx zDs2+cHeCHEWLiJZE!j)&9n?~f6g0lH=vO6&eKw^39(K>h8(s;Ob5$`IRv6t_{PAD9 zRvLLYbXFfBMD(dthtCSqCfJpxvAnxyEJ9p1{#a<;5T%FJ3@rL3YKxI=zarjZrBXpV zmS$1EH6PXy-==(C75zbdm~^Fj1_kH?8wUSE=8uKQh!3|9B9)h)KPP#uL${R7o>$KU z`aFb_2mSra^=c(yE`V=HOfrrh{S>$u8Nz1iBE!|iX(qrGv6_f4+~>^8YpYFbgcTHS zaUX>dgkkNT>NFu&fTP>x!nPeg;!H2|8(cV6jlHaA7 zNlz=-qb3)>cR)D&qNBsq*r@_V!CkahQjQLt*vc!AW}~)!_~;SgUsucw;8TFM z_yR*mS{hL3pM&^caZa(wJhzTJiiNl}6C?0}UKSw(8uGPG9&o_E*9NE*aK(k`M6EiM zB_uy3Pe#8(OoMTbYGhPc*h}16Vs_8@NJW#k)PRHv+iGO9Hl=u``Z1q?fS8B4N-tBsYbq3!ci0WWQGo@ z3ImRD2)1lMlL_9^)_K!#^uq5W$MqJEX*4Y=^0&7&CvsjvUlwC`ScDZNB){FB<$lx= z_@)ds``~tf-kQPQ{v!jsI7UJ)(f!%bDjPzUkXzexB5F_@g*kB_A}nX%0KwxpnzcA2 zlGvm{R~Tn{>W-Zh3tG45D2ECE8%`;)$2>7rKvXbzJ94*aX5Cgrx!TtXAY(LEf0v@< z7z<%9D&Rr&(0rq;$R^IkWIz|fdN(8VvTy4XN}|l6T_L0e!Z!_eN7Q(UU&s3EiT0x2 z^?#$xb$jfK06Lf|e0l5} z8XjH~rg;KNm;7c2NZ_$*Y*+2UPI3)EdIZSZiDw^Kd*VYOKd!W}`;FEzP=b++1n0bo zV&ck`H9%L$))~StL5-sDT?(b*MR6LKB?VPhR%TBxf=L6K1KBy4wzq{t8j%I1adcY% zmU}VaMpJlp4w6w}Pj=WsHsX(<8I3>Y>m;89b6*b3`ZpWPCa`nLkBt%;j)3s zLi8Ji%)H4se`r_LdJy8~YysOk7v<`~MZ-0*0eiNBqr`AEkoZ^E~Y zkE*P}zhqf{K<&CeRJw8Jdy9GIMZ=fdPlwkv{_E(fYkq&r?DK@g$9%`tGCTK`;&jh_rZ zGcW%y{kGvO?hl2?oLB4#r4{CIWEn{=qhL1O^EP_6npaohl#hXY{rGN|w*4UAqn}uf zDvndyj#2_QC48+zk*9&2LM|DBu6dGIWQU!zvvBc|OBHOR?gPBNUg(}E7SK1V`N&Z} zFXNUHhsQQ|-2-q8#iCC>om(>WWMK}vdGH=DK;Om#rBQ1EST7+c#!0T^uL@af;3*m9J7WmOiFnw+hv*kIq@*YkCO

    MS;5Lm=%IFXC7F2DxPF6nCj$W(D zOO=8RFY1Yf=W@7JuI(chiDW}n@ht6}5~>)Ipr!D;K*sB$r9ZbHhcHgb+pO* zaW;nss-Pw3+}o2{z*)!vr`Cfh4Wul3fhG%;ovkegQ3WWNfm1x)q|v4U&tjPfoRXS| z{HryWKlFTg%Q34iVZjpZe$#>ohH8og1?&NJaGMWyP5Gp!k~hb z^6CREi>cN@9X}{8{QiKz8bDE#32F`>oNP0v&Q_gbruhGKnNYiuojvvuWzx_sYpD44 zd)M{^lx&FZ^s&VQ2=)zS3_z+>4G7HSOd}neR)LV+gA*YC*a-x))4_=*YQU5TOUyu4 zj5-Pj_~W$n^z;r^lvaux8_r)Abd5e0?V$yF?II$;`8E_F^5cd|%2O|_+Q))uMd;N> zqb|;CnjNfM`t&||XoEs2*-BBqRo1^bsYz}vYPLtm!zIbndup}_L}$WpzFBXhgw)6a zdl9%z*y+7y1X8U=m9IWL*)A)fSppOp4i&`bRR2yY8h@)o8NSL=jD0$zp{C)tM$oM_ zPMV(!f*{HNhb9*dv?;-X60s=VrmPXba}XR*cZe~sM2fUUFpHwjsQ?hIJV;#ujS}@& zAo0};j?qfdWh(KI1jk?n&3DA*TGp<;2e9d%>%N0DdTrp%^r3vOBNnrV_4oA19@>HU z^F_j!Z&R{bKLnd0wks;0no)c9g_(&o2}?dqi8H&6W7#EWZC`pwWx1<<+_^p)=CG zWVXs>vMF1DzE`)pwULZASnGSXHNXZ6Q;6l#z&?yOUx|CNyQuYU1aa{q!jE}o0R^Ci zH#a)iC*OFch)+jP0QUcvpyl)GtTDYdznnROEY19>t%v zva>BW-`BoIg&&4)ifT#!SU^q1CMQ4JyA4y@WaoMvA|&OeJSZERs-QQ7h& z7VeLPFHHk)i~*gx?$?l$71p&&a%hti3`V`X{bX$w+QlL_GoCT&GhVk|<~Yy<6#nZV zf&TrudbcRo2o${!w^RAEfzXEw6M}U>E%7Ruqd-VVNUYyq7(o2@=wdtl8;hVu8%B6z zVNQGLRHS!k#^e$nbULNkZ{TVwqp0RvQuuoS5O|8nqqB0=9HX^gt*bJQVHorvlcfgC zpux|qQO4a;Nv0>0ja*ny;Y*R6!G3;^#e7Rx0839T^)6QSk`Fg_-r)ne*3urGX8HTB zswO4#RbLNEWoYoR2$G!GL6SU(^T{Njy~)=^;Py6k8!5Ym>1g5^w?`QY1-tP{ocURd zSod2XwTWaES4O2jE`{G}Fs(TVfml=~i%0zxXnQe{{3H!XDy0&emp%{lDyztf0ea2O zK<0NFNW$Mf{VOgM_v*0}=Men<2;YvJ!$;T9>FHMdiPi2tky!UAVWJ;=H5p_-3BttN z9|)Fju*Df&C%^Q{JWiC+GZelZhuLpjpCc`Lw6eI;H^H{j|ILmY`_#$9AhmicmGy8T zt`h8TS$iD0k^A)k1B3B1njBu-=MuKHE>ZUlpP7>kSHsC2)s#v5ydz{Qv0uR6z)r8&ZZBMxyNyBo*;^;^KcQQ zWQ*i7M2V=3@HdIZ5h#Uk2QE_DE;T%eZJ!agfBZI$x9@t1vWlF4uJoWMdTo`ML`U{u zP81(cQHN8UN_QHHlmRvfbg}N!^>C*An!>t?``BPzN2nTrKaGOu|zi2ZAM%0L}h# zuqrXQyx@W#p5-XDWl8Q!vn*dnu_fEIOZjj>Yp2B5*$+|ea$n9MPM?(*ossg@% zAlju`G8X8lGiA9LWLtawfs4#bR~R%>l6SI|$>B6~>SxQ1&PLf=-GSO)7WFSlcQBT@ zdU8AC0vZqT_7N4<@KD#X;jw8(3uTZ`s@>4X7i12N=0pAX%Awho{LXD8^B#BUw4lM& zBGBfq^p|QO*oPle-=+CaY-50qqC3N1?=Dcw(U!8`1*z#j`pM$9eShpI9gj6dzxFME zZo1zhfnr<^4FI$}#?uEP%~qGBNl3pFtK9AJp227hEi{Zddpnh^%KVvgVq`og1j|gN zB2f_8I}z7fIxOBs!mN}knbn*w*6X|R`p0L1uip1{67rZd)3>CDs)vDq*HwMQ=WP-~iE4{(9-ECfcN7(%DDlG2?Zy zj6|CBx)42ghGeZxBZ&Td=c+4eH~!z3TRsUplzQeA@ecN;$zB@$c?=3pQe}t?W&BNW z0Bxv?6zrZ^P+a|4 zz8((1#x=bH+i@gizWKuTR-ms?v^8u{m5*Qy_;;?>w;|{hX^A&Sq$(j*WNOk+Q$XHcXBnqgpRAT%pr5b<`+_-aS&1!7fAW=L*-;=gZDZ*I8lx0| zx`NeQZ05F_ewXu;2lmb?e^qKh>dhXo(JsYp)E8fc|57b=tY{s2Z7d6v%EVW!Ym$jP zc(2=@SI-oi8co*2J?vt8=y0m7tsH=2b@g_ww2r!8Z;>MK`9!{;#LsCq2Nl7PNPwA^uz#-L~hG_Lo%-24QJpSmM<8Kw{rn3caCxGu4Ef>@pzSI3f7I zgWqh#t)2pQ0KbiV=^39pvZ2UA^7@xnEyK&VbrTF`w!BRM&LbqZA-di1i65(W4e{s` z#-!=g^7y5z(U{5QJQ?en?m)O05*U3k#U(Lvy;cA;Bt@9-mH zmGZuF_MFI;!B=ojEU$$hanN_bCHmpH#N)Ual5d*)l-n%W;V}k`A(B&k;uvH|yp96> ztCHjQYo92_*!b}|v@?Rr6ah8S{1G01d!D-z*p#9=&)`t03EJz#GF|7>-D=woT-bRj z=zmAi=;t#z>2@Koxlo|VY_gbEe>bzJ@ix9~#*^6BZ8%rbi?3o8zTU-G$qm28guonw zR)jApz2-485?J}Yp<3B+sa6L=@i$-+w;7GxFLF-Z`mK<&&FEaVcQ&1;mFr}Wm2_f?)68hG!9Klu5Ds`}TvIs^MNS|GAUFlFuH(_j^QD8>=?t z)}`7{H_^FR9R(s@5VlvGT*0bse<)FT&cW&%5B}wH_OkRlnpUoP3TUUu$fwqusWs>wLn@ zicXN(l0W+4ED!p8coqB6mdo{O;>pRXk9Qc5(8hEdUCu7tv;GPe#9!bVWtzM88$8tK z&EiSs|2!S?vl*5QD?=M}gVD24x!0y8s(wrug zjZ_69*kd)48BUG!%4Zfw2GAgZvpb_T@BZ!x=>D^43`%BJ2s@kBp(=DZLuoj!0*gSA z5bUeIBTuhyL=2Mv#F$7&@yZ=p8bfV9y>X9xe|j1Ru5InGmQV~5m>F|@Mh$L zvrORHD{l4vB2x_BT`(WvyxIwkrWT@U!HLctTI4O}iJh9vzP>0HuKB>q8(Lr=*KVj1 zRN7K!MLw(J{0vP?tQ%}4eDk#S`RaW!N87bqm+;!QY2dl9oO)N*uar5i_|rKX*x1ye z;L^GVi{k(3jo-m@&$bBKzd!-P^;|Zaos|QOZrkyGShX{s<>z^G9{OjJP8y$4HeMpZ z|D{;o^z*9$nie?`42wT3$5FhMSj9iU>0z$MnWN|4aOT1B^uvAfS*^v+cZ(gqCvAC@ z8FnM1MmbGs*-v{wQW1?5!B3`mrTz9)kn<#F?q!dN0@!zGJP~kEQ#ml(3Q*4bj_;4y z|5sYzvS&|d*ULvX)=TXk(K$X$3z|Cq9|chrMkYSKB-#`m&w27od^+7C)1yfErHx6lgGS#k4x@}C1a+Ku+2Cd{-n-fp|^gAX5$J-W41d} zWxAeSP53?4H^=3$^lZ%X^iI`&ANJw|zx{i2jx!}}#l@PWk*}t(vNHM*;TMN>a|L(( zKe}N;3}e%)b^!jk10Ovr{@*cnZ#4?14oc>-+T3`DdSBaRxhFQa?uh(&a8d)0i4SfX z&>dUTDG*t%6DB6fRtOTgMLWd1_P3EJXuem%o&IdRAROs;_R z3YrZLrlC@&zwJA-)YZ;1@xyM&^t3DqvpaHD0o~>d#FwYgMi@Vjf?$TVMa3!us826` zQ%({HpG436eqHOguewRH`ss;54%zbXNBV$FCotz@Q)+MGU zEY*82o;AYingp(i{r-68+i-D?t zU#s|t{u+7lM_v15qxD}aD_hYsHd!%yiuU#kF+-eNPW;$w9F8kIfzqkki@$P|ICE(< z+{V9^9!&8fV@=pYt0qjjNEtMk*-tx)h;_~a1M?Ri_gmue#lpE1v|OGtSE$ZBvCt%! zgS$NKTXu3Sz186X3FutZOPWk-x!xU}g|?s8V_@I7Fz))CgownuqIeaKi0h8#C@P=| z?TEpZ8@3kC9SLo1KzN+4?C*4(a+rJAo;`+Jbm&c2G4MR0SK+Gq&FT}<7JbMUZrEfz zN4Kz-cyGrrRgyv?%J$2XgbI&e-`BP9Ffh1Pe9m6F1)0T@(nUC)NxW%VKUr9{GECb~ znKOvtq#QrY>cJZ!z{yv513vm72AV`}A{0vaXu9_C17ng5=#?&>t=QxVG+8 zr%dw^$Oc>6Ig?p5`O-nq+(o&K^QPUwgZMHEScw;&#=hAknpuqNx_gG~H)x=-aD7y5 zKd@Um)8$5UdFge!*Xd$Ro_$@f^OnPhNeT)jsuT2EeK5}g# z?ryH@;ro|imeo|8As7wJi!@CGOVcYWM7v#lIq@Es2Eb!@--bXY#9fVruY?Y z`xC4#^Ng1a+wO_0vgW4#)=A|}CM_h{avq_i_(m5Npl6fPP=2KfxwXK+WiK7s(?b^L z*w&*xQENH6GkEH#yC=|K#XnsfDjCgM!5u2O?q`app{qp^)zzmmw7>Sx`|ofd`o)zA z=m{4-wHCIA4i>M!Ojf0Bmc=_W1$AD)-v74=kmc*Xo87&FTrobeyJ~F%W-S<#j4#Bl z&&lW{-CF%RS11zOV)-LsC~57ij?ulp4PQK}rw4y4wV1%|SlK2;NP{`MiW1rI+x zM|N(SjtiHymAi*#^n~UpNJy8!N-Zw@)rIt35vDWc3#gQ+rR>=cM~9>GPgQwlGtI+Z+q; zQB!9C0H-9#1{*EbSV{=yoqaHVVRL1CMvIX!DZ@+Vh+f(T1qq!`)~!Y=Pepi#AGaD+ z&^MiM-#Y&^iS9Kncob5N+pIQ~t|U(Qlk?}NPL~B6(goZ*IwdC|l+w+1c06qvvg+f+ z6eruOCdl>bH(eyJKRY4FzC9mxnQtRMr0aFlI^uJ#8r~ueL-eamUr`p-#64sSXBgaJ zDoByf?Rl26?9qmMfjS6@AHgp=Y@L<`Oh%qacpcM=M?^5n*Xi=QQ7i8E$YvZKq(heA zWihW`fg!9X0zM#ZJRIaqhn>>CIpLNcMHQo!vPK0s@LDJz_ht5n^q#u(8Znno!!^rk zRm86uRWFTxLT=j3hgIU^bu2Ph%zOamR;*@KLmpvEJHGW^4@`%NJOF-!^O`#(W~$7a z^}CS-irLgr*5@ZjBe#vTG`ZL z8+=8xHKa93=ivlTcDfF$$UNSSHZl?t?-Nl^9dT9qzym~3u2uEU#)jc>(}KCbhfC{~ zK)Qk*=JcbpHN@^&?*KK}BA7w*p+t^bReNqUmcszq8{X5S(G{)8XXc(2F@d*!0w0SbmUaUe~+-fngkH!o^aNgz$6`AtgagYC^Ev zw60#v^QL{7bE;T{6&gs?t9sMI$q>8pgX#oyS7uEfU(V^~7;-U+EM3<`ILd256^cIu zRlxtwcP}q5;x!i@_vI~OZN$4epM{pMU0FkZ^D<`eBYTppJ+=(}EP>aru?lf;I*vQp zXWSSxaKHjnl2zRQ+Q0uhSSM83*ZsMR*Wj#}&aFgo^3Z;{KfDo9?c`DESlHpX8#RK*wL3e!fV!9d|S} z-_Sq8{EWonXeHZfPv`2idWUN0AeSiB-4xysRk9&DcZj3z^6uvvYnj=tPy2Hc(!L&t z6Q8Hyr$;#r{o*g^gO9z_z``P<$wP;<3lC>nl#gc2tVm)k+OP6A+{Bn!VH1V}%EV_CRX0%b_YKuAY$`@mSEEi&~mmK^0TgF$!@7 zgVa^clY1J46dI+*(p4p|?urt_9LR}$um|pcajEo&uld#m>V8Noy4Dk*mj+NGJO!|O z1Wz{m{c_tVq}J|~H#k6-&1wRfkH=v{vOFGLf0`s|4PPNkJB&6$o75>+DM02a#*vbH z>EYd>zFuDSg3WBBZa+AYU>_}{ zBbj^_;^>yjzz~vNA-%I8Bxmy35TuSk_OrYYXe30jvx+Zd!*d~RL`l7!7whf|AKXM@P3Oj4t!;PpI zypKf#+88Kt;NfrQ%X~bYRfuLM$7qhJ{{>gR_3t4Ng<- z5Re*>RN(}=Y2S!p%v2rf0dE06Pr&ek(3_!i;=v1^%4J#Lb;ZIT#soO_O}O*#-n>bZ zuP-WLc8RI&QJ7d`r(u;tpx=Sq$V_6c3PH_ToI?Xxc|&+k+s>?QP!1jkhnJKt&sJZt z(sC!7!)2;BVvj-P>fs`K{W?T*VA|bw&Ct*r0YGX1UM3 z$47=TZL38eWu$?k0@>lyRMvc=HTM+(*O{DE9GtGmwuXp;3LOy#6B0r)f0q(+FDY*9 znA?V}dfj=Z_72+}ziBxOqs3CE;S8FD>(%-?tTms6eytk$!mF*-v!Vy^2pD2;JWlxc z5OnYr?}`#qjt3+IW1;>bHZIyHz?JO~(4{L2ULtadTD7E zw4qdOjo2OBlHvFBa9=G$^gj}~?%4u)2v15Pm7H}ce~gdMTB1t$aG)S5cXaai|e#KU7e>xI=14M5t_!&2)&^!HoMh zx*#RLGW+Yiv|P$JzgE5NFkL7qrmI)4&P-1Jyl(R}yq^pe?}rebS$%0sO7tUVki1sL z#dDQ}FjkAEM(z;}cNAwc=YnI=4G7y9*ucf37~<1c_*m|E>^E{R7oX0VEHq&%cBGFS zw%u1uw0uS9e>Yq_V{Q|kTk+&{_ON26BUc4)Ijr3)J*Khb6}&$Wt@I63y1X`8aZbM} zm>oW+gzCs{yHq~+zT;S-T{JvpULx34(WaX4+V&40tVV(pPG``M++yhRtTkj%^F=+| z|E?4v-Hh?AMT+&^ej>1dpceRxMF&G#{=vd0w|J6Y72pqBFYd2Ogf*fDeBOjT%C!7| z2!^-?(d@YefQX{FW1I*F2Xw^@Vd`EZcU;NS6o;Z%TeY{imtj5WvqVoTMqGJFX%*mL zu3*&)QXcF#fGJ*cI)6fgl_Qp-Z1dy@+T%AJhl};AZCY7dRl{#nqRTZotcJsC&kntVjHS^Bp zCG4d<4k=V&gZTRrU9b_T$er&jkq(*4pos@!#nVzmXdq#fWp}!K;X~UAhmtwm2mQiA+iyNhg}E!u5(L{2b`F=>N@!*O^~GtDS9o!1wp{p zz+L_Q0r1>3<2#jld0Hxn>m^}5M4VkoJ?THG?r1F=?;vf{ktgsh;@YH7W0t=k&P?*Ms4Ry*JD-euSL68b1E{ktYnJZ&I0#8c^p5lTrDVR z@~{}i$6hD$qO3o_I~}podUm?7MrySawjMy>zU^6Rw>7RaBMS0*gV+88z++E_fC|EY zE&)73vbMOxc&6i)0%_k&&0^Zu!Wg=bCc2f!?)ul*HfHS~TJSOFxDRE}uBKVfT#;TL zvgdimLR4eZ)>LXHp_h>7O&ueyK&8tUYK~Pan`fGmzc3_8d)JJrxc8R-Je)QDY$Jh} zQGVXU8~ABIH}rZve_mr<7V?_Sbk%9kBYS+_`F9BHMic&n4}(Zu2}@41wFrvbmnfIj z8>EO*x%tl}_0SvIh&%n8K3*+e7hKFCXQVys>G zCJ!~eCXSCib=qnUbT_xKsA8n4@U?oNn<1IomEqE&h4bQZI+nUD6clVE14*g@Ags$Y zJf3h}sN3(VcM&Hm0h8B#A<`cQCy;>>ilzq%VS9%vR69HUcjrB(+_t8DvaloXCf($) zxH-h=BCe{elUk@ZvuS4oydM~PBqqVrjQRc+HjT-`?vz&JQV&F(qv3#nkkBlRFuJ96 zTdO(|EI~VjkFQ6M1rimyd5hob%Ez(Kp0p}wlUjOMwP)Z&w|s>A%o=H)gH~D=8z5go z0+gFAf2Li$_roseX|JLxFKO9+XGmr%(a~oHWkMV0Vfe|>ScfKl>w;u@e}7AV5Fxi; zsQm3Bd3OFGHcrkLRaJU&E5M0dth zzC5WlT5uvDynN=kHO@o~^X1Oz2H~y1<#m;uU)~zslIw1u_}w8WT1+(X^Cd|BR|Vsr zx0lj=_zpu0ZSrt`Xs%#-w6SLzliea^BvM4s_QL|_|!zU)HhdDhU@l&qrxC+JJ83#Lb z{=Ez-#8@DQq5$g+cUIMz3wC`6b557)lF?z?q#B<-vQP^HhGMKkl~U(FP~nrHHV zmB_)esSA}h^#AmJ1dN;)I*u;TZ)|OkRqW$@%j9w*EHPbjwptv7P_MLgej3M2RlLgk zdUG%ltM(}4_7As=F4qTqyKPss>*w8&XBrM`rDjt{a6kFV{?3=xvo=oWIh`G5>J1R0 zuy)-G`}L>35KjvN7rBJp(50)@2$RD$g$G{cz}OpYZt@XAWHFb~CV`Jxw583b!WeI| zL3S@96P_rF()QhZYi@{vLN$(8HkGOT7tPz6uI4&U=Q-wwjv;T}^lxG-|D)<$Mnr6M}-_8XJ;DLd-f((tfp;)!y)@uPVEr6RmbOXKCpe+J-pn8W8 zSni{>(Q4>BbCzfSaN%^oK{M>>jrXsjZovzl7$nc?@?`8N37 z$)a*rhdq>~qca#JaJa-U22E~ue3^B>Webm|Ya>=mw-qU0@)P!(HK*vr|A00aG`_#w zC&2CQ3i6+*GIdg`w%2goiY3iMcDdz&jE z1AvjDU0HUs9OcBv{&06-)J#l~0_c{$@MvjjU?U}dKtU$+JDOvb{uIEJbY5wS@>H6{ z|8~NNy9vQV?-7}_>P@e9fZD)mH1qV&jo*2e<1wmx2nLU((4hH@ki_RD$QMJ&mR8Wq z@r(oBJY#nmF`eNSL&zNe1LeUZ){dyhGcPc}+;u-a7Di_2G0(ITmo%d8kfQ!Mpon#W zDP4&x6QoDW-UQhZ%dXdTx{dcCpsDp&iEe)0%OmLH2!FbTzg~({Kc-}nQ*Yy;M zHMDqIRJ*soJ5sDhjlW~Z$EmqP{<$xRD+jIg^_W?i&jOT@Yj=qaQf%#f$)}Q^e8m~H z=8&`Imhg^ST6ql3paF5xO^yCPA!Gb?1#T!>DpgzGK~-TPDUYff;*suT2Q&+>?)q#| z^oj#qyxJMF8ltJ;BruT`646R4q{#2Gd}|(scvvFgU9UUlz$4J1-XF7W3V#BR&W|GE z+0S@C^=-M}8huQ*vg<8GE6wjz7~yz3_qsk?PzGaR>r*!w|Dx3k9e)z2Jt=blR5)m% zoBoE@>=0Zeec(m2JSy-1^3cQTkDFr&G-ikR9U50M+C^uUSAQzFwIhER`u9U>#wN3l zXp_Ylw*?QJMh2qbt@T}!M` zuIeDMMX8}!-@J~tQbl~pl1;z_6fF;x7D8)XkfryP+8GR(3%506K}Atvv+*og`Eg!3 zOKd8YgNW{dzk_-7&0Dtu8bDkf#zM{9UPc1Nk5jK_a{c#NFlsqtm&N8R;P=Vh=E{G* zdGPROgY|e&bw&rLyKG5*XP;x+k7Q5Pt6&~3NJv8P5=r183J9d>jB-?znQLe$Xe}V~ z<`hKL*}Fr4MFewQR?Dze0W>v3NsX=xUF0o3;-Olw2pYlezL!5|wW=D2gPCF{Z)70( z5QTi2#O0M{*c8t--ST-e42^~oySS#;l_Yf0T&hi^!hj)6pa3t&F=2^sUE)-r!B&ec zLm(;ddadl};Ipe~XgCw&aA1VOf<)$W=`S>oF}fp+XWpNH!JA!elpF^KBv?cq-dd*JPf!QwtG)J<{^vyT96Sk zW#g73Dmbm!*cy1#>{YV@?6`$?jNdix5SzNhizv09#7>}F=bnLKucgGTw&@uT+zOJohpV3qltqeL2(9qY1UV!#lo(iOe1x2I4}cmFvN%-12G z%>jZrU&O^aABu=bSU~uPdOT&4T<$wV5;HplI|yd}<)P63Os>JvJGS;U5m*d&o6CG)pqwAVAzqc3j?4MhVs))31ftp$A z^orBnRm_)fKo#{_APR^gx_ESwK=3_UuwlUn3Z5Sr5AtR>ITS{2%D6I+jk8)Vp&^`l z4o^88nhUKgIuuACvWltvH#Gx|#Uk`e%YN+953jlPI-R&#ja#*q1Ek>YRamb3&{BBU z*rA+e2dX}jt3=Fj{2Pn$8H-AHw8!CQAES-9s_@aJpk%aCMl;maN6kKb+{z?FdJACs$#*CVOn)z+o!?(8)fp7uW2?KkB@6>O}Uvetr0f?c=fB>LO^ z7uB=9bGLj_8N57d^dv@)H)4aD)XTNOiQZhi3F>J6(&(1R?#HNU$at~GC7{g=#8{G=&xvbXd^*?> zL)xLq$=z*d=xb`x+~A^F%HzIpV9*F0mv&FPU?9UCifQlNmL7fE#^dx=6_0mbUcbTm z&4Y-JEiRobtS$xcedhPXrjSlK3`n5yA_`0G6-7RdM_jy;xfETN_5FSujrZ;d3i<)y zsoai}LC|9u50vLWY#phBDt6U!0f!PB+ntR+`aWTxlT(N|cw{BqcYL5-w?Gqcb} zk@oJn3r+1<0ogMEI&oD^9)ThH+xBWN=N-xJpw}v6)v_djYD^b@qVt1EMIN{3+qSbA zY~%uT07Kg!8HmPPuW{A0E!LHGItDq3RU3omy$*H8qrrhU?Ix$YTaqm%4}c-Co+T?? zcvS%qES;B`Ea7|0WsK@qx_}ZJIsKMZa)PdMx^S=g(p52vq3P zPyd_FNDcT%2MuTa%A-jC>#JF(Z`$HsuLI(apV$Rjhs)E?NZFcqv^SYUvQAtHi7*A`r2(RZO6tQf(G{WAso#z z9ha(-*LGm_8Ny8McLCZvI)6FF59J3_V@Q*@11nH@_Wo4^Qr@K3VCrcUxC~FnX&!Cw zcc_*$4Xh87fi5G5uX0=eU<64IhmE}h@KTf-HgyzcHIPi8c=GgF^`Q~6nV7vX&V47A zgDE<9FEnG`u0sje_fQRNGBcFCXuVj5019(IVJ@M@KlS%2wQXE!nD-Px-DcBn3-wv5 zx(mDhBv`tUn0^i3I?(2;NC z)o;`m>l}kAz3iKN+H{D51WIj|PaRDsKuTIvqN{xn{WwqCTn5-n&?qe=pm32`#1bzB zhfk;}1{AAtg?2>XGN`jN0EQd|IK@4lHpQ;6S2w0#&C09_M180V$z2;4+;JR8Aph@< zSQ8Yy>mLUwM+22RKfJtN3e)P_mWYV_CV`LaecaG1)>u<}yqPru1AA_GY&B^?+Tq0R2tXg1c(+Ugp zS<~ha)U7WW3OAvimOb^zf%);tCY||`x3+jyjtHD20&7C>uPdnLLi7G(- zPHn4|poz+$J!>-uf~42%2wZRY{1Nsd2O9r*3hZOs9cZq*MryC&OJqq=Yws#q9#y7V4OFzC@`( zdn0|c4stZl4F>T42?SrX?6iUerc1Q|nChE2$4szL;_v@n@$DE}$?!$vwl^NgsYiI6&w(n z1%G!5+?nOc`uVH;^AP#2*mnsH1HX-1sjJTuvz?1RLRJ{84tSb6jiZmfb5VB}Kq<)o z_x0qP0R{yik%!goP7*0p|GyhhxnN^cRX3p$)1^gBTul^w1UtM)s!e;30+~;mbnyGuKSHW(^039vb>lUyrv+`uhPZf|_OAT^klc4Xyoc zc<0-6!-X#1vgKV>ta4@uh&|F0WCH@L!oftl7HQz z&}bncGOH&CwQCR3dVR4g9`yuHb%DPPef#H+K-l|FvizuL@?|ykztbdK{;!+L7hp`j z`NzV7FCH-_5P<^jz#g{0?1aha{J!_EUz|yLL|LyOCDiGh0A9U#rk89=U7)K}|Ds{n z`80nP@ppS)ViCc(RhR->_kYr$eyck@b|3unp9{v+_YKW)?8o?j`YP|Q-=>4(^A_k9 zC0x&44G~IB@ZU=yBFG$y9T*|2+4gJn&N-iZGkaXY={YpLzxHU$wB=} za>&`@-+O@W{YG1a=GeU59v;GtJ27FuIk|D=#O<6~E$kK(Vv5><4!bUX!NH_Ox>nzw zm?(V0WFXRsuL0U+A%{u(SFW|qUXZZ5&IPO@>p$D0(3?hJqdFx! z#U%~h%IbjkGDO7=b%3%Fdvqv#p@Z|b>aFDIyn37in)Po$qj*2UMiJ5CB&R)981ORr zb>DF)>Yc*{E{rKGW3X^bwsLvG!k651*sVoJ({Am({+o)LMGT`QXhEaP6- zNuPs`R$8gZXveXZ4WNu^svY%X!ar#f*Hyopa%`M%XDD9f4*GcvdYfVkTiG<)|ikGsH1r_b5{K%57-xr{2$uClVJH-&m%H87Aol9m1F0{tvRXG1LW`uILqmNAg|SqodY6Ub+-vrp7fVRgbL^W znc0@c7bdZQu={prY(64j78ChFs$zPmRbRnMbmqu6cZ`_)B<|>&Y+AE5e==+4xqZRp zYzR3~opOG~Q-FwEvul5ZJloVYui6=*gAAKU(*!)XZwlvD0SRx=|4A%m0|h@&-u0j0 zex{Zj<7WY)?{T-briKB|yZ@Ns9l?vU>L;+>Z%E(^6^v+RMoRTGSNOgjbES5t{PQ9d ze|b8sX-*~{A{1EZ^#VjXn!+}~i1tOX*Tr1@wF~u`adtW$pp3e6^5QUjLy<}cqR0Yd zCbnOmFK_dh3K0(L0-N50q(@irG!yTcl@z9%Y>7((z&r>r=DD zFl=l%b+riN{C1%*NyZ*Ms)Gz|7cZKYp(&uhkMFFPP~n1vW03ueE42Ue!(~{921n7j zD(VMXmoBnvq?c;gO#O2wiYW6A_Q=QrfB?zhF^)eD#OHu4{Jm08Q8;w5O~HpE z?@@;$gB9Y|&47pHO;cP~VIu$v4-|t*&7#L)K7XAD9^XDZ3 zXbse@MK#LUz>b5gk#jOaxYAz{OJ^xCWuD@*m($BA5Jt1wO?9*wEZ!9Wg@WS;jIntb zyP%L51~pb1z$JNX0$7X(#%4R0QD7dREt78*gLosk=|eIbSrz?itoDCHyA{KZc8 zGtn|+x$#MkTroZF=qReG$_yYTR`qV&GZr;lT9rm_9+j&Gp(3jEa^1(GxQ0-*=}z?i zavV1|>gC)mpWVVb)%73WRg+vbO+So8^^_#oaEbco`Bhtb3(LRP1rvedJ0mT4Z-ZpK z;fO&~xqGm_z7HEB$9j@_z*)L<7j|V*hE)>N88%-R&%J07P1Q_MN*L@0#U96i3(vjUpbU3*WaF#eYCH&>N?G;2LAP0Cz50Jht1Wh*- z-3AC1s9$+qm<2E~i}hOB<7U8X={U8t0hx3m*iJwL+L-h@{ab*{H?-3K*xL0Az8)sF z(pB|&W)nVk4^DnBYwwMC{??@I3gNu~qZqnW9(%w=0bV*|{rNv;DrU9#$Ew4VL;$6! zxZ~LI$0rXs5m7UN-RPOYdVAtZ&T_>&kF^+X7pCBtEL}=8K?)b88}G$^z2H8tJKvC} zQ+TD_`I^z^^JMtVlSlDsUe?2+NojrGgj@9+Wrql^OE6u|7YMpOL|xEPwReF2{25+& z*;d8KuVuSi3$-U>6AMS4!S(Avedx&D*>k^o$~aBoe9?{PxC8rdP^0B{I42l2okLR+ z!YxwgsRFI7wc^hmAF629qedy7!*%m~w9b29r`IfVq?Poo&|$vdlil5If>dbqOWr>Y zWLoz8=I7soF)roMWH=mI2nnsuRzef57uR_rt2ANmn=Ql_>=Z_wz0Dx@u*?3od*@N5BZ!>%fa~t zV@ykQxNj}E-0>#M8dR~;ivE9ZW+K$QM~h%!PtHrQ-JKv6nIC=HXY5h^h05|A3mq+^U6{lA|Lk@x-n z{?B#c#pKx?=RSSTea?AFm}rEg2=B#q9!2WA+}sz2j?k6{{rf@F)kIR!siBnIFC-N# zSL=P)8JIe#**ydA8DfGd>d-rG0Xu9Iv1`BQK-wNkURtoWobie%Y-yfh%JYiz_g)|S z;qwQNMN`WxiGJK+9+_8aFxUlf_29!b<@Ty3(xfwb+fXqH^%Euy0odL~s5p*){F zutM$uS8ieG!I}?p(6qGY*2!|pdK-^SQdT~1Yl`=>b|ko}&>=nbS>`q-#itWBCFK*- z7Ru56uzxWi=HDjU%ry56Qc{5=&^I#d*Mt^*rEm_{02Te)1c?Upum3`bL8-L-T^k5+{ua^G`qpQkqUYD^@endpc=J~_SwoTN#jF$&a*oHoMI4=UXdNDbEfcbJ&-MK2$i6f~qJHI5 zkccbw7wSK;6iL_l55J>^SH8Huzxbo$swZz3R(P@WDjlV#+#MG?3ozC^gN6%3pLPH? zp*NH8ltKyQI#+X_xOfW|aNX&Jul==W%%cjyQHQzgGe$?gpY1`Mg*VBaEv63G&;`J(tBk@<7CS^^i{Dt z;SPUe^su0Jbwk9>zAVWN@+;N&ge0d(6yL@6Y92c|{)f4eWs?Xc_tv0$`HjNOkboR1$D$M|mFyQ`09^-QBYe-Uo zR^|Aj(YuBrS42}TdBJ{iFooR0wB#p19DfaE~v?wzb?PiEPAO(md3#(h%?=Luyxl}R zONa9$vfQv_pGK6X5iiH8Iy(y^W8K5NYTtazSI(R8^4SSWkcK#$)1=`iHC z{xZQ~t;d{;;MNT&EOcmW=Mh~SE_3cNM|94pVG$1X@d8=acj0DpuTn+C*RT@Pqtk)q zCDTtS1YbUG?s%}G;l=EN;pX+#TiN~9io2YZ@ zVZP&j2|l2oaa_qRDx9%oV0N-oOTcPFjQ`esq#0!4(jHw~wOxA#43r!U>mysElq0^j z2b$8)T>nWWWaUo+O?(!AUWF-}b$7e^k8T96RSjl`f*ZHvaCoglCXM!kt9K|I$#<5K zikYQwquz2a)i2^94Oae3r%F$M(RtZpw?fH|>S>LoO<+NzU+NTSLFeTR8*)=QGIwA# zwEmF~2{+OFC|#&&xKGJ>hQL(kF#Up;wr#dxRd?-A^dV@$P5-s_Ho#^LIQtA|*0u4Sd||xz zbND2y0viKCZ#O}cqA%|tYUN;eWL+j>U%9E3g`>;0tDIdS8}AqPkCk_3?xyx7W6@2 zhdde>8gf`J9By^P9tSH_g`=V<^*#+WcBCV@lTb~UGI}^m>5HC`?9wxQN~@*L zh9&2QG+O(cpU}8rP4H^N<0)H|Ef~2IqMuhgr&wFo9r>hGWTS8LYm9vY;lkRKeU%^V z7kuhhb3B8DphBsj?EB80@981*NyV>1$8;-bHe9mopUlmH7BY+4;>nh%6ygMN9WSiT z&kOKyL0R<+T_q^|9?uRi=J^h1(2vt3*5n;^!U$e-#d zSuvT7(G!k2Y2r558YZ5Sa#eszpAY^E$_s~%8^bo%B15mi&264N7E}c|sLc?~WGD0J zZhBWMn-B>|1xV4ZtiY5kJp|k4OwO` zWP_spc${NUz+L+b5@YvrJ1NkQgDSKNbmf1+^XKPMIguiAR-xhkqAUH3G^l^^w)$U3-(JY8Fd0wNjk<{p&W7UwPCcO{$lrTki-Akfr zW9^zd_)YEaM!tL=#hibLX-}yOo=5WOVo5^8lt7xkc zZAI!p&_Dd|rvYu+rsw>>c6h@TB|;8A%toWDWEUEpQNMeOw{*P*GGk~~+y5@#=)qU3eM_g@OWe7%=SW2^h4rG!kq%4R-~VTpX1TY>WhrhmAk1$MQw^<8 z3AA&dF3|$0;~L1}X95l9-3>hl9jQpxdS@rNM%k{H!H{b~rN=N-1pZ*WlQd1weIK69 zdRUj~Mi~nj9c!wN5RUd~G!gqG(csPetjt9Ix&ONc?y;ufLA%Uiaa)5@9&%U8j~oM()=!iNax~8`KJG3JiLV{p z!P@wPu>HA$EwdyQK2g6jC)9nty-W2^#upJfVbJiV7iVk!BFphFucrF!$Ar_EqKh6p zR67?YE7B4Ufk%1hM(7Un>dm!s#9H|Gq4&{UwnU#O4oKuliGF-+Gz zgZDH!6g#_3aNBpa!$#|Y*A*MtvbE4H7ET);vvc^-xFna#exoI2`S~A>@%2g`7yIm6K#0Y;iWr1akfm z0^j17$iE4}v4S-bcBta5C*>PgfJUTbupD)0@CW6tb(e(@%K9sSlGe#-H=L-xyIZAz ztXP9U-F=zN;_*}mJhTw#N&e4LW?u}YzFMD#Ndxx*G2_ywr>CVsW41aDDp0_Cv1amX zPT4)EGc@uKW?j5$q~o_tyK02 zeIfaDm*FfsI&yq#UzR{s6HCr%locv20hM=4LFb*!!a-jUY_Pcg=X7qdt>o0OpxOU` z;ucJZM;1iJXgvb9G$JM1#t18aEyMz_K_xZHqLW)+fG$ZW`fF#+z^OV!wqk+mT0BlZl_6viTSiVh< z^zG({gW-BG;}(UY$EfiVKzJ3fE{j*^yJ+l z+y#IWz|X0;m=#zB`mF9NU91xII-jV8F&@0SwG~)!n$oYs6|WnkS;0Mko!`5gevc8V z`@FZ*<@Y<)>id?_x;wsQb2<`q$Llrepd@u?9b5d?`8-@<-=s;9euJq8`E}sS}I;R2}uV7tzDT@5(E+|tnnm5;^q!c1- zaCgUqqA7o#P^Q2|Z& ze9)eX_mLB3oA)!wA05NLxBq)uZf&8QDZP`tz@YZha10?%T@d&y3;EQxDjAF1q$n^Q|K&U{Fxq- z0sV2!=Y|`e8_R)8!-K(Cq=gTY?yJSc#d}2#7F~@^Lk@rdZs*UXsBaj;ZXJk`f_->4 zav1h$U~4qd+yptZLX+|d(v(j?z%RQa53TeE zY?~b{)SkEn(-fld!*75eitR;?Yh!#tnSW$6JSocIW|ULw4Ia%uF7R8W2Lxa}G!5vG zDx}HqXO@u4%(WbLjxa?*t{b3XzYje z$R1PlZEI80(@_7;?+{f+14wa4yLq+PV8oeajC50YFE<{4`CWF z`o*$+$QuJD8>?CI!N6r>1;3*bNwx3aC`OpT5`KhR#<2DE^#M#=>UAVm&@-H~=Y~)L zJm^}d{^BXJzd?_$$F*vPJSzYCHo&BUzCBtigneURTV&A;2VJcFp@t_rj=ad0vR)mJ zdAH@{Vg)8G`u4-NL=F2ddsrsPE1yD*PlASWJnGv>(sei2Mqq_4PogZ7YK)^-HLzv~V62nMymiS^u=!vuoPt07`k2muf%5A}4kvn(UY zO*KEZ1k@oT2#K#Z0-n9svlKM&0u8>2a{bGiW|n=9O$ws!p6#i+q6k73o|7FkMYws6 z>cjwJRXnkoniQ&$3D5Q9fWTYP46T1N8h{WggIw9hUhk*iXHc)d-8uG5lb zUC=+;=Co*%n9~k(>5Wyt3Hhqwyq{`q#6R!zw@6G@N#KtxhgBpmj8+FwdYiaJT;FU3 zhhVIG0mz^YK#!Q!I^L6=JF+fR;))>i?LX5T+BuDWxyK{(qBE6IJ{m&-)Nknk>kWPT z!Rq4FyQUGf*-p@jo)UDQu#o9mI{BteOR4nY=D*Yz!S2te*qvs9=R1YST|1S#^a79_ z^rXI_X<5_{39TzOM(^rE4}?j?o!69kplRqeG43{+65T>*S&d)Pc$Dh@N!)-a$`H+A zCvW-?IGV3IQU^7EzH>L#!37yUes+ezqxDi8(&CE1*&ilbrpV15(u6r)HzFG7?ak4* z4m|c}xVf2|PN0LmAUTVE2gEaVH1Ln9j+?c%Dsrrxlda{=T!6_bM#k_6ok?*U!*k&+ z#~gVjrpW6cIB`anYDbug?L4jnN~nP`R?0U?!e!iYMY#Pm+3y&QQg4Mh?cDpZ4NKis z@9BPo1MoglXTG-OlYl;;Z~xm6(#Y7SWaps$|N3)kr`%irDWml>5s>fv^5g$IKx!wU zMJ|4IDO^(I#FT_$+(qguXLgv=%DO#;34EGm$SUuLxDnvj`vgG(##;1WXB0PW0Pa~X zNB66!l9a!QYbrRo;6R9OeGm;JD2;`IC38S9fX_*}-p%V>!4ZuP&o>_0xA3qa( zlP8Qyng8<=;i(}Y@`Gil#meg4ZPdZfs?mrU`hZSt>yi_TUkxN!T5X*}&<;P0a{Ji0 z5OUQ{mYF;P(gC-Y0U2U{9-ZjMvaeDwjO*IqPs?t~|IZW#Klct4h+>#Va2}W!TdNS# zp8hik;1q^Nd#quKn@ueE*TyBu|DhdtkOhq~QQy-|dV9D6+hwQE7)1SiR%_=rw7>5i zNGy)vK1&7l^_U$bqnngtM*)V^gt*Fe>Y=`s2Z#FSN!8TDZixs;zxngu%IyN6ZkKj6 z?N7?iJA5Xwsp&o4%qAs|+doe~PS#M>kk$Q2vm$C{9bf$!0H*U29FX2x6VaaRA9#3` z@URDJG!8=x4l-$Mzm)nFB4^R{&NF-ZdUQ-uO`MBc>@0{_5t$}oh2fA%^o z1J`oumftLybNdu;orMB2fUYTDo45k}QFqqXwSi|ANBa5FelhD{!fkMy&1G%^->vF| zaxBHxQ9<1PjgOkN0@iTrtR5ksS8;Rh_3L>;*;7O0RH809FY<2Hnn1(5o9kqKMq?OUt zTGRt)u>Hx{*;lGqw$#Hnh|zSnI2YY6+v*LwCE?<R_}CPpNn`_f4)-g`}LBY?=ND z!5c$p;Skqn_wzUc`|u6Ka|T=dIiTp}8u4)8n@4xmuJCRQ<eo_uxxg@kpd482Ju26vrF3v7dS&TG%HDK20Xv(a6zO*mwRp?W5#J5`ZWz=;Nhlt~!LJHh z%!yKA?YS*gSsiWd5WFIV(;FZZjcA@|a#~a|Kv=F>4JAsOy1)(HSN=V3VYsf=h?~uq z;1LGF6hqI|_gS0uA;27#xh?)8=mJc~7f=w_dJ8?7h>$#Pu|W%9|A?>O3r)uV@~^y6 z7EmCR2@wzrMu>Bp8!4-uB=0LqD02vES*2-qfuxf00(g+G^f@rvbNj~fKBg|Sbj{sp z?(ZXWFS||b8vyn=VzVy^5LaB&>-x;I5SKxdN>+sM9oEb4)&oWO&D3x*=*m32Nn9ug}m19 zA#OAp$mZmo9f2SRJN`F9YF;fIXsv18p|mz1=j|QV)qT`2DNxJWwpDgDo2(@ze^N>T zC$lm2=36kDj^9tsR$n(80+s!$rf}DN>R?rG|3=67gYy@Se43C}s#<__#tvw_EMBd# z0l_%0&%NhC?oo%`gs+<2eWUET5D>!s#-c9R7IVnyxCEMC4SrTMlNID@u=xOA@G5(ys9r!_B`*4s~LBOX7MNVXWrUhR}x3 zVUz^CW;YVdHa-joMN#dCTk3xkD$r+#=9UW=S{5k_=2Jj#4*1zFH}kslOn0|jT~y}U zv`6+uo^vp_M)7D*mFP_}NPV!#(IiKrH!u)5VvYibsyGSA;hbbhwlG#7(pS`FjSHNv;cUm= zT*6|JR+dp-?HrsN)Ge$gsWoK)H2Fg5y+2kH`L6!K<}!keHB0Ra!O_z7FjSZrfV4bhrBc$ zB370n@W=C(s^70HQnoyiU$~gLFcfg%!Qt>w5m0mKja{<8R@uKd)&@#dKb*c@2?fF; zMM{Ki4U1CFj?js@951G$nDb4u*eO1``<13Kq&}w!Y_M{jjD3I&9Ly|H;_Ui)dz$}S z>n*wY{s~2gU%%Z*=jVt$__E3(+sLi#Cmi$%->t;5)N=T1N#xK|nG|3c<CUu_CB{Grlb3zhVQE95{I!b1l945e5t-Ws@z>zB5XXzwWQ*x>S|IDR50%Q zO$+9gh{CxUfB4i!&QMDC$yCq0YP8<9k*RJ-d0CQ>KZ{ieNWuCh@Jd#`RP_&33y5S* z(MkQN027=T#=}wf?i?*{<@Y`FAW^S0rGsKP` z={D=j%%=<`7!da{$TN4Ecp0jnGJa2qfgMt3NQe8T*}Cz&{ zae%%tB09sqKO!+`+P?mGb>Vo_eNdM=$IMbq)o?agCF^n1#y8Q)r{l9umnIVZQ~eom zrqhmP8)H43fp&zv#Gm;dzsn>v$crS=fJlOizRn3sKV8K@7PeG~;7I)D^Afl{PFl%# zP({jsCe_gemO$TlWx^#C88|l*;JLDtFp)Yq>>9;+kXMTLPKj*O{)*R*UvTz59dc1T z?290~q##vqX?HBDctc9ae2%bq6&^t&p3~bj1k1HTINq4()C0a6pHAy!Mj8Sf-Nu88$E4bj+zl2J zXTyt}r;#5(W|RtEoxj-2StYw*LOVrgZ9<6Us>OYh!rsredIstJ?cMNIy5`M`1+G;Q z(KRLq)&F-ym=&q^!$(_BXLsb{5WaeD*kA6qOjW9;+pZ^9D}CBjt3xxTMNS?Y#U^!x zoSxrPQPJ|Fo2|%j)|uVPgQQP|U9-vZ$Ky1dLDMCbmK5%sA#5st|wQD)J<|HFp@LpELoU0*44PGQbj}?b`Q{p zUvRjGTx32tC@!ibsk!o-BP)leD5bQ&gp|T+q{j>@C8s^m_NN;y&o256Dp7Hq=OxqB zX!>{CvwLQKN|00BoM0yRAv&vmWnaatF8JamwAdv;b(6I-2jSCpKlsGx3KO%JzGbKA z2r4esniEOotETZx?B$dm-7G5uHRO;4o`oZGuc_$`k6knGh~tAAmg-u$ywC|%CCZk{ij!+(2?Iw;}%`*Wogk2qbSooy#Z%F-G+YoV&@F54A5Ey~$< ztlv0Sq$L72kGi1=b_NCR>SJx=na3Lh5gE#Ap!$c3=kScDY;sI z;6rG*Id$5Z0;IzM8cr)?itIGBv6JtA?;d!U7ks|Jd;d!bW()ftm1Uq4QQPTELSfXZjAlY#9klI@l)VH!V#-Vk};0B&)%tl5*-5~{2AsQUYzsct_=4VJ=Az0lI4 z&IN;wiUR~43-(ME3My6DsBTMQ!7Uz6((?25I_VN2lbD&jP>ythN3D0s5nru#sAi&5 z-og%@dx^wqCEei}rFu(EXT~tD$G65~J+_$ZyilvCJ5-|qssj}ceiR@-TPDsKOW9q% zf+H=f@^-5QHAX1NwyF$gyW~4ns)GDD%yRpIe@xMrGT-j6u&6SAMBV+Xzg5#$>dO`h z`(b!Vcpy(&DKTpq zkM{XNAG=u-Mq`P$E)040(Lf7=Kzfb{SL~#=(X-~M&$Y9ZQNKXnx)Ykda(a{AcuA7~ z)T(TZbK}gv%;!;N=24PxohVsHok4{UU(0c8Kiyh@I^Pp1cLX*2Z+chDN$h%)QkBXa zz6viYBU>$@!`J)|Y+Xe%a`Pk;%@54KfxeXN1-;M~cHk4Uv=^_kFR?;D1>U?OV!X(ryY5N%YZHm7B~yDrnyFx0}H=xIT4hxbs+B7 zlbz8LT%#nd<1NU9K6uCI_6e2-F3h8b;2!;B8T*v`Yldgb1K4S&*DSuPV(akcQ-OZK zwKA6NhF@Y?>W*pWg|SSY5shGZulnQcT{~4rRkJ+UsKK5?Fi9F0kA2YI5 z!;wa;Ud4>JE2Igj!$f{~ch^#yq+(ce@EtsNKq+|BneWHn!bHS(QRDcrs@P%oR?$c3e}gi@jRrmtc1uXfFr zzdJz_*rSZw4E82C?kWU|avf-Ki;uYgD?0CfRRgmq#wu|n%^QXK=3_sY%c#=sPDxQ9 z7nxwa50*cCl|oAw>;nO`5^2!pMml&=_w!TT}w14c{|w4ljUHbwnnZo^6a~I zO3K1b=R=W#u^`Lw^Lr@aF;-T7<(t#=S#c@C?>t~1jClbd3(x(5q}E@|x^YgwGzV({ zI!bh6Br~uEtUs!M=zY_zR=I%6Jbz;2!~sMtO5fkqF?fqxJ47-G?t z=T1^wv3!~9kN~;P6~lHg=?JMM!bxyY*s{S}%h*GmTj9wQyr%6Nr?2-j5qB2?$68>g z^z#7=ykSD~EALI2EwkOic=VUYb_Qg+fzWedtX!UC9IJr|2P30W+4y{+^VqPPsgd@% zew?VjY%#`ph_H}ejkNZIX`{WoSbIhOKny82{=ej5RtLHW9ZQPG2ZHZx@)wO+{Sb{=k;_# zV@N=y72Pe_m+COhB(-L$H@M>TZ=%lDx^J41Hoo$~Ok97xYudlrii(!Aw8l-WbpaO9 zb;r={6q@j^hWY3=nf})zY?k+-;exe;>nsgEt}&s8VIK(OvJoye6ZZ!4`TVlfQT+nZ z{u3G*mn&fFM)_#illxGOJMhHv?W9;tsf|%fOLPNV189ZQ$jzejnQ_Hejc(rrT8uGr zvQio~{qtV_V-o;CDMgow*=G~c>s|eLgQgg$$ApkzU1|TRSf$#B8Z>&~XLkL*wYlp* zjD%b(eK0r$k~5drFZo~nmrU^rCFkuI3(66?f zc_(n%bg%N5#Vn#z_3D;nYS!N7ZD)tUArXZ)*G-))W*MxHaNWKCEMQa(ELKFx{^nZW zSlhu&^4uqbK{eO(o0$TzWAAI2FVGe4_NOlD(B++kYlpjBwT6fGOCcS z@P3q@a=lP)#cwR(6?5K3|MWd(QOaN+Fm;UfJMUIL=HR{;t(~G&ev0Z5MSl|_{ngp- z-LH!gr|Eq-j5-qm$7+np^f!2$Y3IW@f+c7W`$ET(Rgr8q-#(pF9RPPeq`TagWyZ=m>(`98DdC8?`}S);egWF(=#9B23_I}N4pykX zh12+L`jk#zDA8BDyXx7bbU`yrGXBBB7?)seD><)I6Yeqv!vg$>Tc0x=-iYIQ+zc&0~($op>n| z)Mdlv=zR&|?@fFsYdA8~2=%1(4DB??NM>VY~G1j#EY;eUNOE zoavpw`vWf^u37~Q5e5?>U_e{&ZfP)K+ZxR4TnjBk{DNkT;)NL0kHV|)3s0h*E5j%a zh^7EXC6pxrj>>XU>m^e_$zQd=fI6*+AfzMgc|8-jtFN@?_V`>^;nLfYPj?uxau)iA zt}Ri3z@$gryR5x{o8k{UN^1S9cCPDb!!3~md}>T-QV44!ByoZ7szp&x`&#>aOCCfs zCvx*kh1h{|laNJ8>D%wRN9?nWoo!%yk3r0aGqBFdt)il`)==M+P`|=oWefI0uAJVP zSJWRhA$EQKBZXQ@CeBB(Xzm4SPo3YNM>>%OOxCHS$-c( zwR?%Gt?wZ00U57yGX$i@;+`v@>>(lIt+dZG@lCSNZD-y6E_l<6sopSP;&(@9WIeQm z*Pql5y`>7HuWJCRlB(_f6E@M|S0}tS%aR7WN1A+UXXhOQEauiOeSw)m*n*DPW+4Oj zfw4pElTtK%LUCRES$t30`D(Vt`B7$ZI*RBD9jmk?sf#PnPUeZSlz_n!2W8JenXMs$wwy0OZQ|y(b$8P?e6nt& z(iz@-@4d3rAqgM}8WkPXZ%ep<0+RGsn&>AYZkFK-Ha<&EdpdMFmc`TzvjA=V;1;fL zX(s@5WIrG^BDfTf0h0C2be{iMy<66d-=k@dYNhwT%zLnQR#VqMv!kE>TSuVR8qw%Z z+a#6&1)IxvssYs}`rc$is`U^5y-Vo)laSI}kU!bS1**ZfUbWH!(cO-!A^8ZQ?)~tU<;ogW{+fDLA^|f zbT{X6@PnDba8G`0_+?1X#=k4J-E~V+)$I8_HSDE zP(jXDsjBcc!Jf$SZ1HRDvA-HvnKN(*UL8LdB`dG!M((|8bv{>vU6;MzbFPNmt(`br z>Y@j?#7$JchIDkE(L=FIHiR4{k(I$d$VoaiH$yU6dqA!pZG3=I# z0%?Z!LIn~mMnvE>2_%&*|4u&V${z7solDoCxp>-IgfRE~^{U3LBeA!_twl1If1QDx zo@KT}_kqb>ML*#(!U1fSEo~0JLjzj53s-f$J%K{?6#-Afzn3(mKTt{Ds31)k#PRrm z47uZ+v>- zyB~PXfysh;H4O6@XGn8dbUwIm!3QH6Sfw>p1NWz^pnge#?+-^3djSrE&qHy#KxqhD;W=Kf00Qw$QwC56;+z!j>a1K~9e^wgX+m zZ?J*mzF)a)9tjMRq?A#g(>?*!|GG{%}jm^YfNEEP~c)PX&XQ{5jt6wi&=X4>G1g6L)H6F zpJs(DX1*w)8&weAQ}!`I=@0xzwx#u}&m944-&BAL@@Dh?Q$Hcc=Bj9fc5`>gt_?5x zd6tIfVz8*iTxtwnIdJ(p_3{&d@_&TR8tNF_H-4r$Fpw#0d3SAfLhC!i2(FsAyAL)W z;Q9QCuY31yQwX{{xG(G11N*Oc=pKZ%t%^h`DH_{<{f+Cm$nbUMl$g`}Lzo+2LX_%> z6W0LfZ!8J?WfCRX&_Lk1@*@Hib6@cHn={ta8@em*Y3^jCYdlim@({B1Yb$SXurby1%`vd4GH6dKvk;_lSq`Tt!uTP2ofgysTO>A04i===ntf_RF8TiTHp?b z{%5q#HQiT~kR|9)wAR^i0M@2DJ{P4JT{9dHGJm#r-w!G+eM=oRc4UWOEuAnx-DBVMSgrm3;NbPmSNkjGqq}!K!}Ub= zs5S3b9&@tDCb##4aOT>$PtXr8ne^FMJnzMhN-1O1Esdj#v1?&I67n4=lD2RaF;)9W19fhV#`O$x@+1E zX@H#Uz?)rZ+lU|kaW`01kOz0AKRK-y1$oFp6lE>;%TnsB)48w<@*BVQI1*nxKI8kC zA@))K%D3)9%l5{gcBRKF-;*c5_{pDy3l6>#((+;2TweS>9Mq#UWl6Qw(42Gn4{0Zl zzBFA>S5ReO=axJQitAi83SLrga~)5e#lVo#fP+JJFK%rD^#)ZmK!UG}2i7NML#fq=Vkf-SsW+9L7H5bvp^y%i@^*y6Akv;0_0>gJW+Ng~Xgz9W36MTy%7n?s z^WIU}ZKpIlm|&)3q>G$tY;Pe13#XR9IvJQoMd#jxt?v9&Xg#nV4}o%3ixgw8a!lNqtTF>isd1U~GDTT&?9+aUq2N+fT$ z<^AtL^<$|@7F0>8`s<$ywDV4}-8(!>#ID%B+M*iFOG@yk1VLe%*^84waY z6ZoScSo}$bsyIzflF;BuS;ZBZ6PZNiWO<w1Qf(5Yb?rTZrnCWMG79$K1|z3rcpKfC?q_+Zs-**Ovs{E+jN)Ab zT~6TKt^}r6LUDY0lgDmoHLTyarQ+VF){-nh(~q~p{mOl8zu=x@Zhgi1veBh6kb~-0 z1u*wlk_&!mb6%%rv1mH+6S)N5kJ;1N9QO0_`oK zS@ufM7%Rk&Vn3bP++P8_#FPdJOFXb2c}D-^p=!4q-8p3?yv!-a3W^d3a$Q(kEm(B5 z7%Ywqxn{1R0>Vy)`{mRKfCCO{Y%VA}SvtN}D!Teg*JJ)5G=Zs@+F$ejI5rOrn<+Q4 z$IXb+8-tOTa-D;b46LKmhFJ=>xXlz?r$u&=+ng)s8xZaCw&r^Ecn)yT- zoAyf)Zcc54dwHci#TUA~y+H`$M7znIKa1!^9@vWLiTx+n<-x46xx?w_m+aJG1R>a= z*9$YR6jVA3QAXOhc_F{S5t6L}-k1MuyYx?!fmqS`jj>O2=D&V0 z?vvk$R)G`6%k>#oOJ>W<7DKvkcG^R`M1MK=m&@M5-DN_v#e1BA^>&B5d(8697Ze6{=298 zqzY(r;Gw_gh|t6R>RG}E9Y)L=3&HA5#el6`Ev19+@SNi58&M+NXD1;x-rc@GZ8UMn z2-qwe@RsgE=bB+RB;3)-CDiu9Vtl(C5y%AuaswM`;|~aGq*M#|N7g3aHIRqJEkS!r z;3c~X0(AuEm9L*`v&(F$yG9>#kfL5&2grmTZ+t);-*lJe^b*{J^p=c)qtBIr1FG$z zzb{4+m-2Cy8tX3zwDUt1O@>L^uY3=h-m~5^tgs5ccmI^%LEP}~2|)F8vYYu91_ucf zL?si>G*E*v*s>9lP$vwN_#Osk_z@EifkbyMrQED!edl)0bt=`f*8fE*kdxU-qV4p5ww|h}*XUQlJ6B{n{y+%(9P&OQ;~ABm%R% z6%N&?D_t$|a57eP<@G8-BG#sTrc|a}iR)Tb8Vt7H)7F{Evae^Kvef&yM#-&?DPg2- zt|DiKRS%{HYpOu{kq(@CHuG1ehpDRrTuDq#a?%Gd_G5M>zv7<3f9SfKTzrnty`4v{ z0S+yv)Okdn^TWYZlEU%uW3P6{l`n5#I`Hf8NDt>GPlf-$lnOHij47WGgVCEg((e@1 z*f!S7MWeawlq@@P%3KJ&S$jGom9kp$s7WlQZ~tn0rvd#@C>eFcR;;iu4QP3nuN=A% zdP+*bYq3!rs6j9f4hI z`q9*>HHz);icdH6m zGBiGRfFR%1ab=VPl+Uv;E^h9rZ6KfTZf8x%*&H+19kPJprS*|NkAiMuYolKVFVBPE z!b!d+*8A3V%_Jak?iJhHVM#sR;Xc#qz|M)0>o+w)=o!v^Q#Fe{G#Jx-&$HPaQ#Kjq zW<6JSuOw&W(y$&zUP2^7Nzn&fh6T?k{;%{yzs7WPm@Kc4SB^)6Gc?PKRl1R+4dnsU zvl=0q9f78-142+aat1SsLIrupaVPc$4F^m=vL#KwFSRqq30(Ve_nNybGl*DL{brPa z3bgChY3#=V&o*DpDYitqtWN#I=7+T z-*sghc(*ywocEh(6blGU#WlvFY96eLz}5;NKS+`tA|BiGz2|dnj6yu*pr&dq!8;-+Sqk}5yfUeOwo2PtTSkVOe{PbA|q zV>icCm;33`62FtEQA^k%jcsYaZYUY)7t%N#KY^Q?47cw=GzPQ)Pp8u!`X0!q+XQsp zclsd5fho(y63(3$TV6AC7VW1y3379xhc#jwFII}cF#M9Jh4%%R6PuK;?ukdgiUSvk z1C(B3uI_0cN6Azd@mi`}d{O*tqiXlS;Ni4$q=^%>anL))8D1Pr+>8N%DB!N*jLfSy$fRU2KNaQ2r54i zo7wiS%{zja&aAPcI^%owf0K&`f2W);t7t|#zJ`fC*LE2gK_%pmW9fP)M536m^8Y$u zr|q_s=a<`gaHAt9G6>;I5ygUSd;c+ka`fOJz#KfZtfUEiTKkmjs}s8fJT|Rt1O9nVrZ>UDqg~1D=9|89ON=Cg=0z{Ps|DM zi8P^`&5Vb<4kiV7_ZvF8T!I^D&^hR)d6zB~OkxwKq~r^9RIB{?hflx}t@ zi#i)8$g+H}Kpm15_ZJ!BAWISw)WE~eoJ-hk%HIp&NjpPXFwaQ#%N}cH6{ykR8+1wyI<5{K?y53SAUPENgJ_? zMMSFV2x`ePc+Ro};(>m_oSUDSDqq{0c=+=9@q_=_*bftDJ>S;X^CuU;LhT|Q1=4mQ zo(a@7nT}~|e`}G!)uoI;r3{;!NG!buY{LM8FuiCPLy+W&2RcS%Q`Ea9 zTH@y4(x9WRi>?m`RT*sg-Ac#GZ{cEg@7)Xm8@w%P5K#;mJ7{SVrj&IaFrPP|Gs?6z zW)GTSC_z+K@C3G>0|YOp$q}`)P5{%Mu>wOcnN~KOwRne@smTR|N?Tft+y+zM)_khS zX=gdgii1}Ld=Gx4FE}3z6ipGeByLaijRnXhO=4y|pB`UW41Tw-lWPK8QckG$Nb^#^ z?Bf;h!YKvIs<9kZmOSb`2H2Izk}@h6m;t|~U&^YIHXBFAnI$zAYTOfsIbLLqQIV9&{HSnN-TtZN` zZ~`kjas3l_qW{SgP)a0Qf)xYn6Ds#XBMT?~oL!T3f2Z+}6&d0L)A;UJnccNtIa44v zQsE?U`WRpp#S`D03VEW}yqe9!YGvg9R@v4Wl>UCXVW1cW{K@u<@5~1$&*0DM)1>dl zT{5;{H*G_wZ^K>lK)m@!c)~GgXfxi&q{kD!1*pw9;0|X%U6^;|35OZFfaHhZntf<|%;;!iWqJSlgWggH)h`mf7w(4{7A-R%skI0x^7`pu1k~ z19?Nir(uTnU^sA%4TdvyFdvkll0~f4c8q4T#Z5PT;(pj4alMJx72;&YFf}Hv66T zl%^eLLNhFqQgP=vg7<|Vi3&6+8%Yn7wYt~hOvRO0(ZB3EyI(0w0R$X_eO{&}zB%gf z?EhoyEuf-YyZ7M%MUNO9N>l`t4gnGA^Z-%<(hUkIASKexvFMbPl6uf?YQ=}_f`RziKwVO6nxPKOrDYYLXj|?p16`aeo&?^ zr8=duHTLna`eP~lyGGc-mMug#&hXS_DX`tOm{ut63fvT6&&%ggZ&})as{equYZq{h zVH2Fl@hB^WEVgBl^uJ&;T^_kYY;PW5v=NYpL;Px1my$mb}vfvbcQ0&_9O@WH%o+zfBz;>;V zJ*@3|l&@Y@oxrbxnFc7L2$B5`8gmkQCwfog=KwaqZ{5BH$c@4N#*BQ_B^u_8Fq)HQ zawY{zV&E9CRPNsd5~vnuK^&2uSpqPaYw!M|Nd~6twm#*w^W-IE0A0(7%xppUe$zm!`^cfN?zQ3* zN_AZ`UF^ep3je$NDMsfS5S~-SwtI)tlIkwn|A0qT?jFc0>nk73U9Ztmz{{`~ebZ55 zw((QU1dXQQ6fo=Iiwr`3R$XDY`q{!VzprF}Hyyq`_r{l`i7&KPGHX0O6&V zr_Bc+SDh!bKPX6@59hLbqVIlGVoYd&@d8n9AzeX|^}o=0fS!XAt;$U<8{c$D-b_Ha0YVAYcKq|m1!O+pCK^`HR%!v@fwhC^#8(xBZ{mU9F!6e!4Oykh;cG7# zX<3S!rO$tnKkqMTJ(n8x)EAH&a3PkKAx)+U;?P2fn2{~h%p>Mbk0=9Hxd;|>^f7$M z2@#AgRU2oy0vBfar^#glOv6|PP?$&o!)``lyn`KJ$^fszM}!m5a2Z+^`~m-#3^?|d zV|8K=x|h>S?opBY3`@rL;1t@sKcQ!FPF8xDd$X+StOo@(%gN=_A05F-WZ<(+3xITm zD04$OHDC0sefV)$t?9!~Yjm>E$CQm@|G0Z~b9X*vemjCkTd}`29RlB z>cz>>U}t>)>HqBOP}dWKCByqRmM0w@A?(V0;#?Ua)EWav7B)I0@HjzQV8SpA5KCxl zf;b`_t&Y$&cMsNw7+qcM>*|2b2wcG1LN3m=hd);gOmL=|%YUYy)S)7%%p_h6 zz?FNiJOD5OQ9~+$C3(rA>8XY#tTKP6VL0<2M%eTo+Rk{4nG{C=DlG{vRQ-|SI7 z_(J=Rj_$_m$A90p4K4J&lAL_y@5ax5cP@pV$3IW<6W{!wC`H7iI$Z1_af$tr#^mbW zo*>gw=<2cXo}$?sB9~PUF|gY9ae)4MRhL=IO4cgfSbw?m@wFW0EZB*TzJ$N|vdxsi zFv;-AX1eq4LbaCibjhei`Axl>i0K#hfiwoHJ#JQ2u=rZMJPgj__+Y1U2FCR$=!}*2 zhP{q3vXU|n>w}q(SWNW1m8*4F<277;fAg|N(+7AwX)dJ@XG~$1ji2GEx$HN@@JRLH zrM)U)!iFE*ibEE5knk^i7CD>dX%Kp{5fMYZeI>D*f&KS0#_N{K#Y%+9DcVIo!kw)gd6PX zeS&AWQN3y1o^5W&z}>A3EG!gY9}R2@krH!W9Q^bd)?)V%A}`^^g7uE5ov;q$G1k)# zJ1+xL_Ki_%uj!BMPhee3Zhhx*12O-p`Y0au)xl)WiSu3vC)&ty%56Y{875&^)H?FT z7Ukm86iG8dhY+E5{?+Mx&`i#fk;3U}XJr>sYtw(7uz|`Y5XSM_%=j;b@9FvOQx^yK zt&dD|wc|y$!Jk!RiL0zEu`Ce>yO?Q}Kac7){530X8 zKQg_>g#*nN4p+0+9k!>&(@ThY>aKl$NQ)@Dnord`qe|Zzmt4NY9~6M-8tkPV~{VUXt7~Lq+s8N`sGTI@}Nd1 z>PXblU=U%$xzVx3DI@|@(aj0U0SX_%l~ZsO7#M+_&e<&uO&KIm+^n5HSJOh3bXs#m zC{Hk5QrwA+y{(Bzv|eeQKZmz)j}b;>>7`SflSv1_+quG8swzE>lF|9AGbE>25)X_y z=66I&++TyQe6eodSO0MI7+N#uUG#qZo2<~Lkm-j3-eJ}PJ#+CRW- z#!>8bZirAZ(4ti&4f_YKgQIdr)9@x^hMiFo)93+7eYNF;$qDebyI3;tTy@l4%=He5 z+~^IQHoZhhQ6d%h-c$*Hj^35Eq8jC&ThvAxDzUGwFe8*Tr%6VI>xuTTMH67jum9T# z?cqM^jl)2>KwrCSlXv&y?h7wSiYrm-=qCaeAtwe}~eP$ihQ$n@}65+VYV++iVR{ZH&<^ z*VL%};Dg@44|_l6^}$5x9bfFmcvDY40i}ImJB4&xJ|+3>>1?n*AhSl5$u% zgWAEZNVFaQ*^JyxaZ-6AX~S(ZItC=*zI|Y4POgog<@ZYs4A!Pti4scqN3=xDbK^OO z6iWnzo?lk@I5;mx0FG)Hg=SjB`zf=jk}?sh=KY+?QrmP>WYb{5h~(jzI=M^Qh1^Abh=`R$e5VK{sOqt;MWeorrM^T74> zi$`nIdi@b9B(AAL!Io#=TbAL+uWULKS~4I093Z)E78nso)H|v>#~93P<{|1;-sALj zZyW#hcXZ*|r_v<C1$mg)LWDHD`S`G?-%(~Wjh(BIf*fH$9NeA4+#_MHRiDShyJx3RPV8x zSll{t*QL;Ka^N%A{!it?jIgAlrE)2ml5D+APF3$u%Q z%+nhVe?#l4GJB~Zoq;PY2c`I*B2xLYU!gux z0-wf6m0(>>)W$xKrOXj0BT9Z}Y9KAeDe(-1f$hGLW#TPxTHiFD?dqnvEs^7j*nOOQ za4l9iCwb4N&_b5wk_h|CIfiyQ`IMa6hx>8-c`|;4#{bXp1joENyZjEP+|VE!3`MbV>2kvw6UM;xB!aoaZep|Yd2jozT$WUCecy9|HKvGCCvvzFEw`96&RIns*E|F(lFoql}{4G~7F5 z#=Y$=2ko3oP2FJph$v=*eJQYth*OmNNLQ-SQ8OY$6NsnUbPHoCj}Etb(b^2*{o8yG z9jUpQSv%zTY7^T`W&=?QAON|qgZ{-Q@&CxBP#<@Y)C7zY%N8`Lw4{TJ`NJ}Y`7(6& z2evuBZuS6G6jk(_2h|d8ywS@?os;rlpN-nfC7@rD4W6`W;od#{FTU5X(tPE0^>3{Y zjcOxYM*OT!`5haf4rYYSfra5qO&NoGvZS`GD-G(VN+f#Sn}qJnY9s&e@|tbP@D_8? zrlkBNW-oF{y`X;mD>_yxS4Hk0CkuIgyvme&b#JY>7-44_ez5<2>d<>qN;+CrIjUa# zI6g-+2cQ=WhQn1zs&)JPwzI)S{|Ar%&)NLG@&KoV#Hqutm(zl9fBE`M8{K7{>5;Lp z;UxLp+Wq&W3mvNNF-@T$(-4ORR=oK?bIjBp!#|3KPdnIuYi>JQ+_(SUldnU1y`rO| z&tl|SK8L(j;hx+Xk-%GxU;hkP`XSLL8yEXTGPc;a;W}`0NGWJ4EFQV#S-p~HxjLCG zVvbiyUl(#52v+H+$>2;`{*S<=4hM7LWcLeHA?xwmnGzF#R7mY`p_K+~(?YPM3b6I^ zW$iwn%;aoCUeUmQz(L13oQ>!Go#nUHGyjF>S5r$n*=1dEjG9WgAC0?vQso{E(GQE$ zv5fr)Qe{io%rtVBm+d>1Ra=^D;PzUx z4va9A$RU|Gn~G<0(^7Cu{3_WDNd>MVw#*0k?*=4b5&AU7KCmZyQL3mXI(K#_>X23G z75rt+3@n&=OnqM>Oix*ZgwN9mK4MjKH+%j6=jjyr=9U4PQ#m2fuS>@eqmHgY#@__? zlR(2XS-h-6E4t4vY8Pkp($Cb>CS7V+kaA9LdLPDPJ550p1dN~bnYstRZ>9fyrWEc# zz|Q@sj@pmmJ&io*jDJyVsbDvC42Z?_Tv-p`A@)DrtzPJzmoXf^tTYPze;N*g5Sxv3J!E#fDFv?53Y^T{4Ht=At*e+H+4RkVeK4vQjR>4TSH$+*i7cYP@<%#X;g z9oCGvUhzy<7a-FSZ?UV_09*R=LUh28-}Lfy$#IJUwN@`(E$oEDCMKeSDu&a!zs2v) zzp1KRL~)XTmDZNEMKBHimc)fK|BY}NY%D|WXO+p)l%L3Zp+C{2J``U)_bGGfqPYnw z`Lw^5aB1*bZ4ClI|lP2(y6xpgV) z`sUEmeETHb!c}9X3c02_#I2_@#m=5>s}U;7z8|CZ-=ap$cazD&Ew!y)Xg^w$Kht1$ z{u_{XmIy!~Tw12qf+O3_e;cj|dMdEVnF3 z-kbZV-pVVHqas)8!b1QAf$i@p|Iz-EO?yOem4Q=`seEDkeo8s5Cu*T_E?&Zk*(|A< zjdE^Z+a`_FzqZWD~8C z|Dgotp=aApT|C+Ioe?gIY#(P~pf%i}I#hy9xt;XzV}7);WQ^91;WNS3eyi>H`)6*} zxhXq&4QURHqDFKewVw6_AMB_uq4f%f*=f@CLVvwtOi`+8K4=yy`ewKnx?T1ijr2K} z@BQ(aSD4pUV6ff5^73-$mGo#MPzadIW~w$u$jSPib_u;kp#fE{W??Xo#gL@Axw)FA zX6x3kM&tF7VlMN(v=LB29jXi)C~-}I9+bUtJvs}dW;-sh4) zam0-QOf8@86|1{mS|)H(4vzX!eng5?l(E*VL&16M>;IC|y-J|N&P@DP{4(sy-=mhi zFS`?|`T^BMn%adv(RtR-%*<@rUct@H?JFn|ygHaW2kJV9FeSOaX&ip_>JYR8VNShl$iB7;UCk$K5XlmW zv&4VRNQxvn4rEjL+&S(k=@1C~V4K1Y#IGA}L6o20&|)|7MhtklUE_@nP`aNkq$$B^ z>L#d>t5mzwC6v7}IWlqs`r8Dk`3fyk<$6iSY=08kJ|ZeAV;@`h9`@AICLbhmo;rF? zU{1DE>bonHCb=(YMpEpFc%uy65pook9v*&+C^423>+OIi2^qB>%nTGuc@RB&2B6je zFCnW}kKAhedp@h&+U}hS1M8%1o*^SEi0W=t^7}H_Mx$r@t5~SjQ6e`W6w7FbU7!Y~ zTs@ch;D-t)^GsrXk!+fdYsaF;>!r3^-!8U>c%95yd*HALnbl67PGqEE7mJzyOH*L~ zb2%J8M|O0d>bsvdP11f^iN&Yr!Q6%~l_P^bIR^OmorrE1TRNz=`^luR1I3Aio2!0ppOw10;&~R)#!B32v@)ShE_WSNuGkbzw++CE*tu$%SX3V)bHgd2IKBg zoWtNb&X(1d^0)gjc8A5lhY_A~&g25lzNK?rb?tBK?{d(kBJCsr_f~!Y|JaTe8v2TH zxH9#Qb!>XxeS9@1(AbeiHO<~WgFQ~(9u&Xn78%EkOtv;oF z`-30{3$pjL)olg`Bc}mq(?6@Ym}@9coAm0{tGzuve+LBxfi4Eu%gV}>RaHr$|LE#c z(n$xeuVh_$ot~Z!>Il0vS=Ve_|HP=^ublc=3e>iK$j8^(9?515%1tAiNR^u25?rpX zU8;beZe(R=`*m>CP&&XD7GP#BVMDfC5cvgtH*H z#kQR#v*{93{NER;?4J${3|KmJZZC8|tq%On`!kxsdQ`Zc4#UxVSa}7Osl+A)IQYth~JC z`-jVOpxMFryag$fVj!p}dq0?e))(|VATLQ^Ge;xOip4o(<0I%y zQP;Tj*jz_49+6+etsEr zn3#iJY23Po{pHV?;xF+vwz3ta?|KRp@eSauQTwha(ZbqoxmxfjE~~MxH$+_R-DgRY ze3d*_Rb3S9(lO&NqV;FDJ2*o?b!ibfd3n`oOkQc1|HqFX`9Upyp*riauja_ILJ#(j zS8j&8;+zecocgM|n+ypn!PP08D{8zJ0M0hQHMo*M2ai~;fbJa$yCS^ zQ6&xsm1(xDT!MhklL^^aQqjC%D1%b8} ztXoWU+gypdhuzX5p0(|J0L(I()x{K>x`Ss{ zZG-nhgg0J(Ss71;LfrLFOiIBa9_z+jc8fnbB0Y!4b;2r2+v;Wa$NLfy2Bm0=y}dnK zsNqPL5aM=bf}_sQM3I^-xX<6jT#oA_pltv*cpacCLoB~HT4G;_`Qs4?Yx!(EWTigX z{)O~=$4GXUSR8$A(p(J~Td_FEev)P7{7ebSnO*xVc{Q;&w5P+QbhL7BNOx|08tn)S zDU(kmo36U9r<1&VKwYKLmyf=TyCLLgIWRQz*ui1%Bh8B!FM00yA8@ty=d3)G`-^mnLiV6I@onj zj>gI?jFGd=kmX_h1gBi$Udd>|ASsMN|9m7RckXG-H}wVE$ySt~(&Pg+UOV?Xbp$ia zDR)2Egh+wotl%2#0_f0kAzo;+k`9tST9vPVxn(RD3~R4A&6OZVij9pCb*NwqFae^<0hSzI1uxwr~c>o^(bZF3lY-C53>7EnGUf7{}%6^y~&o zFRN1vr%4A*XjZn1v8F9hs}vv{pTu7+U-YF59$DontlR&527QTG>)Vy!Z~2b-(=y=6 zw0;o^@?Qf14?XuKyWT{FA$;^Ny27U7njk-`k80#BREQ{0!Y=zPXm|f93yk~O&(Az; z^#{$IExm^ z!7!z|T5#~>iY3rkzW)CHsE9#65NXD7A(mOzNI)qywG}P$*o`m<;drx2 zT?^gWWeb`hFVW|6?%N)uDQS|wzQ&B5As?{nAF@2B2KxH?daf(!w&PY6RxuGZWwVH* z;R{66x1j^!4s~Hl4HjhmNJKML_Y0E)HU`=&Xu6jN5*t}6O zO-*z7L)ta(q(&h23FH2x6V#@sp19PsJ6O}ug9p+tkj&&e5ganCKo6HAyD=wAVy)(x z3D;>38ZH|B`u;)Wu;UAjxuxa$?wY!~`eXzSpye%dejyR>*^gl`;LFOX1?9;7jkOe{ zrYzv7V*)6ilo|6esEi5lyfkK0MX++>{!;;lWW(d_X!vc5p}f(jCzF*|D2XWvOCf^< zx|hY4qa_ERzsfCWU)0p*z3z`CID*3RmGj~9M!@7lf-}|(t_O{T&$UUDS>&RB1CiLt z>j}@}4UwBko+d7alGt` zzX|%1C<60oSM8_TIA5d5(96?vC(iT19bv*nt|{>U1;>dyeiBHi*-_Ip|6yoSFlK3bODbfel$EShQ;qANF%s)Ce1P zEg~Z$p>|5Gkm1=U&lv>PH!*mCZ5_1P!LBdD3v(PJ=V+cMa#EfL5@6*>H;?w^1+0D{=eW<&%tv*z85;3lm8xd<+5Jf~y8 z>oEHM{*nk)>aZY?g;<{)cwGDTWJg6bn1fa>r_Bk)LIG&2n|!~EnqZ#;JACzO?S~rx zLu8*!dYbuzd&dUA`@KvAB@=oJSsPGG*w7r-v5>+J^zDD@7Lpr03)2NR`K9DR{splV=19c|!h&c}ccJ-}OmhvF${GXTP9?InGX^)p>AkvkimbX+syHM>6Mw8uO)9y+ZqD{1MuR;&-uZY zLndrs%hxvfVD>)l2tFrx-*vc0oe1)H<3S!hhd?r|oPy!`qby4fitgG$V$7kt?rd4v z0x`v=?#)j=S8MTK6{9g3>2wrJB7N~@ozhMm0i;ZkOQ(sjT?4e}RqxFi&vQK$37~^j zu`_a3!2on2nluKD!9+s;^4`=K>c@jE$3c2MKgz3O+Vl8ekq8u%3tW?u3@1{ek!hlrHN zsbJmUhNv6rM0o$#{;RxF(72^y&(!$REYUv_>TTyYp2 z9E93XH8=T@*05*`J`SO#0wTbzciI$a!QQ@-mAPJdIXR=PnQu~FUapzI_xbUX?{xRM ztgI|BQ1``YVMlZ*N?7%~Kd1{nf*^A&?=GsM8yT zI{KIu47RIF`bpmjCQiMx%Gn%%{o1c`b1w`aL>k0r5&gJx@1ZN}m)VGS#a{6**s>aL zTo8A+FgLaP);GmMHcn2gG`uD-A8IWZm3Wz>@(xGk%-a-rH?`Y3F*u>q^Lt}sWBjXG zss3p6t|9~w9vvMi7@$1x#6SO^n>F0&MQb$pnFHSKm@3_(EM3Q07znHDom$hG9dZeg z1W~x*Bi+TaX8)32WG6tEfbp0fUx1R`!Psmjls=?goKJX>REP3U-5=vX?ERnX<)U>C zMooa%a2-hYgNY?k3gCO0W)4S2L^N4dOkQV7bT;B+z#2&21s0&Hk3A@|Y#tU4;8x{# ztaE*HnE-mUNz}bAjX6$5W;P?zB3?by(i(o+bF@l`qQ~wiq_prxQUW-tnXRi9qVf$; zNtnYV+oP3CCkY%FDN~RQ&W6?~;j)jY$4J`2R{b2|SZaNhNd0cWXmQRLo^-WSLkW4e zM{6h$#!SZzD{csyWfi2yF>HkpdH(&qwHxPAv_(M`Bh>IS-@s`hQnLm4i33;tu+zO$wOAfpx!^ZE zx8cynsICD*9H%3;ZkCkNn}UMqA`t%(q1Jy&VJK!>L8iKAxJJkf^V+M_SABvN@vvPG z4-O3v4i1hHuzM+dIRA;uv@2e#=-H!MWD8}n>)xt0`)NURn@LKY2mqZSs4tys6NNcd? zR-*-*irjz~PdQ`UKkzAtS#U8kSU~`1pY%in?%uzNuB+LVD;aUK^~ak507eIRB9k2a zX%+;FaMW&n2WtR&pEUtAw(h@2_xIdNIvnLLws%l9SOezMQ4IjkE>ERe>j&V!rhuSx zN~VqLOSc7C9>hKYb|3bQJpdtR-W+tivu$IDZUUw~ozc#R=|sUmRZ&J7G0b82+-1Xq z?;3EgE@0@#@LK8crQ;OiJbKTGb5S21>O3|;g!EWQi9qvR?PB_8v7ev{}eF6K7|;b zu4>wL2`owS#%=6Yb9eF6S=S%FoW`-8c6IVMMh{LW_%4q%o`04Mc)^}pz^}gPu*dF# zKmv!~-|wg}jbNrN^&&Y7jyu>h9Ivl|@l-B@J@^rc_TR^?IF7hh1kc z(j#Zy5w)~}Hlt=17HhlJq>B8Y5N(IyW9`^)NbL7_4FCZ!sNd!Y{uXr;FxLLL9PB=1dV@GR9DhZ52%|g@P??!$;l@paNu6}@ye&d){8dIw2^fg z!8B3rqOiKjrD-t%&*SvQS-|^SDnmz5Ci=Q9-BS=y$Aon*rf~f_Kl3P(umSt#4Tk(Y z-W<*+$X2M=<&-6okCxY^E+vH)*jdpdkYxej6o1G^OMdh&rM!G7!oc+dXqVT*k{M5; zprDXo-~<5NX7E7@tfO`IR&EXs(kE;EJ9Kg1?NpqmUOo-Ht)_kO80OJrJ$}`1yvxJz zw)-AkvAcp@N*UFtp5Fc%g%M!H8D&~spkR4Ey$iN*HrGis+F3vU%v#&hRJ@vex&E-z z#`<6>C=*@a1@%14&P=?OndIpT^`C^SuML4OY>6KGqgdn>G#>@8H}mhsmQ&O;!VRl# zy$ukVJ7X#=0FHFunV;+*{VO@-CQsG_TPVE+M6l2s-w2R%+(gX(GcPKk#(@6&%|Yby5zAv z7}-0P7zAi^WTblvO7%yM5S^{d%|qcs$oB73I{+)6h1@O1!hBB5%LlO#nt?@4S64yG z+C_a7fInNgT5prGX%?*SR)fPMLhZWz(><=+rR%>trvZ#cC9nAl9!V`Dv)BMG;Yhuc)Nci?F`gDiBz>5@h7-^y*6_f z_~RKE1FzG)cKEJqM-+QNYKW*{)IIG!@U-|`j6;C>jJE-D91I&7Eae4#qIMlQM^f`#y!J&_eL>z&0oTkifllaGg9r&KV!=t`q}U-|6frGSY4wn6hI_v3o7#{78~yIRCR*-x~(1 ziKwGigMxtaVEm-^p4PgAe=fQH49x+gIqc6V=!9%3B_Yx1=2`D~gaDA`w1i)>1r)0V zaRj|ufIKA_R6vnGfNGHdXl^yb1pCF%#B$4*YZO+GUCbHlZTqZQGVzvcSli`h$3hf3 z-A)mU^*5RHFyNl=0ix<)#ls464R30`ys>vI*sptE1&}*iPA;EUWqIQ@A$yy@WuAfS zV>|1|)DkaX2Q1ftEM??YBT*}81>C35hW*kV{S6oU{C2qqwu9Mj&3HnAGGc#=(>M-9 za3S|dGbLTjJ&81(9h$2TMnX(mIFmf-7EC-O?A)XutzkTeds!H8y6xy)N#Zpiw0gcs z@WtZaCguXjH?_<;eLK*x7*cf=u9K|*U5C_ubb&%6ko6Qy3HB-#wYUh)ISEmMnQ4#1 ztr3@>GrPd`I0qt}Z*Etu@!GBvQFpk7bRZHajumfE*IX$Qvxpnt=7fb%>5yYi{$&Bo zW$ZkTK=1Goe_+<}Mseuhiv8)9^m+n-B@%wm)(k+uaSnZ_xgfsl0&Q+}prfuPj(d4W z-KxrD*oM1O<&feT8(@&}2Pc*&2ygfK*A7*DHJv+>Ht>T|5Zc>ZD;CRz6Xie=w~LxB zUjfxk!lGUEtX1yr3kG0Oxz=Q>W?Jv>fk19<9M0N@6%_+5!Pb5|4Bx(a`CBAGzSrtt z1znuNLBvPV0)~)F4M|5emylah2q=uj`47%sOy;z!zN!la(rotkK)}b|js!bF7;n^9 zm|iyQN)JQo1#%6T!QjaC01e)>hzuJuYb6cXlr3nluryF-WLDM&$9|(BBi_1EBmPZ0 zOIVu;?};!-2LRv>XdaJxhI7?mw6tR+*P`?8v9T-u?d|#UyD#8^IA?z0`9SX>ZKqq3 zsiIcJgj?Q(r?8LtH^e;MZ@>9*H>{%$)lbK!k>?9VOhh6Gv5)iiod>f82I+Emqti|G zEo#6=Rgvj)`brNF2=&b~ex+sXr}N8i132rQOA9dov|L}L$4#$R*Nykn@{t^fN^^`_ zn>m2^f)?P1y?TgO$*sO{7EyrdF4|L8&kU$41p#&7)!5A)`vjuY%moY0u4E={elsa@ zfr6C4o?Y|&8N-#D>4i(aUN#-GYbz*JE5~0hu@Ea)x{`CR!|ikxPZOpnh&LjFvtC9X zfFN5+5(wZaD=Q-thXED^^_VVxHJC#!hr{ac7ctx}zd@cJEQ4453PfiPdYMoGRu?oE z%RC*7b=&=1E7Ay_sjgrb&AW?V)|=xq0C3zf$I~HznH&<|0iN z>0d+E>2Upi87jit4j{$=LBA$?FawS}g)9GE+&O6IOO$u4GY^2ZUCm|<0f}uSz$s9y z-9I-ha-C14{Ql4tZ}SHBjW$M@rVBG}o;{bCE`|1ha&u*)BwGND{`(@e^D{l$W^!ds z&EZBC+&f?R_`dNv$j2bOUz)iS9wMK`$-X2aPO?( zBW&bB=6I-2Zb3CG1j0i>ZxAO105L7Cj;=1Y8}E~t`**v9cYam^zsG2$FI^-a$DmKf zyi(GGX_Vvt817l!emleoU_>#GH_Er|Hd48cgVb5lS4BRL14PjgSKtIzo|l(-PTX)0 z8R8`j;p#~MV4j17@l*UR(5Abuj|2`v4YL&R11U+#Kq?_#&~KWi(T6Amz@O4kyl3ad zgV@T2C|!Rvj)DObVF6@@@8_R+*DeU*IUBRB>du~wCj}j2R<>>^$8{x&X7 z)gkqD;ep?f8bD3wt(+B}lX_2E9e!SP$vy#k;tot!@{!s>#YIE^T(MfGS8n@hi)l(} zf1M%q-d)fGH$mX162P`|ZA?jlPZ&$T>>h8@Zn+{j&g0?%p%auArO1=GSgo;8zo=l} zec@n3;K*)QbcW`rq1-_7lC3%~1p`AH^g=HU8dYyI&-VjbvH0#Apg$bg~w75#x6WG^nJ6p zx8+;!zwjSPvRS8U=*Va0t5#I2TO|wym!+z%4Jc-Ygba-->W&L87j_4x1}p044si?> z>r`kE@SP_o!;=z!@rfZcavpuk^@;3$Xgq@ey-Quen%=_16511iN?0p7oa;Jv-*oxH zL0b|RrIlw%5L$fG_`_2cFI$ib8a^tadt>7xJ9Z0!OF_ zp2_q>=qvxuPwv#5oL4@6@EW#B$Cr02xC2^n@`@_I{0moCrLAHu+EZO|pN&NY9L<3N zVmB!%?ZT0#lcA*|)00~L>6aU#Cu{DcZrgw*!+x{Kt$ylO-)j&mY4u}Dyb;G|6HG6w z!+2b-zGWp^$ZdcdezFZktrt-Wu^RnAjO->G>pfo!Q6Yv*w}SlkJmDH9t*S4A)WDEz zS#v{e3!Mot9wn0G1PG(%2kq&Bc(L`FMRY9~rt4t`^`02fsbJr9MJL2>YUjbOghpzs zer(YUp^Pg%)v(TM8#PGS=(Z{7c;x{-68dSdCR-4K*%LsaSrE6D0v40}mx{7ko6-a^ zHWn5?QI8`@7niDka5EDZ>h!Sic=(XfDk#oF>&Ml5s@re7qb&&;Pkb>R3xuK4e;k_VzehWX3I950yE?Ka?P%JNuE++N|`%4YHUZ zj~|Lq?SzwJAC+9Ao%EtOhlimKT$DH2Un}oh3onH_AC#fyOhf8#226FVcTie8yPH3` zH6$h~@WL#Z)G_|*U@Rta%}?Knd~jsHSYh_9}{s?gPMfy4h58CsvpqCj^$KM1LU9&k&QR zbEO#~;x{if7=o&T&>{v7!}m8Aoh>GZZZocG*%Wr)Tl?uJF>B`&{L>Z}SxT-^hJEA( z-VsWoHJsiLltH1;d;Q3LHCD^FPR3muXw`TN0RFqwDZL_Ta}s$ z4GqX;!{?cmtr=uVl-La@lM+vtvI=aTxSdW@ml^&PHP-2f4#BiG=bwGE2Kl(Mm=F)txcq~hurks zhdXSCynY5nQs&r&GFKEF&&Anxb#^ziPlY>@h(0 z`A9Xzr-Tt%FKRUENq*#VW(4$zobHA-+qMMR8MS?$P{4?+%=|(kl9H%D5M;39+kZ{n zpB7>|7B02-a6c@kNG-p6%2GqM;72|_3rCAGpw}Dn=_>^nMNL{k&;I0QPtJ6N7LkAKH_I8o;&*dzOa`Dd<(b333| z*h>XpwVa*IN+#K+QyYpVRRqO6Sos&fmDusZ;w1umnpG-g>>C1TIOCV%Y&|8-}% z@9|XoM$+JwP2KSRQ`{A) z58HofBT7Xt!s+_<78lhX(r3qS@OjE4-58NRdp$ETf@fxp(qc!w8X=roMalmSH@Fw1 zoli3ccUrG-atZE(g|d2n9&Z z%gbBv07d%fWoJQnJ?JVW?>rYS;vkL+v%)(#@OwuW*>0tM*?T=*CHvreSZe7Q9Sx~B z-@;aS>V>FgDH^Kinyc8G;!XVs+V&bJ1Qf%ilMSZ|=HumsP?e-iHSBX?lky6u<$=T3 z))V|YL`ClcdG#Z`)HKll(>3ZuFKGuH>G#6 z1N0aJL{-Qg0^zvGZo4ASEKCa(50ymsS)lv3aPT)2hszm zjivhwhH88!_4}Kg-M%i2tWpV7@SarTkI6W^< zniyatW!>4Vn%UyF{MjIrUJ`c)XI~}5u57453PbeZ*%hjz=!;>U3^PzD#=3eXLpbA1 z$dBc$Rirz37SD2uNAmzFVCq&^{mM=aJuTLx;N{7-TAnVZ;OQnC-ej`~r!;h{UtGH51zzQ-lUK!kQIX?rWP7{9&3vVB`g+gqlY?WSB`F8j zX<1@oV$B48md6PF#NIO8Gj%`!#QYX;IE5ib@_d-|=2LvdaC&MG&x43rdhW<(5Hqlu z7hu6YQhZoB!4a?W-CJ1CuM3XiP=YXWl^waVhPj=}>2+TbeaMY0^l~qqBwe&Q+R;Vk zy5v5nca+j@oxo}L9y@ZZp##jOE}vikG+80v(VX0|27w8gbQN}n84#PV1mXUOE(%X-}m^$g7{4nebdgWk+E=JElD6YdQj zVDwg0h|-`=Cjm0^G)be|#kH+E%gU^MRgiq4u0)3jJ3NfkR2E!f1WdmzE;qL?u~ut6HyE$_tBw1KcTA0?$4|qmY}EqP$eP9M z`y^3v42t{HY!HgCwS$ef#s4Z#??^-w_~Xkmr^4@QSJuJFz&>R@3LMM3lSWpe{*{NU zRJijF;?bGY{%l?~_ct7xKh*zCp3KI^!Ro79zZC`&ZvtkgC^Q}0d8W1W$xSEtnU;B_U%8$) zal;~K^?`xmx-64;1aFOz6E`^WNMZP6ph5prHML zeA#WPvn#C&9f7M+U9CzP!%h(F-@|2a!tDJapKwsfz+V+JU3wGI%NE%r zn;Q2fhS0kpt1{~jBN2jz$bIhzGsk+Zm{+WTtqd@d6>F%m@7`ngC$*5OpxRT{eRDc7 z=psdJG?My5wy$c-!)DPJ0#`1GM?3cXsGA+@&vCK&!Vb`0@9IZO#N zHE>@k8!4zyUR#RXXAR_f*FNW4>?Uoi{OF#mja_Y3H7odBb2x)M zh(YnP%F%v|X5cDvl6=If#D}{&yIOxX)ko)GYB3LWW1^6Ls`Jrxm}_u&%6I;kC&|z+ zZ+8OM%V$4taNnn;rM7Su%E>7?Sv*4_?~%{r@-9J{#X76(@u+?}d-Vjasv^O(5$4_OPcLRfs?EJT}In|;yml`r@s%?VL5Pq2WFi^g~ zM_9cF$`2sJJmw17d=~HjZuql)=)X;c`v`1#>eT~g7zKISth^TwBZsIb=Gs{p8wPXZ zCG}nzf~ZPTAQV?`yxzOml|Tu?K{nfGB5k?lK`iW~r&+p{PmJrXD~fg9Tk>q+B2!gZ zhVF5fQ$6W10`4_o->(oxFIzvit_(saBoK-EwrvwJ5(JQzgmCA*CrF(Ss0qQ z(0Zx}+;xP(_T32^>_Ng9$^fg`6!{z3e@`%KPX=8#LoJ!R6#iz+iNpkemV7I2#mG9|0ul z*(EWI%fp8ccPo={2RD>vaBoEc#_^{}OtKG{n>5hA#7Hrz84x9E0wf{gxz>;nN}F0P zz_H(nFEFm#ZfC<%_MxN`%)Si<%Etjq(9wM+j8g~G^kE#U$@FI{*2BXL%11qgF1l-n8)f;* zZ#)_%?n(x>55$d18^4ZkTrL8|fPp_;W-;6n;<=m358{bNAmoqiFhrMhC=wV{zJBh0 zx@HJrjICe=4i7-)8JTSOdig;dz3lGVFei~Yb~(Hgle1a;K3_NkMqn@~6?$?E%$yhs zmD0a=WKhbO&OR#R$8+ zc@q180q}RLwcwr}xy{py$JS^Rl+psCeZCN3&Jc-vxHZQl1UzM*AyzP$h@Nu&IdSP* zfF22Gu~fDY=nSO~0QUEo4`FdWxk+wL&g^ClA{Y>tgg~0c+_w99}^1%h@iBf~6-87FdjNK3s@4-d`Vu4E@%NH10jGkN~8zbZ~GG1_%xk zq(FjclyX zM^O}|IV2@RW}QScWeTATAyddaY@JT2jFl*vqEg1p^H63olreKQk$Ilk|8+ml-dpeY z^ZWPtyq#Y5eujHk_gdGw*0p%Ypg5u!+*x+W3>%fDy8NnvDkG=i9VW6%e7-M&?9{QK z&0$k_S$&Cvc<$z>`_5jo9r@R@92D~37SWe-O%gX&OP(BR5kcf1oFE@)688w<<|r+H zi}^%Xfk9`mw9mtZIri4PHKlP$|i{-1&Z#wzmo-T*~We{;@6F zeR6USkf&(a0F<-dUNg55n-jR*nU6qfz3+(zmN0|zr%xBTAHX87d^qz|-@UOabfiDq zR3|I*lI-Ak_K@@|#2Etm|JdS0H80hl4DNrqe;`qVCO`}eHF(ug$#$q>+|qc>`eF=J z=a>WW1rk?_N6x1+KT%Z|X;E{EZ*5CfSI51myxG#YMu;9q&r96ERH5%}zfg zf0jC#VJ6_vQB*WEwv%S;NZU|;$$gjWi7F^bImE};X2zbb9v4X&zBb)9*DM}zkC&I1 z49QMQ$T>>@o8~9lc)d%V#KmkAKfK#bPFeHeA)JoZFKEU$bEi)5hS=Gr5~;1b7Meo0;OLs=D_`ELPx_8LeadF$c)N#jlDmrTIrZ(N8E7}pdO^XPDX!xmmr*QAcfZ1%=#Hg;>MH|=*%xE?tfv%WpdD5ziqm>`tHm-@pCr27~=|2g@%~g!^<&;i zEv*_gcK3Wpn(r($wO2Mn)IDX(%;UP@`@P`|W9-G@D&C zj;E?%0lPkR<$fPN0MLHXf;P;U(KFh;eV;Txm|RB_iUcIGh5r1>Lc;sUD3S?+LpJ+! zB*F>r3NDNCL&Tq&lsXHO$4M4}JF0W0PBxoR%SzC_=N!$5&v5ZcJI+o~4<7nztl3I? zmaw*VbsbKTN&3JHrDmjpZ3cLDn~T#-`3+hu&=*1<1=|+o zXAZbgD!W0S)6Bh)Jq8C2LIB7h((JKcKtM_U-PIGE#F%uR3em_G z9+0FBFvjHq1md?)*oLV1U8rCY6_fe%>+HnqGU3D(Hf^ejlLRU;E0p4UBAX5<8ZL<8 zGCz5u+xL`iz8eE4ZAZse*v``vvlylidVAkML}QzR)SNy}aDz%1A)bwrlQpx^dGpcep!8%vejs|0c$t0n7$Qqz!_pOIoU#VB%y+< zG6h!wR0XzX&9V_AR)5#tgT@6wck5#ti0V($Aayt01t5kx>XKlb2LFLUZiToG)gU5@ z-`6WuZ5eN}vcfH#4l;<0Bt++=cJx+?ba+DWQwV|+dXVVCYdujtANbO@v*M@_;LZ(R z7srbGqhM688O+=6h93^e_ z3~q!S1D*kS0=;gxL=K{42uw=|7|Slw+H_QSh@4!@*&psDsQM6=m|4nXi}UjE<6QA= zwk-?IDyeO(|Gx6!2T%D(&g3_?W4f|C`T&1E=;HRMFzv2#D(n)!+j)p}X;G)wt9N3lu0WdCYF#piLuPcK5@z`qX zAS%LuIr^jB<7{;6)?-9V&xPv$Vpu-X%Ad_rqsc8MW~*+WJb7~cPKgr_Htg8i)6;WV zL!)^d%2OUgPMcF3oJkL;_eJnRbfb~kKetVKehf*Qn3{Tm&nJ!QOHcIpDRrSrJ3zLR z$DR?Mq+_C?e_VwAuE$$)l-hPvF@jT*Cbs3^zYSV zqstI^kN8HXe8?9kH8>AK#O8$_Q3}ZMC8+c`LeA@)IH504vsCFaa4)7|q%Csail>g? zkP;-0gP1mBP*XRQI-3>!%>q(rK+h|N&~+Q4U~)KgKRI?i-!157%=`DK>KFOwNO!oJO;&bP3NkIAym*@aSH!H-grgP3}GYKxt=^z4Po-@^eN)GX&Jp_`#cn8)JyI!U- zwJ+yOBv6yr_eazHv5YY6LRuPxd#I3$9qJo3E8euGKF+HwnV%lo5jtNN+4bhxrN;;| z0MGkt#t(|xjT<*E0Nof3A<}GsEySO_&t}G7Dz^2mL{h=<#)LVA~6K#V!{KM{=0t4i#=X)spg3&wH^gLc{sNu z|FLGUT_7DiyBSnl#_Ho;g??6t?y8nrFvYcK5)%`hi@rQUfEY*_bzISJcjXzKmL@Lh z7Oc`}D9kYXS+At{33 zSj-#|%y+_aMCo45$N7YTi7nG#HEM8><8K{G)9l7G^n(NRwY_P(|(yWG7)%xKB@NQ|FZoFP%{(8{Kvh>|jyNMyd;k=0g) z=2L|MoE^3|2UP_DKJrt%c;^5anx{K2l6U!lDeDm@A~9dX`l*(0+DfWjmV1ej!|wcn z;8Z_Siy=hFbKb;HyT3PNP9n!0>XnF}$jGn6AV5!TVmM3vJ_dPwcY_N59$JRO-PrV8 zm&ioNMJFwFe!9QY_b2kzv_8S<9G;ym0Wly4;7P{}%KZ?8gY>q_%ge_(H{n<1(zD3c zVGZcWlO`HHwg2>*%gTMfO@u->u`a@xnw4vP>*xPEwa`OlTw&P9G~#J~-{7Ood8lx|(JN**tb(3+=19$2v4 zDPQzl{#W44p0A0Xn+W#EJNq=*dD(|D>jP&aGdjO4QS?;g5!KNTMiq=SWMMMO8epIPYj#`^Q$_a>;9_g?CtuI+(x& z4PLUj&frBupWy0_M1%7ZOOv%@fX=6J@bd9_fgh3z69tr6M5zXd_@?7JBp`Y-Z|B+6F;mN*;^ueU5vvBZSVo$&YXT`0!dHuWkAVBrw2K|OH904_GvOw3Ck zd(^EogKXQuu<^b&-U)so;z2O%TLi4O38<4nPUM$RX=xzWy!CGc;ev?VTvvDNR~0#C zkm+w|zj7N?&Llue3Zb;{!bgsHpM7>91zs5Z81%xB;%b6!fT-A({OOXKI+zx(S$*L0w_3Wy09Z*7k@oaPC^n5!-{LQ0l4tw@)vu2TvHKC)(Qi@%z+RBZMRqIr>Wt2M-qBEtu~) zK|6-gy*}=MO@gF>IK71e%#}VUg9w!Zd<7;J;1#=WXig*$z25xnQvAUh(*P(WvhGkbIAi|V8_b2|`SzQR@O#_~h zUa@Z5RssbiJ5kmErY$BSf*3umFXL01WX~PFZ*t-QL#Mubw^!tJ%|;~lhW5hN!&m=? z7?0D+i(xe*s&=w_(W$AT!WzF!8EkX#^P74pGMv@-PCbxQmRa@*U*c*13s(h!rS+_D zQIN6d{)-o7VLJm}JaRBRaLKvon4Z4e-kU)e_HB3nFRa*fGs{W6J1l=Q|FK5>8nd#Z zzj>hc`x&3bK!&%`S((w9nbGkBK~k?nMr^k+DfLcHIQP5uJV(k0F*YoL$5auLt1Ky)Shms zm%TV%k)T`jnC-;v>#Eg5pd#hDL*xjg5CZB6gX^}K^y6L|x{jQBQLba`NXn);S9Vr#9nsQ>m= zcN+N0FiQ!VdYSJ0Pu`)!qnw{9K~c1^j7CwJ`rvU=3Y?czs>f4fO2 z`QK#fOucWugZip6N?n(vh_83QOkSNIyDm|ghAb=YT9x0O!hZZ_VTh!Ym6qJIX$Yop z0>Cw@W~{y<%xv<{b#xE9b`N$zdm)lEABmR5;$)<>m%hNu0jog2se#6lHQTQJjdJy@ zysF)q9Qa+i?tL4<22-ha9uwR@-2Dt}+ei+s423FhI+lj*GL9VVO*L=ZuBK(9g3>cP zU1xt>3m|r*{z-KMM^3jEmVVmAV;7+}8s9$xFFnCR6lU~>>?qkqaz^y|Tb7)6MF49= zN4V?Kd=U~fegFQwktK`>E&OzK}iFYC<`HCXThHwM5;XD!U{{0#7xa`w{6TfTT5+g4~``_ zGj<@}rmyBln0Xo#VtbBL z3CcuQOH5pVkNbV<&=+727PBconS$R&Ce`mPJ7(U}Y(`jpNF|(WEjt(=tCb~;(rjh= z0(-i`xNc7k^mE;Y!A2sW;81iS#U-SDfg;$ZBtwO&{&)`%k}bX{(#BHoU<0lsh2(cz zQq9EmN7LqA)F^Wx$?J(;8NBXS(c}2oxg9rB<7H*8X+?(bT3NP5tr^yOposi6PAlsKI9X&=7x?Uw7&p>_Oq$ukJO<@n zB_JHhsUSI}jMBUhVIE`)KmBN5ExxpqXRsB{>-3+2CS6F2w5zMD*o9bUGOGKZl{FowLcCJC$v@}f!|fMO~(`H9Ac_**D~@_SD(rgs;89A*i(yU$;U(IE~wrj zwzHKXShy0qUFy%LGgD)2=y@bifqJnuA}ovxRn5#cH|A~yJkzPwp*J`I^gXuU%XeQ} z3uW@)0pgXv1)HR^DH_!wlIWqn#_Qxkcs{cns-5F_+I=HuI1K6nY34h(N0;N?1a>l{-fU=SSTt#xz$khptit6{ZQEqeyJ7vQVmurj4X22Qf0`7-VO~+n* zWz`5S>6U4ZZOYSTU3i*Oy|nMQIcCP*75#$4q}6$%(y~&hu@Ll_wxg0#;Jpv}p6q<6 z;C@$HbSE=P;Ua>D+`wWtJ5z&FZT6}A{_>!blh$f=KFD?c7kexbXd8(&n6|TvEZN%R zd9R3bDgiAnGXCV3+o7esbZ!run&U`->CX=ap(j znJ<&GSC<^P7{~%*Ha>u5tffkOhh$A9s6}L3>Etw~eO=k=EMPyzkX$UTDv8EOJ?Ul< z$SvGj|3gkz<3`(q<+`ct{sEv0Bc0Q$8CC`eVf>d!*VL?nqowGnNUDgD&;OZRwq?># zbBagaLROv!%5@-T134baCXGi7*wQuLWl>xO1{cbbq}ey_1W0=kYHB^f(K-%foLn|x z)2rmABEmk2rZ`S`GulwR9vW#LTCtyJZ^W&0d)EhwVji`Z#Q7j-K*j@C%RoB^92;h4 z_w@|&g(vT}J%}=+AX9?2KEil_#bh{m4WH*QhwrIb*`J&^zQ5IC&; zs;sR_EN6_hc>eH2u0_Cl6=I`8%I06}Xx-(2BU)WZDi5*W_v}%P)nKibrZ|Ihci5j# zb1PDq1%mdQ)(A1KYXO%&A*%v$L}9PgOa>crV0TGNiP`kmjZ#sW?&q9NS2{x9SN_K! z8GdR<8c{%jY_H|PUH!)3As=&|9R*GmFHjEv{Q>IxHjC^rIizAU25kRgP)T4Fw;g== z^yyPzh$ zJ2+wZOksfu!A?B2+SX%Dxnr@ljPi|L;fIx}?lLAw??x%8_sbR=CSA2`wHh8hyfWbb zL|-GS_A#uk+QY)!=U{{BMU#t>wy{adw2Y@OH_dL!9G~2!VDYf!XP*CbW);nS!D_mH z(UxH47wa8Tp1T&0Eg>&3GIixMb$?-}IGq8PsIsB@DGM%?G?P6qV>+5I4Xr({NlTFU zTCU1hWU_0ultsOeqy@pf;?1lxf)$N0vT%__xk{e1)?G9t|?@Ciz7xbcyZ zS(mC`JIxq7Qg?|qR#>1I!}T)-NT`9d)JWn4BcE}Eh>DF~OEsmWog8qoF@N>?95J+* zn<+Dpzu|~Q_9_T4g)xw%>!CV8VQZSTue66vg^n~zo_bFG2KF7gp&FmTEfD$sHf{XW zfK_XyMYy0fpPiL8DA=g4c5v69E5@^I3vnO#A~W+CF>i-T9xT$a%{+`h5m)sPcl_g*KJi{9jiwi! z%of7`o&7Xdpx5^#I7yMHJ%a4A@v3~^2mQl&W%^c>0ocTapj}1=_p8Fdm*izqs_W47XC^OPUS{@CJCQIZ-m)*-Z^+VUI(eMR*=&xS)$xEc&Ua?Q4tMl(s zun`;Z332s7;MunHO{u7=7UxkG^5iMYOJw9iNjgmn zIuZ+6#&&VS0vLr^(+y58X&XFgZpBY`?IphFLm z7260#oSVdSmHgWc?Gf_s!tC#9R>J54y#A&w2QEBB*cm$a9=;d-W6=T_xJZoKj5770 zDcix?dB{Y^1F=AtXG^5z1YWl8T8@xG)bwdXaM9enr zS&+Phq;yQ_RvbZG+*u&sZCbmmI-)uBtTF4(ugxes zh{E@R5f*$zj7*)%c?WW)=g;1QW_UY)TZ4yTRv9?OO9g9=(6|7$o`@(78}XIEAKCh4 zPiH@G%l#WrFsW`S5@ZIuCPFFB*C3CR0JW{B7)j9ud7;_u;6Bd|+vV**^jx$Rd;mGP zIj2SJ-tVecd^YCG+n8*d(OFirocgdjNs)$G)v*2Hw)+&!M;E029)mpTqVK1+e(8Ai zqytEP9uVMy4Ek>|hC~9b91~?d=L107C0ApkyGF7=$|ZiUHH&ss&+R zN)x|1{^7QbH1OudiN24Am1zf`p#Nt$dgk7MwHni*OzD6>?K9g5c6n)cdp~Ajb9)9% z#6#dX979b>Hc3t@;+s=N#YWMt115QLp=bHSAaT=UvTrM2a;s4|V!jNkEeKW%AWo0!!bv%5C5;h2&L_SwU z_AY$txJ14UVXe9Exz0bQE^f@LtdVre{~8D#9dnu*DmWNuOsu%(i=Djry9*G$i^TB&-!H5R7FT-U z8m;0E`73ah^q}(X7?6cc{RuZf5R#q?U0!Byjbn{FH0Ve5_}z{9zPmwJ4TNvR;G5mJPWlRqKFRJ46QsK z8mkR{7Y-nTIeH4b3=qm@DaxZW`A71Zw598UWcM&50un9PE$2!w*Ja{dKAKouc$EW9 z_Y!%BQidL{{cZC!{o(eS0ax+@IWdBY((X9m`>A8~y&Sk|*TcOVw@2q{FFC@|VcGv7 z67kZ%H(3yCqV)BMR3eX5tCn_r3eDHTWL*CS(}_6E2$RK28$fTqcI~n)ihBSowx6gJ zAwy&!^?t|gsi6Kws0PMuJ~aAhY_cG>b?IHsx2$8`CYl2|+ACvw51mb5S3FRBT_rXU zgW3_Ht-NvL6qpNPoRk92Xcxfp-cbGfLdwMvkrggqy*m40u09@RRzN26F~Wt9b@1RL z?z{SYd(%#))>~&Z#p&z2bRF{L5R!~`6fRx`!lOyjeXn?CU%^RN{Su@RW1#*UB&L`- z#cd^wMo?-VMcoi6wdAEbR`)kT)Pjr)lHSwH*1~VbB`@rfo^^6SJk>0C#a+9$8G9fG z$AG@Xbdw&_8dCJ?T%k22khKl6EM`ZLC*tRa+l{mf4U>=nJ{)E{!53-IQz-njyAwc^ zj)nG_E;uPFy2J^O#LC!C-QZq>PhXqpijSAE4_j|@`}*G^Dx+zR!%#ts^v&^VS}>9Q zcMwWI2Kd<hUn?_i5cGey&sKVvwYMNnl&oeSQsXOKo&rThHOy8#^xd}2+tN>K_-og|5c z^z?zxPco@h0nnlkdEv@T7JK&`$?OZq$%5|Ei#LFVvY%{d1AlKla*YlA%S-I5v>_#g zG>3%ETVIS3Nnp3)l&r%!*lkL|WAebkojcaV{zuE}a)thho!Soe1j%Y4S_>*;A%pKw z)$f4f^bX4M462T)V_OAQCIO!O#nBu8p!{m|6!F&IQ^YIbJhkJmy0V`-4l+lOkGcWC zPS87*E`+R_9w@bW*_s0fXb}X89$L6gykffVx>uJZ(gmgl(I*kM1pA`ah*~fGQsqjB zHkO`#@rFM=`nD?D!l1|`z4S{#58QDkn@+O}aBe~QW=J1|tjH%`IF(dh(M zg$jrel?G*rg6ht>Hf7mappAy0pQaQOHAJ0Xm>!DIEAjpc`Aaql``aw6tUZ|*&}+D5 zD@If#+NSVB$9B&ezBP%>3`+LsWno?ld!ulIRyT=rmDIXY_&FO znS;6?9WG(54U&MqE;x_|lpZ~3-*8z)W#ZILlo$ir%ZY)QB)l~X$iN8ezQqS{E;8|! z&f=}_;t4r#Bw}rfPMgmV3mTJ=y7hcumD?nu-yzo2>64#ya=+$f@>+r~O34H#4@t@f z)t{LV0QUnmpFw#IXs58N5cqXU58(I#uM*YS;Ot36#ROjk$)n3f;lVUlUUsgHTF?x+ zw~MmqsM2iW(efwVb&vwvaK_^Q*!k*SIngRs{EP@;8y88Mgo>%wu5ZU zlpU)cWFoJi%Q|%78cI8}x6L3Y6oDP_q@@ARVf^s$jW=Iz3$(Y8SI=o2pobrGaGVDw zAoISJPlE;Fmw)cQ-hUIgrjx_vA(A0K=8bz_oA(3(M@Ux{ z@vMeg(x8~=v}s4KB*K4C3lk9dN^Outw*-U$ZQKifIA-W;C+w>Dty5Ag#Vq(PJ&J!P zhp~;zhDy0~Rg;#j(P7&7w&sta){NumP?d#impiOx+UR+I-8R&#WCw6i3_LkR1u|`i zwu57fU`4c=@KyrSlnH6XNI|hg`4Z$3$h0TefTI2(ZD^K|JdHyOrFN_v1~KQhHz(Pn=yBpL zc!N#gk`-k;Ojv0#UM!r+qbvbMD#kJ!tQgu!M!+@9ndS$K5Q!0g1*mm*0G-IVv6WM`fmUj>*jwk2UA$~V0cu>v%swb zL6ccIxvD^LX*iq)6NJ3gR8)#Ur1{yCBz&8WpL7w!q+JTiEZh5}AR13x36PY*9CUvG zBLY%$u1~D0fbXykOc}dqJSZ}uCMbS@O1#{%F#VPygA-e2q<9pPRwLB!Ylh3f3hXAh zA8;{;TSx-}(1rRF?cj8w620S&KcPd`R=|`$SULk6a}07I29tzI{>cNmqu6zARCWjE z=Kon~73R=ym$#r*K89j_FdHwv9v8P8<}eJhlq(lasmIq#%@yT0-x<^fe|t?$Cpbtp(_AeIP}LBiB7azyvYq8ARSe z&n$F?)B_@dx+wnEVWJRxrLF#`Nl@6Jbo+|^IgD!)AN08FnY}E}$turjqpVsb_49>Z zH~^>Iy{HEhuOV)L1P}J8{95DYK}*zPVMU{U-~(vnIy;n)K?#7t)FN2GHyk8zSrZ-c z6sU}~uQ^j^_&;gW_zVKJ`*^R|bF{$kjzPHqM_iDdJ( zOg}PMfiL}YpmU@k3i2TFhEvYyf^I*#(9o}B?T9CG1ovCXdlLY?(Y=kS6hPlr9>0Pdd)YO? z=vLf0!N}#Z->LjtAZ6KqM)zyDnR?Vahf#;sGJ5~>S50>PB!!G6bD-_=F6QvmYCSj& zEd0bEj#Tn)R5jF_hg_*{WuTC#I0;M-%8~^IE7W$woxDEvZovPNspOevm6Z*znwU{h zEsWE0N>Woi{*(F`__N@Dg*h~(S?I)_$GA#x!h%3FBm;WvZ`>d|&zv&rty4XS)`CoK z^tp+bUjNw9ms-*23rr@2nb;^s^H0kjmg_s3tQ}}SOhxE1qo1&t$G_yde9)9*VPO$G z$C(nWq@q%P$Oc^z6Fj}JXAk?Y{f_H2-@as{0lR^G4A&v+ui4uM31qns5vkT1Y36P8 zuRQ;dS25S@^$IZWmK(V}Z`$*6QF#ZGdq0y$wln5ocA z?Q7RKB7>~XHB?6$Ye1dAU~|fVQsYt<#`TPL=eoAwbvi!cIvN4fnXg0HSt32f4@|5P z+AC#&8Lj`HzXC;c8Zfu`f3eczoMLy*h`PSl>DDhmm;<~$F=bMYru9x^7VBy^0g<1D zH8TZ2sA1&!?nnNCjbDIqz2YsRilwJo--^bmG+Z5nEdidS<)MDZcnhu0hMo9C0r`q0 zWHa0dNYG#)ARR4o4r129Gosp>!T2ZUZq8}$Dq27YbI!(m>X&M)koBvc?EAX6XBHA} zNjq18z1IZpRAkUz!eL7mBsne>FvhN=H8i{tIwo^-3f6mrD2fpvV$+X(0EJc!Vv#f( zaIZ0S(37&TAT%~OZ?>Vi_oKI&fHED=tD6hF?IuwRrMVhe15msCN<>Jk7|>_tUI zG=sxE`#tGZSNzDl^}T|;(`#aNAvGYN%u0LqI@tN_sX#D9g;S`ZrU%pB=Nz`*84l@7gV^37r|DvSw^E{+Dd3QwP z))O}JdGMAt+=e&;^*76v9&EbW=Ay*BxPOl>glm@2BC7GkGNeV}xap|~h~(G>u!3qe zzH&-aMADuYzuR5>z%UQcaTV?1Alz-P4#_-AO}S}@#Y}$L(72)FiM0G&jdOCj z4MR;UDl$MtG$We;ZGW^R%}n~WDyU-D!-pvQnG6R&@fa-75>RD+@jNL2=>L%B67o(1 zSO}*%4MqC< z#Z}oL8Ue2d2*v!=KtKWksRTy(%+&E?*RCo5opfY7tGumoz>mk&ySn{+qXH@YpVz^$ zOnE>$cqxbtNp-`LEJ2Nik^238QdtI|^%6a^=-I$Qt0+~6_ql}BGPrwD(~iAF+Fj6K zSAc&>g#{^SI@8))S|DVx;q2I)UY6l&9_rn~L;-5iKw1YV3l1UZ@kcP`%LziChjz_>z-d+Oz^hQy;Jprq&=*lprv;BO> zjDOY|$1jZcNm=&#J+YMSO;xAY;2WV8vUT0IBNE+HfWskR17JARvvx-Y&-+*49v2HW zUVCO$1+5(ZMjcXj+^K>f1W}{8d#{05!B=p<7=v*Svc@mAJ$r9lP?7`ysv*e3BA7PF4!6e{YA?OE{-TZtn@cxxae2y^GaJ{msLT>nZ|HB^|ml5~i zn(JH-cQ1%(q&08};BREDn!?ZCxM&4har*~Sa!nQ**yHGis|vjgP^0552brX2PwrJ+ zHC3DIvVermuT*^p@C7LixPpv$WXcSR$PnF0Z)UiSySEb9uK@A}G_>P0Qdt%~GUPcm z61l8p%%j!JYVeW3w7|p7fRwRDHsrlwdiLy@rdSl}hy{8>h^}UEQlm{gu16EZlj zB<{_d?yyFnj{&#t0!aDFvz}Z+)u>3J!S6>qOdQgPKol>~;L!tlPn?qk_83lhUNGJ) zs0<6yPi@2|5FKieA;l2A{0NhK|%Lwh@n2_Tr4FVntl2M87#UDzL z^{rEMe~ztw$C0nOr8Cpi;{>Ce$JlOtg@-()-2qVBUbR&(@gxdV7b8-W`ge-w@v4VV zU8gUpPYko4pI>AA>f6z>g*K5J%5Mu%-&qDFsZve=u?Y@3*Zz5^nGC&mi|aT-BY^d| zi)<*ppkAD*J~R0JI4bu<8KOHw%|d&f2z$A0ztg}rEca*K$z#(^r%3Ds8v=qbD>Rl! zeR=2jJOC-%Gd7oIBbW}bQoM&Ytj;)Xr}gXtsF4{fDy2BjpCeenN?dl++a49;_&FaB z`4XXLj5lAeEJR))_tn$|1H^6#5zz=K7#1WT-hgL5D~RH;)iiUhMNn|} zMCJ=(Mlz}c1eV%q2!ari2H{@tu}7%)B*5xjs4w^3)sjKDyPyb=C{t(c1CE`B>&5q+ zUop$UV3u{k03%(=VpxrKHB%Q~2^S&uK5#xoqt**pz<-x7;>)4#R9X9^7&g;ab6_PJ zo(scmY-dz-++%%#xeo)Br4CB)y<7N zBMU@I)P)C;J+2a&PhXSgDhs+6J-NvZENR?duFz*#3KBbFeGsG}`K8eQRo6g`Mx^!j zDeov^H3k0rbUZ4#k>$7W?)^)6%df~PL4-BD{P%5}ZJjy*CtKED6zNG9!=IFETRHDc zQI3Me87HlUJ#==7TOdsQcGT$xl_g5EuF3`E7Bw6fjoXNS&*%bw-je0wluyVbr;u~f zSnF#z>8Ptw@i_2HP61F%26^*`kfSB>{IQrb;=+%J1(1ravV4wzQYO`G*J^VFIlOssv;s@)dEmfb;w{NK zrL7Y~kA;2zJ-9AxBiio@T3KNA@a!Tm80GgoY1*~w2rsV(D#wIP96_QiAA{a!kPE$r zwk_H=Fh?F>egx08K|;mM&l-Q?u>B4*WXZAC2jDoLqNm2r6g^v`$b@pqkYj{{Z14}~ z&H+S$M%gfEm00TfB-HoJK2(bHwHkk5H|Lqp#SiY|$<4I_ibPTqNHy`u=ZQL%lT!I% zm@%k|n4++`rqNHsj3ZxP$F|&|4zWz7ggR!Uti;r*!05cmd8zE^Z9Qf&wB}FzTNFg& z0$^@~-?db~hfPU}B|q9LmQso1ev8u6!;P_L@`TuMd@M{p{t~7s@dN}>n(fu3N z)wywB_k5kO`*ZQ`-0Ms&0+~APOZU!Q_3w_bt`(J^cfKh|o)C9zpOE}A>Ql8KiG!{e zJIeM7#;^8C{ihT7IUYpElKJ$th1s3)jf7kLvu@pIE_ zb78LzYQDOKvb5zqIimLqH#AZt{#;MIj6JYS2XeXxRWI`p^AP)1w@8(DU7_(58NvEX zymVb3>W9JcSoyGpje#n*Je%l1*W-|p<9W;E zjnze`_=l?PQ!lT4#&<(L@p0c`yPam0QP46Fs=H2=qiZI;=*4&U z%I^}ke-x}KPsxo$Uq;>s*mCe5LOSrUkpmgj9VTH5QCwKb*vKz#| zFLfCiS~MiB>rh$IGSa_5|800I@4~84rhqS1dbAYN^(a~)uiLXy+ts6s>QiHHH&Jed z&}Uu=+A$GV50cf~x~4OuGG%P2LsWXZNhB*5E%H73U4>Pg`aFJ7Fn-=PGX@ef3Oe&L z7vje*BHHXT>P7E&zx+lf1G*x<)-<3-{u~o z!WK5;!C{H(R~CSxv;!*VheqD=mV3{Ly`{}uqV=1IgTjj)p~ag*TqMcge`Xr5p^HOa z*uOUa!e3=)a|5NH>5i1eDcveh_(*J*x1F)WxwCaz3Waf}hSV!X>gWC>Y%_+HdSz{T zvALM1;HE|&U%(YJQP$@KR9LrIc8}ixIthNH4JlR%f@w;hjqW#@mS^`U#_$C^#l2O` zFFZ$Hj64F56lo$@51mM;gOl;$kS+C}hgdajmjrrEn&>H{?sCTK@BVW(D@xHKLeK+g zL-A=n&R%pe8jMRG-pKLnQ@=VJV$ikb*XTX+m)~F&(s-a?f8S@sazfm>xL00E&(@MFM=t= zf8e1jMqTHj>G8Nd>>D2NX@k;@?WmuZAQoi-LVh+9R~st1rdBRHdtm<|`Z0#zILI z8UnbJDF3MT0LO`O2leil+bY_&yI$_N+$-M|x;!M)Fi~p~wPKe$&FBxLt}x; z^&&44we6RTE=>s2m)L!pwraj#eM9}LDbu0k$0xvG_!v`P18aXrU2^b=ueG65gL4yx zayHL>TBsjzTePOuPGd@{h8x#(DkOiYq?-&kyF=7_9W}6-hVt^<#hggc*OlH|{r_`^ zfUz$nRl!?2W@9IyPsfVYkdalPud9SR)B33l_U)dTv(qCXI$^Yhg;^v~m$e&rbdpHY zs!`V7N^bgu|MoEZr=~Z_T9BT8y)cwqzGC|A>EdfjSKhUN)6gFcJ(q|#b^A*4!g+O%UBO9*WfDSe*S;qZ#I z%XwKVWJ=3DVF&(!nUVR>l3{Jg0o7@By-6R z@5VJ}$bcevfWD)BT`$mDXiL$ct7AH)M=i@~&BP}B= z=4j1}<&At%cQ{A*_84~CinVAX_BJjj$EAt<$t<6bkFSVYO0WMR`ryK<+cqkv7pv}1 zOwgU8>!#ph$!Te|z3+w4_eJME;_64l92XKpa(+de*DcF>wX#?7j~9d5sJx_wscF#4 z#}k{d)~lMV6tW1Y!RVwMrQD@12&`C9We`*BM^wv&nGqjl9-+bPc>V=GVl?v$2g<{- zMKZq&*CmrEJ{el@=a%pt-X8dg_H`3b@~3c{ILNuSapt^ab(2og&82ozz%WG?c!gq+ zp_1%(fS#>?93-x6_4UaQ#?JZvs8w`Dh!fztoFN0#Vuz*wzO%r5diy6a+HR(koA!OJ z74iK)dkX)89`HK8wzf)4o`BvvvV}l_(FH{1G_}c#emHE_A*dpns;93_8B1tzu^p<_ z5&Q!}EPF#*ppb~x;P+*J->(XL+PRKlhd|bj%^d+mJUs1l9sBVPKR7oLutbj+>+ykP z^N9<&>uGo^lC~=`tmrkip8OH&%TaCiL%#eHZ%)*in1$NG;;1%f&Wf?@fkU&{7}7Kl zOdGD3+}XNn5jDDn0zBnHePYhVVl9#lC1|Souy;Tf%o9|(lprI{y?y)k2UU#c^E;pj zQy17aU)w|GDo+t#ys=dOEQ{>XK{`Ut_}zk_QD8*ssR;RvfG$&grXT;v2C@JWMnjcx zJi7njSLn2tZq4OiZduK5Af&0I^}LsE6v^;7?3sYVkf9{l131gFPxmp8UHZ!&074*W zs1=U)RNy^OLCu0iln=k!1uZ5Yo0472OY79D8`WCqUI&YNJfFKIlpj`qEI}<9P$&;r zDH(B+L9YXxu04A|hzFwJBdD+x$zdUJ8dRZ*lzCAJci^j65zsgo8Hw=lkDS0f>fJUu zkKa|Xe7U1aBs?~ne_$^2H!})@P;dfdcW=M%6b~eeFl;hk4gDz`ot(%>mJTp=B(Zvs zXIRlcH+RtD7QU6;tY-8F_^kuuX-5JqlFhJ4B0oJHv3KpAO&q<>PI$sEu4cJ@51BIM zVLg^pOjpj7u}n8%C^iOr8u8poq4iIRuPom9rr-*XO%fUSj!eyv;L0K01zj80>ubdD z$uXy~-Pgn4=g?_+aWDZ(o7Nfj9QzCZ5x}iCSE7?~zOzqbL@<#C)uLYhrRNd{X;z3$ zdIw}zQU~z=FXPZRyyIcW@?FnfaFkw2+n9fOby>|#nR-DCO)wcc7bNT@enP$@STU4G znwfiU`RQME2f8=`3JuuY5i67`NaVIY+2As^+)R>Eo1^714*j(@|L8_2f3u-q4m8GF z^QN|qz0GU$9~;cterv5S4NT>-rft{@Yjc)XCrsxWf*`NU-sriX^TrO;uASh^2e0^P z&a*$I^Pbuug_Dd+bT9PK2HJ)Ea@yRR$(lZkhyT|behWG|`1`pfre#biuHToTRj_ho zD%1Q7#p#eXmlKh5{pF9}2mg#XP93B$!E_J8rnx2Bjm8cK{WKJ*2bsKbCAzh2UAaVa z)`C@F-sl&*9%{2~n6_csp?t`RQxXNwnX`2gbhC(jd*W6G@i_+ampDNf0hYwK zaBTgWaUg^hqv~v=Vy*{V=LE>b^bPFjsFa5T73rK@O*K__?p(d=A<9_*bMtCbK7M7z zck@h7`}#Rcjec&Dx}zGC+by|3mp_!Sy@~e8R>_kGUKG1mE|Vp#N!)ss+&?`niL>4uqM*aLo_Ek&WsuY7>rI91Y0wj7 zM+F)RP#t0ki0Gc#qW7 z)Dw=AMtBVoN~;Z#Nov%ugwpj_KX8;^>~c3Zbn` z2CBAdg$C{s{v;p%pYNa-SZlA;Hbeq|%++p`$%K;Qp7aXvXFx6xC$^(y31?vfOe(5@ zhl5YIPw0~1>^!1NqJ&09-VI_c+}MdN{0*fscc{x|Vb~R{Pcpa}gv3E~9_wvSmFutU@ z01~$<;Zq%YKRrAsjGx*nBRVfSXlOi;pupcowdQ-P7(McJ=E~K=!D#>ap3j!>XqiRbs5JjHj5G<{D?n# z!-px2q78zbmvwY>-YAc}kB|334WbLTf=!Xr$FUT*vaks8iB+S!mWrLo;in^6xM(4m z%rZClGR68<-1!8q3+~`hUuX6a=pvf!rN>pO(2G5F+|EA#)|%T??-BHzNy+ zT~p4$NZS&mZ>nd&&P$+xeo5XTU)JSM)vK&IL-T(Sz~U=sXxRI{7y6;1&%;)V2(h!X zqeU@?vT@{SJMC1)+yvl+Gxk)88|v$W7));m@A-=tE2)u;+vkd#t8bsWXuv=Rs#qRC zORKLnHAnmBfOtId*Cl~eR2NYyFG%4oJD9+o4|qgy=2%W_B5fy4T==Q;P5t-1ECmp{VEaVK%z7u#m4g0m z$e<*r8Rp*L>JSqX(}iWYcWwCxXJkrV0;KFFKA!G=Nt0O&L~KN z;*zSGJSLF=IoZj{$wJgkRabWVPmmPyKt2Oo2>+fgP(0+5BLdUXXuw?KD4$ZBIvSo& z3H6(-Sh#Y)Ki*h=J-yBA#E#ZgAQd4Z59X8kN=|H6mN;s#z}!M&g0j9_)Yx8TS#qwQ zpPUe|3G9{1lgIt%c2T`74C}$i3J4siV*tL7&?y8KI}Y|2l3fG}i)>*_3mDN=jrH|j z8rsC^YBeD{@H*({j$2X1ivky^FY0#X4NNX-76aO}$6{v1uclsnx(}6Cq=Q`QL5W60 zM@I^(@_tX5l3XAWyNib?iIx#<$?QFIX<|eD^OYd~=rORT9Kbt1-ZeP8d31wF>)(i{ za`139%6H8|9fdc684~+L>$huEVHzVN#)aXP*L!;}7 z{7&}iz=J=}zP(bANW={p;tllyQ>F%|d8862+Z^aEDirO($G?Qs!(u=>`(ug z%gT~Sq{Z){OX|tV$+G9qpKrCQ;2Q%WS~+?7l60Nuq@?4h3=@^iA_|H>I&S70(!$fy z?3zrx{C}Ww*BFrPSrA!^572&)Uk_TF->8*(sOn{7P>C#c*s%M^!&SV5^kVIy&I@(h zXmpAT)iU5aYn?(@-;U%ho__nX@ezXgFm*h zpG-V${Gm%9l4*qsQr1yI?E||IQ`NrQw~KAAC+OFkE6jN_%g4#<0+!D)T%jETEYR9c zKMcBLp?-&m=8d=>dj4)c{QVoHLie3Tj0jZpA2cZ>*K*W(vA82)?I%=>iWoeXwX}kl zcHk?*ZS%9C=?>D>h2`0lx#JT=S{&Z_x~?*dIOg{XmHVK|Ih0_1_}QXR{A~w0RD8L2 zwpV`PtjO`c+3^u**VP3?dN1TfZ&~iZ%@DTs*Htx(;^S${4FdE$M_3FP;;omYmnQ9@ zF$q}@8ks0^&lK*tE$gY?D*3&-?52WqFgS@@LT6q-S+BkB6AV1gp}UYhYWTU#nFz9LG%n3?dQ`99iPZos!>eJMPH6;>vBL~Wp`>x*Hl3;dv!A%d+-y7DB~VVB%_8=&<;rhuXzU@ zSGzi|+z3{u5}vi8Cpw_nJT$*D!7G0TV$+JDC`aQ<8i4?W{H*Z}Up>#=fKX_TYfF0z6M310G@c(1%&Eu)s{{Qi zQihZ{ga{cz#&d7C%rwc6se}-cc|MgfbLLrO9*=qUeXV_*b9%qupU3a<+kf15Z)fkd z*Iw(jUi0huI^ZL*Vv7_=>(SPIIXOAqnH7+{tyA*+C@T9yX;fWb*;ejD0%RC*0H>)i z{-y4%_T2+*X8K}gG!<^Nbs5`WfeIT@iVvjP($iOWbg+Ts^nkpSLdXMs3r8$7v%OvY z8VGlgcjn(tMCBvgCCHB@`$7U@#P^T$udLT{MzH_5QY_A>meyL8w3^f6z*yw&v*Q!< z&u+F~ND5gV>4_?e@G$7(rRo^C-w(QgX`rS6;o@nxzfwXO#o^u|xgUDDoX3Xe2Ax#{ zX)Z40#=8qf2=WtFp!QhMOzFgV>YK9oxH0FS!!=!_oZKL_m8sDei~*2lzYC#mP=edy z{?j|m^DxC`)EPAv{W=J77S-_ZJOG6sd=hQURtFeV?OafZ0KOOzi5Ymo7w^_-Ua+xije2 zt^yAkF$nZLLjGa$cmliJ4<*UhHt5ovQB2 z7xEr}q4hiRH6kcF=%mLxWqW_?_@kZTOsGnp{sn#rCFkvuayX*qXM@jiQseWOENEc= z9}eSo&HR7yS6p-2VWX#oh1`-j?c_L+MGHoR@&Etz7$4`(0B6xclwU!#m%uN|0jSi6 zE&yohT~w!ys_CFNGU#t~V^AG~y4&4^TAx-Zt}_2w{ER({ECs$>3ze=L4_@tQ==y39 z`igckBi=x$D(nEzsX=2m!aM{CqqDp)O@ba2f5A>5kY{=z8{p!&2@UXL1*p;xAxxpf zU{owuUS3{ZTe};OV4+sIamNa{jJMi3;>%E6_nIYuk-(Pm=biDh#_11!lG}*1D_s+eHLlgZ zOS;o7lALuTnIY8rtZ8Fs!1lTg)Ns=^VOZ_;0eg)-uIHbY{z3L|ej-i93wCpev=`k_RZ?(|L1$Z3ZYa|N=DBeGwp+Ji>cYKevJc0u0!tS z*o557HTQDZ@JOTcDQ~N(UMsJCw3jMMQZod21hO4EZ&oz;0~znUgfA=nN0!>)h5@or z(okS%EV$;S%Mr>A5ztQ_|2JW?`G;6YRY=l@a%#RoTB<@AI5o)X6VIV$VapcGq3+uT zn*M*SnPN8j|6y_tPC;=~RDmxi<&PL48YkOYRE4_ZfDq51B@kcr_wQ#ull`<|qAWw- z9M<1Qnzc=J07;8mYj?C#3>Hn9p)3H{zB6xo(1273(Lqb*v-j4bu>|vP`s>Gi;FY8{{q_o({n+=vwV1glZN5 znm6h9wdpNc%}f>5i^-e`ybC%REj}I*2Ps}*wJB+7JMBf&x2J;z&t#6zIc!)oX|a6H z$42xONnJN?>=S;j;it%BHdiE(@Uxr3e zV8F!mv2y~jh0RyVr>>_*%cgH8ZAzNv_&gztL_5G5L73IVBzP^%dQH=s#f~#-e&6&j z1PKxRcjirZ{JexNKR*ISj>5lWN6$5JVf#hPKrP5Qp?Ug`bE64E&3br7#>0Md;9;(= zP-m16<=P%E$)=C2mO-T?o?69b88}3V{H{pY&$1pd(CFQ|G!QTlaOn&m-TCzQNB%H< zcKPX%R#8)Jf%sONzpUtYO5e&q{Bm@Q%+yWW+KBNl@wXo2XkXtbrBVBQkDL09Bbn*{ ztXsG4^TB^FyRQ3N@_B%sU1U^NB^ztiW4$wDEoNGMlhL0}**R4%IxT-4)bCxMfrAhS z{+HBn&@WLZ#rH}lxfh`@r*!{X97px*ee+Y0+2Nex{DgW6Rl&TKBZ9+zrN4i!W>v!? zLtW{lFS3o95VYy~H7Pc^pY?P^pvcHav95O)G@ntMauDi4Cu8^skRF8q+mY*MLdSaG zfF~5fX8lP%C1DvRmmv65c4AXeRJ+6d?cXV9CmD24|1jkE0{P>^xH|v%G!aQ}hq3d2`KMk9H#WCnT6Mp+w;I z3^>tAPBxwi{D6rb?YI?AWleDas=Z4XN@sB|CrCY+2n9D+3133Phg%E?UmJA~#nECQ zWp#fLUVwq^HxPm_`-wJ62n>Uk9~xdeusCfn6IMq;Z5nU8AgSxne}T;%g+E{~ep+Ne zG)U>BIck`TydP{!otwI$z8^=WLU<0~-au*HU>>{v{rBJf{qIdSIm6!sa>Vf^^fVA6 zZPa$oq=+q72w-k*0y(U8YRM<3B8WB2c<@my3)RO!H&t7YcDM!2PktKTx+X6D?>#rgLYhawYFWGJK}_CmX~wcs zEXFPiu4{Pxg%|(D>&8hH9lZ}hhLM7>vgDHpKj15SQT2m~6nz@~T7cCyI;%l6)K=dp zjVdH1|E2tMU$c<9=Vep%Jsm4`f%!>_G&h$kC}$V*t;zOqW2#Q{fy=MjSZ75O57p7K zEQxI37ynK9q_4CLJ}pAz47cDi7YbbJ$o}X1Ri;8 zkXYPhihzzWIly{Zbn=m1mfx}~yUmvZ z0E4AcL%y}IR(p3Q&RMPo*qSc9bohl?xWrS}OQ0>yS~qAm$Nufjm?I&|)J1JP3yo&X zESJFzBZIa7y z;)SVct2@-xr?4EbHnunB<5(w>S(nwY(c-@xex_&ai=yxYLy(u`O+Rw>=JCkD#SXJ( zi5)GLQJysvT1fVzZQ}I1CTyuZPegP@rz1ds+K;J9lX83yCSC!aZ6-eDOHKI37{EJ> z4<@N|;c$UepN)TD!gZ<}b*84Sf9+Mt-WD0VO2?Kj>~`;wvRuxgObx>rAcTwGMEqBD zVYqj$xNf#Efz^?VG%T4QahdWlaxXd7O!~%nFEw}bg*$nk9D;il%4etNl6J4XgediZ zUwG}`RC8FD|V|+V8Nco3H*=Ct738rkIx?h z#Oi$rqYJfXL;seChKUHh2~y_%Ky^S4;%v~B*bNz1oSG!}MnG*ru)?UvZ~ko;mc7Bj z!Cot&_!rcEMxS)jcQ77=^V$q~%tMkf|0C`NI;~ENBdAEI2;$CNsV$}+)z#JJ2C@+f zySF?>R#W#67dCGI;_fL3y#fuWuL=*mLmVyp$96MUbuN{m)y-%~$wy10(Vt@yczKS7 z{z=_~5;)3XUVFAY#v$EMpKJsa#LLhBvMB{{@tBY+xeI}J9)L<1QlgLJsdo5_zBO*< zg+1Kn<*6(n5tqfMKgKUWlL;dU;nj3laXSjrBd-_ez0MDS@5_2f_)u+dcr3|0G zIX|&(yu6Q%1(c>XVU{?$Q{uQ`zlNU_=%J+xcJKUq8Ni(wgRMd;iZm9^#SvFby1!9_3CT z0DN$=ug1iuLA<^Qx@vz#F8eh589-|B0`)}sfdpFfu*Bzk35)ibM$}%%+7@7d8S0`0 z5>(%Y5Z_QI$)A(+atW(Y0?dy9ibp~gp|=7{kHxtfdz?(BCtG`~rTP}BmLV1c-m$7D z2uKEXO~8)~1j*~CG(+dh47&Vvz4y(Qp*T6z0l&YCOUi@x7Y^%^oL81}^DP~J;W%~U zQyV0i1B-98e*k3;Pa;6Gla2UPZi#xMK;mY)X$JZl!r;AqEFO9D6Wm=t9$auUpmB-! z-jMIBWCAV`(n3R?Q!5`rZXIOUh@L9Wm*8?fsEiV=I;f6rLJVX%J#~Xnl6h-r0)%Ve z+y{S0w_|lT7nfemRj|mv3klVy`mH6EMIArCvjI=Kw2F$!YQnWrdxT~tkim5%1@b1% zoi$JTB5yWooznmf6X1GUpTPPsK4xB=CQV~(7yh{vtq`3(*8zDS4^hRgK!$bPC~v#t zo9h7jnl=*B1n8tJ)Gc%*SYX2$E zh>$iLzud-*1PltE zZ8eCPWETLLHEs>HdGMeBB5Q->%8B=dofk9LjeltpDYR!SFA<{XYQ&$q>v>*W#>lEn9N(gXC$sOL%jH5;30pz`Oo3vmOykKYOjMq@aEqQooQ^N zHsfnUW4Dm1WD7lK_OsA6fA8$ncIf2`g<}AayZfPzFkX?}aQk81h~uwLuC9izEPhR7 zmN`7?n0jCq$TQcnh=DX;qsd@t!~EX)A`Gdmuzw$C(anrc%a5ER6N*BED6jdX7kmIy z&Va&c)c2`7WS+Q5{0|Ur-63?Trge&s%S7CnZn7;g1*(za;LZeQMZ(F_FWYF=@!ul9tpu-3|iAC5p)K9&TX zt(f-hd)PFD8i67^YH5YvZ?={HK*VpMU+jbruS|2>hsPdP$-0Im#{sC2OoqBs(+~>_ z3$kE09$6R0@-Xl3`qbO+cCF6VpWn8praaXCqRpws6uy>gANRDIVedDM31YR6W|^_U z&x_k7jYTHQ___fF#kpx{(}DYvAJp$={6W;KLaI=5bnyH@}B6vh=gdw~x;RXl6-aa^m7H*tMPQW?=#jBY%4{ zowR-zlCaxF_kNX4#do3qVk+2>Schc>bpY*1_s=9v%67?tJCNr#f+J5VYHL?1aQ4Ej)%t2VAUXp^N z8367ef*j-v|NgW0Rq04^zuR( z)XXg5r%eD@%^N!U-GrtI>3ygHHA+YUfS?@@WM6rq@@2YB2d+&ne$dPjmX?;*oUxOU zkpT}y1CY||ANdS6;w|)ii<#Z;&S_M)++pUy7*MX!alcY-`y5D_0$x!Mk+0;#V}ezg z?itmt7dzHDO?$>OG5H5-9At7?qa19yb9p1dZro{oRWqccz?mj&1hY_E{p;7SIFuqv zXcSy_R+GG-l6T4EJH4F>^AA;K)EUlK>H=MW)r+dBdfBa%zGy|YmnR;><>FJ(8Y zU^4mJeY^^Cm?uaHQEdAs4MuK0(!-L&p?gt&XJ==r=IpuO2&WLSKPb>mlM!8(i)o7Y zR(JUM@^II+yr{6N*&R6f(FmSU-&?vL8(01VyI0fSZ-_7>NGKbj)e`B&NZNzyGx&0w zYKQ%b&eg%D4l^e2)#-ArqRH1Xd~(R!D0k!0W1YdKow?=`)EGNqKPU{^v7r7UgaGqy zFF|j6uF%RNlyoVCGu&;>UpEw0c-gQDh)geKettGr#FpcLE2okQU@qnJ)kOX54!s)8 z*moewX8SIR4S^p)C~t|_g$y`^Ti6{k1Sw`_(B0S^@^Twa>`V6BS7R3wm^biuRJc;S zlz|LaxD-s2sP__l$4CnknN^;p)SzNmYB|Vv&0a_YLI=vCl@E;ZT!7&y0)@I>IO3m~ zBtZMKh3pGB7W-)Uk$+|c_#SP#v-~MpgQ1V_WKL1s0oMG$0vph3#{>yeTG#0({ zsnw9Bgw;JhaUIWXQz6KU{t8!EFMQ)cl)HjZMyx9}?tk7u0?dQ#9d6nawnI+y#eePD z(8-G{E(Zf(ix^irS8&$=d|06yc@PYY>JrApKo?R~AYRg7hp{9+d8qJN}rv z76!TMJRKt&G&!g+T>HX-Vf;S1viM?eYF*_G0SQ`k^BT&)e^HAvsZmmj(#dYd9UUZZ zoBW2{nG|q3JdoY^qGm-zsY}=88298}_kpxcNV>hK5tG07-Y7RuFqCR2W2xZ0)ZVr5 zd8gAK2xdH7oi$I$7NKDaf<@HdKWbPe?%^IL%KGZRaQOu0SBkTTRmIHmUZ!nCBMtT>je&Wgt1rsxsAn@p=VkGcb9 zV+N`lYJ92A2rL!Ke6)Anf)EEf*}TA$Ml;Za@CM2g^A5q!>9~twq#I0R@742tr`~m7 z4&Sp?^!(A`Mi&7(C~ovWg7?6MbldQ2$35*$0pJm}LXwh~mxnQ&x$e?6;(GGI=wxQX zYLPf!mqtPxUkf$8^PVrVN5+S=R)rC?5Txx*ruTV^P86pD91dy{0UwpEWYf=7TS>_U z_`Z&^amTLE%}ra{xK*x>ys55!7E4tnFwGcb2ELC&&AeW>PenEY_HB9}GC3jZT^9-g z>Q3zYD9{#MQsJ|^G-WgL*Ct1R8{@*^k}X905z*7Rxq7#MTF}Jgw9a}SNoISnn{-HB z1t=HZypjc()zE@M2%<8YQF_GGpCTvSD#(RBM|k-I9Tvx0_Kv=x#+R-c09lzBA;li5 z0&pS_6NF-exe|G&U62d(Uh#~!=={H-6}V+YIC9qX#IcZpv5^?6$&VF6y+hR#gb)T; z^?0UPt0e*eK`p2f0otS%K1-}^vqbP7@)(=Jn@wsHsn6F^pQy=Cg7>do(|vB+31_E( z3V9KPyLly;OLz}5z${BpjB$kwKyH9CR7zX?lT$X6?k0Zb8bd(;Gthcy(3)+e5%Z8{ ziY!d#ZnMkGt^O(zXcG=B;95!0IfrQq^Cq%C8FW8a}h zbM5flYg;HktXw`jYxS4bFRtkv6a?je#=oKS$6MSh{_z3GrI_BG9mY}p{l#~vmE8ol z3EvUSz*ozmv8LUIk$KaeUw@wzxoFwClXzjKGl{c96`=FL-zTKpM2ynT8jca z(lC-_xis=c>z6`P91>Y$;I8+BL#V`zdz$}xU_SO!UklBhYWR8aPXMz^Nr^F2D;vHsWmEr#9|^Cf@-5Z6UM8%tlUfOs zr~|-hp-8VG``xoxUT3fJkWN9&gQmx5Csn^U_od};)>?Y_!Aak;t7)Y@p5~-kd)4>0 zTWw1wu?+?ch;W%HHSyqw(EQj+r$DKc~l%K7YA6*z|QakUp3tV;j{c{1nnMVepb3 z_E!h0SQ1(c`tp+=Cn_kN91#2+39vX5#XZafd5!UyZRBJs_}ew84uI{dZ3y--TWR~j zYaA8r)_c;|wOS!VIvRc_==%X|#a)*X`Xbh3wZgmbC;YmI!WChcz*ivDUEJi>x8*PV zjQV>*Bxf7rWw*Ze>1MI+ZVr~4kB}OMU+<8=xGLW+ON60vw}NOt@_;Aj^0zq4`={AE zbp2efE9>6z=i1HKHRw1D%l{#bbG}G`Jb2K?tp)jf9y4tj8!u6AdyjuK!%%rt6Q&-I zv(m7D?R(wLOPodhZR7IL#lSplL%>6x+p3_ z(-Nv)qN5ae6HdxkoU!uUZJo@2BDDBT3ry|jpa(RBx>IHmcpVSTd^E|K|H;;X``rm8 zZ?2sxKyi}Vo(_nft=&q{C$GZydl=X5QUN@DpZ~Q8t34O1R$fGm@iw^<0~(V#g_A%c zu%l<`6r1~m#sSMO;eC5>v#^t}5YT3i$G-xhNM8xs;>i(=yyp-BKe@+2QTu$Ic@^D~U(As5TP_^kcL-)`o) z;!d}=$XR`Akc4pR0ra-SuIUzji*`Y1F5NA5#zPo1EBH` zR(SZK`}OzW;lnK-an6*S^LaO<+KU(p(hQuvC2%7B2D;@(s%d@F7ayXFkc2!Q#TGvq>!dMETIT&-YMEnyu$zx@?}yB zhhQBJXjAn&9vHK)4B88)B~KT<09|2FVE_kCz1hW5=5o(m|IX1;-0@d+{55zF*-~ab ze_>n3I335QaW2cGW;NV%1t%7n5qh2Be?Hnl%E}V%Vv#AUpt=sR6cq46TUTR(Iei9I zz8DYURviZy-j)K3m?j@qK|#%&MM;{?@;(9&vS~Z;ErMz3Y<>R-p0ywuzHM)zLiuUO zmP4f83t9ox1P;syWm$!loNl#@is_ZPJdnB`9lUbgD{YeILSHvWQ$;TqjRPl|!t^Ul_8Y3D}*^##&4Aqr^+6(M{mjxxx-1v6( z4;bs3&5)qae=C!NxWLu9_l z+Yf29jab-G$0Zj|ML$3ULBVutG(0Q>{j4fSZdab1v*?`18=q@zqTJ9wL@VeFQ$~z0 z+5g>!&g$pn2?T~pOx;tS1c~S0+!k;h(H?#c;%i=DWpnHlMpn*G_ci!PXw^Ar$*X|c z>q)h(uc4q0b~;i7GDqlfhHQ8a)=fzuZ*i)f7L}^{oqStVEMN6}b)o|K45fU+{pHUr z_4Q~v?%H~i0d$L`YEO5ul871ZBoqxIt=-u`%%O<$wGLE>Re6b+9lnE~;F zz36t3^`RZ&87EeHICe&a{KBpv9*(9LlE0yIZLM!*ki9tXLTLH= zpy#Ok3r8CPTO82!tsvg)_YHVr$3dhJ*0wkIxhPi7fTEvU6Y4KS95gv-z^g zj?>q*C8m`fzq=k6NL5WD`ZP;eALr0Iu+-kJLd&1D3ckN~Qo+><$rMm+5jUvJGY#GM z3zhF%`>5R;fCX~5FI`)*s>>wrNgdf)|J=yBa-U-N)M0&tpx@VKMUciVAKo^N;AjI0 zhv}T_vh$KC#pfFH>n#OJmWmU>q{lToymCY0J*h-fWw=JxJ&4^tcyyRlmHC;>4C_#+ zCUB9oiLv02{qR#7qay2}9?_B50eaFCzNeu6elSMm6R~)-C{%-#z z7p3YHdFYp;6+#vjp0$&Q3oM@CVkmi3BkR!BmG9hLgIV>*LPmaN4#7Bc2=nN0xF$C; zDkmUvhRim-tXIbb3!}AiPP5utC?d_9rgmAQTdMxiuk_!0xx@NmjEO`zS~jfenwoS` z*Ro0*OL)Z8s(1S@><|}vsoL5vZ%MZ>Od zlqr0xa7kjdDXq){>1>Qt;*G4ulSY)HMBtEqP{L*9s!xuH&#PpvvENo|tz$=XpqzUP zzgkl4Z-z>{r9S6Zdw!OCe$L&$rz{|-cvo8ImwaB`DofAHUH|a@5kT^1nEkEbkhk}a zlkSI()BmPNKca8;Dso`CUG0JK>%7kXfflPgvz!!X@xD11jp?O9d!abxzj8We>1GW2 z95P4pVk0@azOP#8EWH|8t8K$DT_hE?i+w#FOI2#!BUgMZf3iIEkZ!K_@QwVa)uF9A zbyHG|RNpg?>+?8|^_X_&%gey$$(omh=-f|-rO}?%K-*E4y!lf!1(6paR`C4%MmC3- ztZc+T@vU^t2wKCL1mM9UQ4O*A&K5rJ(nS@isi z*iV6e>{g`O6C##cA~_T*doAesdUWt(hHl1~Ap0J}E^u9;OTU3LT!LoC^c$9F0|SoB z&no+V@lEg`c?ZKP93siZRS%!v1y5_AXzAUnSjn1Ubn@#FG#t9NZAEAPS`ovLqqV$nSm!O2T<5H=KkJTX*As>IK zQD-;UYhiv_Kb&O55I9(NqyUv5u%{efk|YmN#&xsOW@C zLNU#>ratz#Hp#>5hWbQL3;8pbJ_T>}QnGYj>I&~V%`L*!O*J03dFbSUl&uN?PiLsb z;#U#f(ov%W{E8*V$@Aj}2WVGNU;exSTg_wIQ(KYHebOrBf_6fUwJ`)YQ9J!cV(Poc z^3qO_T5oZD7+6aXhYx+?hAg`ara*&52BMisf#my7bYyoYrcY^&x)#~g?W*KTc$rB> zlp)-P1PdTKZ&fiC&Pdrr-Q17`Pt|bW+w3qNlUYaZ5GlRi5_nZ;uoCPa`C_t}cLL=z zjBnn7t3uTJfs8@zAkGk2{|_ zXK>yqJOKAPGihn%Emt>+YsrgAh}?2l=koiXhlCt@lpOl&qNFnXN4tY@^Yy70v!Ga0 z_0ojw0TG3&JD-n6ux%|U*-++<-VBwsf_D72N|+ryu5qmMXesv7$uWF`p(0K<)19x_K`KlVB@rw#4OdZ zeosc0tYhJ{-Qz=KOs~XsY|&q34M{RMMnLttS*l_sTcXh!&6(jxXYhC!S|8#^#4VZr zg!5578T){&ZYgH%{cg5;y4RBA*5Ryqij$GXT`BkDt_Vr+1fNwXXR)dJG}pDkAU|5> zL$MH^9D;`a`px7gtje{cpu2)c0{&8!*j5LgSLel-4@l1%OkFK_n`|DUThS#A#dPqE z#kg+PpVM~YEVlY%V2G9{+6bxYu#;%M7@Ep_8D9W;3)$3-Znf%2oeOQ~cx|T%Cz*T^B9I>8876z8sVF;!Oe)_5(oDUr zMcRgIr4G4okf5Sve-u;!z-G@d2+h5Yv*r(!CBhg_YkfvrUfI>p;JIgL&>5r~YX5e$ z4HTZlsQP}Kbunp-Sc{By2>aO~f}({_q}}kvfq6QY*%uVW`?RpNSL0`zC(y|22EXb^ z?IiOKt!MxHgx?l7gOElI4~eB(ADv0>$6QCi6G*7$Q!%#UUwx~qVnDMUuH*b1*4K&+ zGPsyYGtRjJ%_CDS9xz*N^|HFaXoJuP<8nck6PaXX4t)lXEPgnyW%xU+A6Im;9ZOAL zEt$uECmJ@tuvkB?7yU=*+@n6}h?gsiWUvT$EIh7p4E{$iL49~woLeH-S?xfMzA#Sb zJnFEyOXKYv-4!y{1ZyG^W_80uq}+jzjI=#0=Ud zihJ0bN0udQPSn})wMfFaJip~W=+ia-VPGcS*{3oDjt+VGxw{mOMOePc+TJwXaJ<*@I@iK4v$yo!3@48BrzMGl`<$@1x`3}? z1%5sYFNHU`KW24c3<*3g#pO4&FhuzPo+Y&1g~WwA(EYaK2Z@PoQY@3c{*y%_M*?Lx zh~r3+WLn>&1ANDr{F&0d#yRt>qBQs+A|1}0*83`a@^Mtg7pbtgRVSPy0TCkkBK}Ri zXFIXZF7`4~8??tyoto*DzFCUqLcW9~5ewBlNZQy*c0_vmWT={*#n`f}Gyiv5zB=Ex z6VU^hr_VgA2`0YmUnlkuf)?cK2~^Z!M5gyIA^%XV+B7W-cYkgyZPl3-#MrX44{)Dz zy3(Mvmf{bm30Y%28&5|3WLt#Oh_ftWXF$RO=k?<y918O`+4aP%73Ok>d(0fGQN=Nhi>73d57b&+x`1>)3D^#g*H}PU z+TOj)8s}`@`un8ibp2~PJ-K7(+dO4Lo;z_OP!7Oxy9uP1aMrjOAw^{AOZvhqmu^u0 z3m(Z=$cQx4(_b&^>;CtVUqJ%PS?0db2XY{XGMS%I_zDx>7GnI7Oic`<-~#BL1RnD* zqYRJ(F-%q!3pu%`YnY+Fu!-Zthyps9_%)|YR%RuDg~XzW7M$1%-(Ra=xtbn&l6(t> z<=~VT2?`C{2Aq>??;Zw=A+Y5vM_>RKN0u8Ue+IKcHnO%HC=2Sw$#3h7Z1CJts}7q{ zCs9pO^_WabyDY!oln7N%w2Hyy>y*qL_W6QRU>lLg9R3A&lJ=a#K;)+GV3k$=x?v^v zu`0@3s_-LMs1!Kz7g$eOxRW$`)|8Wvs3zn6 zPW<51T4ewTb>V4ya$0g*4V3XJ?g;f_*r^dhbNUML;HPmg{n4wxGW=J%I~`mYuK|rn za$9|(v;CyxT3R6@uw`ETi5q1dwO8@sl`?L+ZkPFRQ4B}$C-S_HJcY3(SqqCVa&UX< z)^nB8RPJH2T*{i0I1p-gc4R{>3{`b`t4CZuUxM&M4TtX21_gIz;s)11GvL=oT!Y}X z?lm{=`jX^xNkAm8u^5j)=$RcV*#3b_Xwm=u%Pktz5*=(4!sFF0%b83IVR4=eRNPfr z&W(GLiJg}fv5=r^)WCgM9zK7ttUN5`Mc6ehS_7pl>vogBIzd^nm1y*xrtU7Ft^@>E zS0Ssvj#f{SshtVRgw$yu++meyK&YOJcGG#=$BpzEP{6+LCU9_|AIMifH#$u0?DN*) z^LBjABi4S%n=X0wdn++UVQLb|Is97g*#f7Bon7bT59@IKSeEHXph66L6c-2;3Q~vI z3jPU|U%M6S=T-sg{)4_`E0KO6^*FprlKb?LQ<#dZ6P}EU?h9L0FIa~`4x5rJ+%`Ea zjZ1k+YipGkjyAz^=8sNMM#Dpu7(KaBM0g))Y6U9JpUzd6>A5rOQ9eTwcjdXdT5afD zwOkC>z@x6gi(OZCLJO&EUXnVp4#*dQ4yhOLX1S}o87dv7nnR1!RtM@0Q=2vLFyp|z z)=wPmliW6uf&bS$=y?MyzE-0dh|e!y!ArUbQ{r|bV%Lq670M%*owiXXjxuwxgY4{) z!j1Q*s*RmlcbcqKJH4whP3wjaiTK6+t^Ehupg-v8U$E>(hK~BG2M5_>F(CRWX}{X+ zsmPE7d=K&Qd2l3tSJw)`18wO8C3rAG(hfu?OL>Bpm@mzCzKB$0Ae5Wu1n3_-a7{10 z(n!J02}$8PyQJ`W#seuQaYr6L>{A@qoSvTd+;vxmhSTz5dAhfGaUagptH2Y*?8hf8 zvO5iN28=(jfDa!P{9q}tHc6y+Xx}l!xvXNmrkDv57NgOLAJofeUYU1D6D8KPk24p6 zwV@cTZ^MOuQk8Rx9h3uT<@LU_y|hWN5Ns;^BH-ci@nmpCI4nJ=^s1|2a5FIWx}l_~ zsfPsGt!M#NHv{omj;JDId6BnU@2)+E;c5%!Q~)-%t6APi1iY!NWgTpdq;o{ZxjJ|^ znMCmW2axRi=;vF*VBYjF>R3oi2BHwSRT)_*ewUrNC}gJnG5zfZjBvF4s_(AKVSg>M zgG}f?R@^fHM~HZjM#e9qHae=>mpB!66KpDQ zw_}wSI3W8h=_Ag^U;eL8d6leV#7-(BM|k>^jKm=HYLWOy203_#5BLbtIN|8&1R!hh zD>XkxocDfbjF%oWf%B*Y7}4a5$5y>=9Y%ca{@9`HeJ1)=c2Vz}3Cyv%4btgDC9Ny>U@kEh4Lx;m;pgQOFO+Q;YB-ZmL=gv7mU<=lh63+VoHcMNdJnSsBG;z#E^GgJ@b z((hxkOIl^oQI)n=(C~)-Iu{MTi`a?NK6iR|^KUibHVilyjFqpjCAb6(B4k{BDf z(yRE(=eUwT$9K#8+-plgD=V^bW>vGDInA11>jX_pC6C;>Z@DmOhr3Pi&Z{=N%F9pV;lZa~MmhT=?C;r#X6hbdXLnj6&Ujaf znk;|whD=cMMfiZ;c%K+qS|TAnif;g6huA0GL&((W&a_XJN~)_EZtdQwx|idC=!+(* z_v`5%M36fgm7<^8>f?afgdOUulN?>!L-USKGRygH$w(i55G8#mv~)_H^0wmhxk&M4 zVg-k2B*$}K!mJWbvKI}8LR7OyLe0vvm$EEkb~`U-_7x_u2)`c4pgj5%(yHjNi+Z;r zm@GZY*E_99w9iQfSvB6v?wxm$;WCIte)3JDUpq26Qb%us^J4?en1Gth{oEG9V*FQ!!UsCNw#HY2_KHx zT3n(K-#4F4^PdmkjHKxSOsG;5J8~x20-4d_b>3`kX{T|mXK1{CHkDTsLc)8a!(aEQ{%Pvg0ggzGnq`S~O)3x3gP zw{5~d@8OT@vBH5J8YZ}}32uxv$fL9U`h)X~1R044UZ07AI|Qk#B1U&kCG1wL9E-2V z^ZAJHW2|ql9}g&st5}kwOtc>dNrQ>L?0S?Sess;CJKzfF@~ah3E_9FkDh7n0(Q+n?B?q1sA-o4Ccxq-^ZJ&mS+Zs_#MwZ5=>>pVUu{OyExq?LpnE@jwDILw}F zRda!~00ysm#a?aTU*-*73 z>%SP&a_k$2e}SLOL)_-_F;pRI5&g8}9OW^d-x00$qqJ7}`TPgW$p45( zp0#f}Of0_cN_DZ;v(_xY-EH_Y(yp<$VWlrNZwK-pvCf~CaAwEpd7B3~UxEf6{=!vp zpKJd`4iv#*Yn#=>T?9;f!EoztkFyL2xkWBnK;shVyNp0i2!FE6Jn$dt6wkKN()1-} zS`9hT&|CnvktHDLc>X1q^2m^m#B1bY_pf2~hWbwW88?f6p;bnFL1(@*)JKN2MI$YN z$9gYwTv_EQzonnBsQ5+fzmJcZ)gMumpJ*JVSdOz=&rnstEyTYhsQi&fSbh6?OtL8Q zm^&VnIFOwkWNV#R?QWFQ^jHao+7>ek>4|zy$JPeMrck&53lJhz^_Y*eXa*Y9;{-t> z2axf*MEO*{g6BP;$5+8&ID0!}fST8tkQytD@K7p`Yvw1qbaFNxetS4dKO@MMUwyT! za;cM1t$PpKqLagXuS*t+YZ3lbM0}v;mko168&<3oh*XAAP#MtZkF-RenIoyY@rnv4 z0spfS0kUdfcYN!$tVEm;(LO4V}96az&drRqEN%)(!7;6mXJp zE3epfkl%}`6}W$l@TXF&AfHIAe`P@t*;3V~F~&R)d-sW`y(|DgJ}d2+Sqz=c?h{+~ z-a1tsEfe2wnA?624*R?@JkUT%eGGcGd1h7L4%29HE|n`Enl8 z>@IYc={DqVXAYGU>nQF&e;+NIV%)P8do6KB^Wo+@r0l~gg=$*n=MS7wE8*Ek`QmMe zP3|a;l2{&?tFXzf8Dkqj<5{^n{J;|rg=`;eJppm;V`?7 z#oIr872a%(rVONg|0kN#=h?Y#pCXZVlDAV4_N3T7+6`oJrI*4XKciecf=#@rCU+AP zw|#i@##Qg1F3qDcgHuMT~=qQ&o?tJfgEys$$05>7Mhes_kS~U%5ZDO!WFxd%? z3zLB8ZaeqG#m`|FD&yTy>yaWi!foZUF~`JNzPtRmqT3(Ew$$Y|=aJA(zti;fSbvZ} z>9MZi?uNoF&FP?aqk{PZbR&hHomxmVY>1cUbatjR0!a9kj0}X9SN5!q%qe(-R!pGU4GZHv< zIVFIH3%>}r``q_oGoRAanNZ7`t9~eoH|V$|c%@rbo!h9&;S?0Q6k@k|OcB&pQi0Z(?ihmLh)S z?0uo}zReI(I+KxOwngwbo==XyU%NG3 zXCs*Fwos{r&>$L~`>;4pRhvVjkQsPdR@QATMP;g4C#i1i_eCX|uU@;1{Onwf#BvSl zNA%oB1DYA}o;%kB3w!*;UX)7M>QMn3A*~!Ip59UL-|xkd%updb5GOSM@K6C%F0re> zc?K$ogS}~?h4nh5jEQ8M0UN;lUpP_yh!UN-oz7`R_~dZF?8UO>?%J@+ZEs3=5; zAL!jsf&}izCZu~{{SgJdoqGwPc}{oo4pW|%ln0*ZnUR(|9hV4|;78dOQ6;;}0gH=1 z40Pe|Z(dAA1K`rNN-@PQse}HN)dDbv&K_UjGHVwh1YW?Tivy!Ux&5t)MAWZF=|*R28{ zU0h)`P0Z}oP^lhT%}+XqK>4ZH*02RFj%RSA$@=jJW~Z?qaPEc+&-M~>2HS;lJ3?-9$j@XHRZ}(Y#Xy)p57;CX=%B* zGJYDp#J;w&t-kv z+QG-J#Vq5K@~Tbl9pWG88_X(JqMn?O9~s;J)b-a15Hz7&oacaQ+zp`eDuWv_be?YV zj)RH_0rT{HBLbxc3cC*E-Tm%K5O`~_mu|67GAjE@zfXN&|uQ>E@ zYQbAkXK8!r)X=_hU7>=wpF?m0?%&GsO~%x}{q@t5KBIVLt9l^wB`Ui=j>N0v4b-&V zAjn)gPglx|{CR=!h*X66CsZPw9w2ADt0qYKN+ z?%0+mZ4dGCsFMtioYZN7x!0=bnCa zxHNHbf4S9c%c4uydVA@>+5XYAEQ!#QTSVI`YviwAs~OAA8(Z}9<$QfTq5Rd#A5kUx zyEs+2IBgWQkIXr)mz4OA|M0X9KFIOGy02nPO#49Yu>ua!pKRd@fYg*$fY_?T2m*KZ z%bkjF6u&Nz0}xX}hSxGrp%Q1*m!NVEupLXgfj9={`xLLB<_)^~`n~%k*iu$CK6Ipt zbTMm{Cij*lh3@eSN_iv0v5twmdtwpjdSX#O{Xtfnq4R)cKz)$KcanL@Q3I*&*ifIV z^$VRBgu2GR0?kPe-FB8dx0Fj4#`YioVKQZ{#|SciVxI4z=ZrY?e%N_>t{IwKbU~wH ztx);jJd>mqO0y$_U#YVJ%OJjOzAN}i^U0O7&s|+F4mKss@3`~!#|)MGbeI3Oo%lO+ zIPgH~OZ5nsXv+MkO`eE1Ai9W$ZecR;vYSZ=j=P#MaviAslqr|Yqp|KoZJNIkUc0s6 z5N_zic%~JG?ZhPK5n^omNGe)9)LsI$vTziq=NSz=x1Yck7%=qt65MQ?sj=AGJt*J$ z@?o3a&h^Co)bI$C%{n4>SRXnkk+Sj@v$p0!e@BP$M{J&U-p8&I*!M#pr}+6HHQkti z{7Nlb^;&x#IpFD%`MLAf>Li!d-8N#`f|Jc9(z^iAIc~`~^%8zq&;&8ha}500;UiaS zY|D)`8RBjje{M*~9E?GHcERB!!BxKk8*7nBI@&&2&~jNEdAoh=XSF&4IhUA8dY8?( z_Y+>j+}1A7bK8l;V!$!wd)qRyV}WV?G%CIa3nRJH7+M3UXHN!?4Ntm(nqPx0rAsVi zjTJuTi1%U>addR!0L7*AO+ZGvbxlr2gZvB+wq%=5@r7cAzMJNY-WH&F}*~{bcYGU8l-QKS_ScfR1)=D1L9(9!6Hily!VR##RS|NwB6YcbiX- zA*)089+$!T@rOlhd-Eo~ya<`=vwP-|^A|ru8aL&2OlHRnL9z1KDzDC*@bI(S;~Coq zt+rh%&RvDiQClUR_Fl{12wF44;awNpn)(cxHfwf8!)po^L$L8pPAjcK4h27VF3C|dk+GMRa9&*z{<~FHTki6Za)Mpm zpOur|Hrd@z?GZx7@;vvZ_nvOjV)41dQ**=2TGtFiI~HHJ$O_YAs-+?zC)RQSh;xBs zdRrj}r?GD9N_O#ukiC4-;6or^1YU!GHe!Tak;#5#l9}_If9uegz13OPzyMAX+Qe=S z~Y!CtiKU_H2E|ZLe`$dc;tSA1I^@mSmnwd)w~Cbqt6jSGEc~vO$5ffJy(o+ zHWHYpRYiyVAGbWANG)yk-@$pw^9M(qnx^6M%8jUZsG`<0YX0gux=v{YQ*5rQ#>X{U zUty5;ntSBeFa|qGy_w$ER|{j=29|9nmV8OuJ$UpimJniEDBvd%o4ib!nfA@i_*-P+ z1Ks}Rp8XJV@(vE>hDKo0M+{(F z*{bclrOwENo4Rop`UCd3?9Mh!p6ffNE{)9@REnL=wVL+mnveRxnN8!5>kt8M?0pZ# zu|)~F2aoOD$1dT2^&~n@*YX`W)G%9}#EqS*By8L{uWR_GSlg-WoiH|jd2YcU9z4g~ zkl&Y(`Tywp4tOfR|M5qPk0hT`h|o|{gv{(xMrL-l$e!7*aa&4-P-K(6=e1V@*?Vuw zx~_S-xW@lHSE}##`}?2Qs}FrT&vVXu&vTwDtAg;~kq@W9$#)JqNZ~apa#fi2-~vHN zGRzkU1BuP!!1F85W*gv>=cj^hLgmuZMP{IQ9M6b4srCFf;@=YxZzm&yk9Cnc1jrxz zZc_p1&6`=X(N|j~;(qM`GUy6RBLZFfD+PC*lnLvX3!3wEC5!Eg{|)sWMifAG^9XH2C)#ZN_e4C zA#7Hv?MmSbN}f|GXkypErOd^)rbIsa(S<4g+dw46Z5*N$rg+~Rae4#L(ZdEXx<4l6 zAX=o(b>NG`A3q}XJZ5mG>v5C2OWDb4Fv0Do1*FFY>Gb~AXwV~WHDai`8vKL85!fWH zq^Uy!tObm}-UmqrLI5D*P*ctFcvw)*6_p4RjTw)}+KfYXoteK0;3}xX3m8Sm|IpaG zJz!|RPp^*ddX@k1>^0TvO(z-i{r1<~QW!!AlJP%m$MOM=*S-UjQfs?i6SC21I}~BL z^NDCoSkcM-=>Lg00;>8w){`(LU#m{M;a}?^=Ytgaf^MUK6ZjN?=j~8ut?v(K!2nb% zqXf;%C-b$*F+YQs_i|6Dz9Np2?vf&XhzZ{uxn*%@Pbdcf$y zgW^FFyh27F`v;!3YiBS2Movgw9;ub>kC4Thq^LRsnt~k=NSBE zp8Vj6$tG1`VL!Zc(koAgF=U{YcQ(?n+|TijJN!Hj~hN^(^x~%|H3aJ45TUN zFL+67g;Ea_Q2LVsipe#6w4JRHO&{!M+>T?jyuLf2%obyHO6#{E$A8}k`zDkDOPWFb z%3g~)Bc4+AI0U(8zDR6R> z-fRB7gbz3ps_>xdg8G!zvMyKut4{umCe-iVE6FgJ<^T`Jpaax33_wG2AzpqVU6#us zjS7wK39nui&vmF=Of@ZIJWK!)PV$@sk|BP{m|>$upbUDV(vU8$g)!(lf zx9~c1(77(lGm}M6KR@G)DMP+si_mV4fJw9C)Xs0_2PXlEAtf@I+M{Fp$~H%J6{C=Z zQ#7%HywZ#)wW;eE3)#H3Zc0s${Dz@ccb5zZ{gwN*+qPE-yC_wkA{l#2WBv;_ka#Mr zLP|{2w*_%;Y!jEC|#I z0$TY0gF80(u^i@1g>`hYNf3tacU$I_(0#E$5eY~=0a1IkW1pnGL+ zjJBMB6oz01B@E=PeatYQp{fQafnbSdHPMc0vb+p)$Nn&g{RL14kpbZ?FAIQ2w2_L_ zjd6?mqN|>3h z#_6@vLJA1Se*qm&aP~HMw|B`|*f(sQz7&0+Orh`h_BF=GJ->a0aTj$|n0K}*UcKi1 zUkJKFc;Wf_0cfA5DeB>S;j@0Bky;ZnzZQj%!uw+B&Ta%1S95|YLv@NJYLyq-8``9w zWN8u3`vE(9`{MyG2`mS%zB5AV1THCd4i|y8^}Xj_PK4^&J)~6ljd0_A6f&<_EfU;? zoMLsBLEg^sMwST_hj6OY?~BHvyaw8Q0P9FfZ$2;NqDl~#v~C~^9$!j-iV)%w!s_o{ z64-Aa*ZWlIZs~)DzHca9{Z3b%dP!8@R|1g;qXE9lWvZj6Q& z9Lw%gva12yEy;G;=y*?mwO{otnG*9$06n8-zif^+TFaX{kBe9| zw%pg(gm)q>P5`-#Jvn#tD)0yR!(}LsgV(o7;e_+}y)Y{Lbrdclr5h18B1^Vt4TV}; z{pE~}WhTLuScHi+WW&subzp-awF~wMC^CsICm45_D z?^FcnxIbd=$zfqTBU4chfjVw7zwMh6=j1LCux5iJ8pm|4*vq87SIeBgQ?FUFq}TZ1 zIdLx7b5y-u@dH}&VDZx~q@hm&y(}|{{pz_dsTt{|ml-POIMpy#mFPpGAJ! z0*6;ADC7KavUbLgqG0Fvh)hTz+;{NE!6HhRF1tgpl~ngSR6N587*(7DC3r@qR5AE^ z&`PrddzZBPlIm}MKgYkXGe({r9drI{2p$Fb(c~INtuBnDBh5cV(_|1oK~xCuk5wi} z2MC4%rxvpgKxggG9o}|yWAy2g8@hh51>{w(cG!4D=GZ)#MTBt40kXGU!<=N)dLPmS z4gKZQ-TO7s2|Fh}_p=ZRJ(ydtA@N3#{0P!vUMTQALgcsJI(3o2n{vFtuJ!%&_lCJ! z+knCmuPP9%$$mineQ(O0Rylsb`M?lBs=mIkF`m>Fb8ybk=DI)N#SZUX{KZeQIZ@qG zC1N{&PoQZ3o3v*vLlwWlz7s5V%InvRK7zNzYBac--7ggptHU^@U<+>L;i z_tRE7R56IoyUXdJQPizMn@hk={$8OG9p?hj>cu)4o|r*0COPrf_GET>0OhdXRk?kE z(`!+_9HbIIh!Jf!b6W7mE6+z;v%AII7$^V>xhFbr8R0_YR0tPneBSi)Id^O`0vG8st@Tz3DB zyqV1Xuu8W3d!Kao^*DL(FR>Z}mxK#uQa4Ad%62|)pcIGC3Nc1BmbX6tZz=YX$;=i^>Ghj|OJNinx(`IOMEV{3BC-*j9 z&bWN!x3YI{gmr{O{QcGeNT)>{mZyHLsK<<&KtQ%van95L2gYT8&6kBWe_SAns5s*Z zEKYeSS$Bi`$%B52B6&qiqKz!{mm+`j^OZL+e*(~rE_Uw-nNB_##)GDV8r6&Hv}Qmx zT>bPRWVQNJ!JuFNrb3*Ef=-dJx+1^qO|YY1)I3fG8clp8F9H)K!R@ddU$ygrWfwFL zHBL$?=+JBEJ8Na=-&9*)2Gc__0QcDx(dTDABpP!F5XyKDtmd!rvpysi?3D;aDcg=N zV&(jzyREny#qC|OZ#0D-RS7D9PmDEyp2SGTfiIE;`@x}$?9Jb#S7L-EF$_`= zZ8J4?TYfkUo2MdpnFMPlQSqSP&T5pLWs8_$<`T!R*^p`^850a@{13Rf3-8hrQVFU` z)o}%#d34B&>!^V+(B&$9Z`11Ffmjz9z;NK;TKHcB#?RA6cWB_Sh;)PmKLV+ej7FvJll4!!r`1{!(DoxXM zTiRf5r_Kywlq_(`3U+HQ_)GkR_X&QHbq{U%KmrGrdQc#10gVXtwv;xtayAH;To}yd~W16{{!~!F9f5iSmE|uR( zRVBf(+gWiLb>rM!ZjmDKJVsIdYaTd0vQGuSQWzPW<-3~*AyUuhuiE~s{8fA(`*IeE zi#JDS_Zi@Jq1B+s%*8u@DK=UX*x(=Y3+~On;@PUM4P&~EDF9Tf{Dn7yCsr+8-)Ys&*mh17NQ$VS`Chh=zjhg$o> zv*|oP(mVGV&g&dEbLpt`8fi$C+-}v_w#$gLSYP`?!N>b}xJ=hyHQ}|{Lps?Zwt+9+ z^?&IOe@q(rN}UPZ95MHRe&U)&)s>e1;w0M`vV%3>6U=a6hun&1ji;H(bvNq>at_2FMrA=PIvoi9FG%QG1lDO?O^A7=*tq&TNR zY^O}~hwbhY z>G`!`quJZR%Vs+*f6C+=Ybf=E`OnQ_h2IDQMp4z5NC%4 ziVz~pS*{b(WtS|I&Gki-1OLjX?PKbDgw5r!5iubSSXkbt56`L)+fDq>>sCP7i~uTl z58xF3xxb|I6oD&Ol34Ocke!TCfMB#50Dvs+pgVue-Y2+^vadsrA}xyR8(@L~C!E11Z=a$o4i` zERg@$-XxY4Qt*sTskerePFV(_M*elC7VlhBwb#~b=R00bUo~^zDQ>yyA zHrIps5`Gua;{6)yS2OQ)D!6jp@DkJ!!hOZ?0H41e*cU4y{KxJWJw-ypggWlA_yF(8 zkz#aQ1=v{-&;JT*rZ(3ZP{xf$cqW4u0FauTkHF2J#hwWHtBC!UBv>3!@kKg^5Ib&w z2QF(M?F%0bF5F@=tf%{5_IMF0f}h#wcL-=k6%uTVk#(yMqD@LOFX1}8#{P&GhuJT8 zIr>@*!{YXA{*7$3BdjnCB2j`nC6_h%0#A*^hi&AG9X#;%5MdjB?iJM8?jvMjy@{}J z8DuzZIm$2bYgBNyi0$UwM*IhmX2-U`<88KZSRRj<4&C;G&3TPTp6T`VW*4t9Q?!PB zt#Q2TBr8@cJ$QYaThF5>5Dqd@dS4%L{aa}fblbc!L(1aU3^Ax$dJBlygou8z2;XQK zH)CWNq89Dv&aNN|`hML;a+l|(W6l*zKU#|?D!wnaRJG^+d5@mwB)s_k;5u7g;2p>>!pX21h{^Ub^X9Jmc@xK8Cu9Nf8t8xKF1%Jk0y zHOSX>{mIGv5&~y9$FECd;L|uvx#+jIG8-}JQ^u%^6$$opFQ2Vb^y{ryVzzz*y6N&e^4{yY_r++d1$IVgeebu``eitT*53MQ(jm`W z)~~RZ+Wvvq8;>0aS*a3dy2Z_i!N~@(t>lkUi`ZF5=zh+jf#MlmFG^&OvX9*LEzn zpMDy_{}h^NuUHN1^_)lJzF{bvut2lCjrT5@9%IM8Txmu)TO=ndZw*5p8?Swb5X@^@ z8PPT&PRs|iHbCyz$*|fYM#Oe$L?6%Fe|2H1uW;@h4)``puO8w`2Q~CyoF`Yc8DG&a zxHH@I?`i_AB(^*d{-_z8n(tnIs?t+algxAi^_1e%U8~U#RXh9>;(aUlGSkU~i|X$k zFI-9Lo^4$dU&-!eZN2F%@8P~$sDs#UyMGOIU%hu@`@I$MeYOMSxLbxpO=P{qP3d`0 zR+LT9#Ar`Efv$Ap7)R)Kqi1noAVQEtXM4x9bCUfrrpiW><#nG=`_ z9Oe|1BsgF`5ZdYn5-x5mOpI$=TT zH`~eTSC?TSinS^;)n0C(v=ublz@=8YHu`VW1bAJX8mM_z?DqZyNL+2FN8iTRy3B+-vjp=bY-5MRGg*p7u(2I&=B{}>L^gMJ7X?_m00Vyaq!UYdGTOf5G z5%(be)ZR~FT&a~+YHZa)DIwCxTLTr@r?ra~{V`=YvE_WNJ7--s@&r~>)N;!Y-72kH zFPbQgD4fbbE&LXtBRW11JUo)STL>6l!LZ{ zNB7`BYgE6Ka~DgGt6}ok6k2X;8hUDZnQjfvbxsuNIh&lVe3-{EefR)DTSiMNZ-HJk zU3+_;7Tk3dlr+3C6tY;CRL1C+Ip|VngdY@J+Pa^fJkb=dQS-=@@ys;CXiSb$xbtMR z6s{)3x@_`E^7HQ(E~v}%Ph^1nKG@h>-`e0fe}w@*Oa5Uh{h`u}g;t{sW$UPDSN7E2 zi60k3>L_i6*+v{^Q|+6=XCfrggFGlrUCK|Fg&RAu2l-3OX`=^u5gw`e!F11u5z5}n&*SiV1HiL9bJ`Cv3bDzE z#waog#%uLPiQZqcK4G0^DYOul>24gCq;@JoPvAFOz~~mYA!HtqhILlNc1`h=+eUT> z`ZDZKsoptMlpkwR|43V0Xdy#~qJCd0Wz7A|L5`TrhcxtOH89pap-j5znQIKhHX7>x zcJz*NOKGsDb?i>r3}auaX_XXRnk@u70}}?cM&rb?Z^jCZ@M<%O8g(G+is%bp1B=Be zCyc68=if10i|rNp`Yw7vDY@5$caDZhcdq}_Nfx^K-5VRbB@9r=@jb?tD*R2)m2K8i zllsFyUmo&jWTKTDvN$@LplUq~;GJw(;mu-mcyr=_hX_BH2)LL)ZF$NBW0UjDiqDwuugB58Y1G7OdL{QrS4SvIl1bi)osdy z1DS)24=gR(pM_+7?OkNC6;!-?{rZ)_dk96xB|nn3VYC%3KZEn4O#Qs|Tt`%654zvdBdVu6vAH$j+?6~RtGtb0nhiy~ zP`*tx9i#DEmBCQ|xGstUG)5Y-nB9OPmr|C=iSf0Q^ztvf@xm3kdX!Zq`n}P7?d_ZM z0)27WVwLAJmu$VgwLGh_nm*@;x5q3hobiJnXyh0hoIY7ESM1^E+V>W5GM!gnJ9XaW zcHG>y&pMn!RBh=ZQu4rBgsT&e0T3wa^~GtA-t2twfFh&W1QMX4SQO!Mk*K4rEK!92 z1YrSeYu(pO(lgE(&uWSQRJysRdo8bI5ozmriq1YuRzs(Uwkpe1qH^DrJ&fjs@FHhG zLh;Y|&8aN!5-F+yXVtd6ax^Yhs?I)f*HE#x#Ti`VAyWFd>gUd)eq|l#ebZI6aZViP z{E*b5SCN}8GcB(;a%lbzR9yA^ymjVc+q8F;a%c-fGLzSg>Wf3ql>y$qa$@KFB^&Wo zCPw-~1MG)G@D5wM?~Ze5zhv@oh|wGIlJ?%2D7nhPgB$7^>QBe*{7}OP_uZT+^f@oG zRI67}ycWy2jSUOu{1P^0nC*nCU295m&lGD*W1wKDdlCJNsLI5jy?vYPkvl%)=mLJ{ z+r-GWh=Fq)i2DB;5`^prU|O$W`6L@Yh~=b@*Iun2yS7@qAIf@8@H{7XsemH+<@d9z zGzy(TG8c6sqzbk3v(=m*_t76ONKNNY`jWFI_9R>g;goan!mQmtGqZkcJuJrUZ?q}h zsiB3%R0^l9&tip-5;i;hqs?>zscsKk+Pt+%)(d@Awzdp7UMR)3ShXvjK0)>sd;5ZO zKLuo(K-4$cW-l*WRJqkBIE;_0G3W20_le79*A7+Rz}{O6=_2N4Efrt6 zQimGo?ECOIqH;Q-e^PdBw3n@IsNqI-QfT)>GTRX;J$?PZKn59cemGi#Xr1#CiHhSg zrSx45K8*BrzkeJd!Ei#PtmIa!wRszbY0M{~tdCI+hEyz8nYKkJZ(&2T>CXzy={IN| znqywiEmT?etZE-mOG+H_T=x^%8xTF1g=5R;!scGe^5^~+(0QOmGIL>s?lNb~MQ5Me4QUDZ4^vw1KIEdENFg4H6aN(KDMq8{c zy!a5Z-uisHh-W6o8+8GL;qNY-O+)Cn8^s9KVOKkqPC3}$irxJa*b~sx#sudwekri) z#+oO|B#K1KO{#&!`kdcc`JfvvkSER`>F|1$s^PIh0ZllCIQwXS3O$o%A_={9ph7yh zD3+#ZkeWim-F`6c?GdD?jonRS_cv^zm8Q#5u_-z6=rf&A1P z7Hpjwue*awFyC1-71JM@lT#@Z!p+%NJKZ{^(3t$I9X6qd-|2p`#}kPL+(6dl4njjz zYkY6%6=~<1#Uah0kVT7oLK$0IEs_yNyi;;eaY?>Lkw{(-)~mfZPMb+9UToCWf8{9= zjY){m!{a()9k>3(uz|D#A zJodHi^ZIxD=0~@x6pik!2vgj+e9~vPG)vuf!KNc*%h@UBU+FZ)2PtkJ5=)I21mqcY z9fxqAjwj?aAC3(dM67L&W_QH-&y(%l>zMOo-@?`L&p6mdBynAGtMhDqgX~?2^4r=d zX(4T!B$JS=O2Ukh*>(VRqPrQdahB4kswDXVzevu#(c;I^mD@8~nd#>8rNaxg*DFxT z530PJimpcqDeT#Imj~;4L;W06)fLQ!t}&1ex;~R+OpfO`?m=1AC5*MkqM}!`Vy|EX z9x>bg0na`vQPfq0UZkIMxI8~k&6345`ws~LA24e6hky?uS?a@(->hX%^F>rKD?7hH z-y@x5jI2ff2natQyYLRi1XkbL(kpsX;BR?5a#}(g2_5 z&vuj+x45QBb0xJ%L z;#zutuGTT_lnzo<2c4xDv#~Ynt!Txxh3~Krc&4ltt2Z~~c{Hc8b>c%+XM;*69qaO( zvUs^*goW;nB^DHUTS!E$7dg)6wnoJ(g{PBcjP!o0Q(x$9k%+Qbm=jq*JUVi|nNA~( z+~jTh=JhJdC*xVYzEDo{-CGxOiwnD5Qp!eo5mqvlm;Kq4cx+}qpGK_pL{G)b|B%}OE9xsFv)`|T1F{Wm@Hw(aXa$9L9IBE&X`Sd5 zNi(f>2Jomt>YToAh4byq^kYhYGH{a&WdWtnAyO=Ln{?nk4cjfFLC?Zhh;2lH z(c}|8ZMq~fov9iQ!`mi-1dmshl#!RUbfmW@oXbLNsSC- z16J^yjpAl+z4jquH%AZybe9;y{^bZ)@@?76evSz!u3?{{sF#A>9Upcwy?|lo5GjyU z^jH>t@ytt+jz;LhRLdZ6davPl(DdH@DHw{L+vWY#yO>q)?8WwG8pTkK`lpA`mRf5- zL2R|CM94F&0`0c7VXHnft{9W~)UG-;^^m}YsXN3u^`?h_?#Hn3qfI#$3PcLk^mx9R zJ}%#FdLDog)fU)xow-^TH!n@19hHB#>B*799fs?Rr+&%Y{*T|rnJAc|T7kd3pCa;D zmrYS>p*&8sXt=}P8$0Bzd&4$zN8Yq2x@sYjUwM3iFCn^f3jR8A8zf670!mquMN26bgtcebWg=Jd!66K za^m}!czsK>@7zK%A9}YJrzN@o*uZl-wRvj`F(t?)5A6upb8yi^yQ|^EXDIgWoiT$7 z?ZgBTb62c0tn(`%sbt?5SAA57bA}zNXKU;p2Wm7A$3X-e^9Rg2LMIDB3Nk)?&x4l4 z*=<^FY;w*@%g}b@N6>W~g^F-@*6=?OsKO*QAv!^Say7L8wyy288@iPS<$43|-#c`+ zfJk4c_mY;nR~5)PAuiq|Yl$l|Yyb9m?b{F~yZ1K!?niB$!L3$s!h z$p3KM3tPXMJo8pX(!xQvtgr`_o|P#ziZF?oo%~3~G{*O)HQg7PW%NDpj!~Yy`DvDD8N7h*<%Ji{G{*IbN*Tj3 zyrExOY?jlA1kC=w@(QA%sO#H#OppSDO)h<9hBbrho`%cW4nT;8$Bj9sD{`M>#$G#m zh!Bab0Z^oNkA)zOwZr@Ztq@kX06dK*>nle1S`@z3r-S>H%ensA3 zyU`wgl74L|0>2i8V{Ze|N(1GQvm&CLXYVo;SF*?*J`V!NT#;z13yl0wg!wo|?-ddCpgEufe{5-GW}A0L z*D9A7czA-~-XrOxzWyH4@*9YD|MF9~d4W3bW5$A`-hqS@U#lvZWFj1Z+0BTghn zQSgy!U`rUER`T2Hc_Ja9{zs4%WUjo#?@DDc-ns4u15qrNqo>Bc{f)vo_;qo_oqP{1EsIL~pc0AE-o*bAC6|^O) zBx@&OwDnuy5iK73=QgEgr6A^SJ(fGT6cIV0eF62bFF1sDC@@b1~B|AZsXQ1>tiZBi!Yt%qc*Fjf&AbQa-X8uOWPfg$DbgijUFE!83z> z4YL(cWz_}y6E#wyX`gsT*SMbObW!=C@q2wqF%`v~AC6pWVmo@$&#lZr@~R&DzxGzb ztGM`WgOylY!yuEf&yIH|uQD)0kJ7)Q@n#Mvk7j9BO@HWk`VJ`K zIc)vKwK(p}tY@*7)1QxfuJ3*T6QWm&@!_SY>{M;tU=iTT}Y{i6Ys6f~C7O zjcd~!k?HmEZ_YlrQ-iM2&%56gPiIWM`A1`b-+ue&UcpQmMFUGAuc>Y|m+URtUTvmi zoxzzme7w+{$<|FV9r;kmibu(8I?Qja(BE2(E!vJ55>{P{iq<17x67c&$*e0|pLF8Q zEd3eRy@jc3ImdiBvYPYQ@b=4Yci<~o8hvzQ&MCX{Ql;DmS^z5js`Lpg>Lj$V;Fr!L z#xusJux%rFfvaLQnntB?h0oNNx?X+?ke;atOz)h7%Gg917y|s#v+x$C;7EqS?Y)@V{sTIRu+M7!JQ%p!@Tn0z10@R1_%=UcwlE^^D z{ShLb(cK{?OQ>R?)BcGSt}l&F<7-t=$>lC9G6>=6{YsOT!-+U&)4OzD?!_wFsA_!pBp zy6Jl*Y!^E5G>Y#=pV`HIsJ7R;;)YKBKr)s!^103h{eW!{B)t?CMNkdv_CEI@*X|LM z;q~uY)|NB0c4bAaX>EX9(Y2wc&+cfkE!-!zLlXA-o9mE9LEfdu!Cz^=G?5^w6!;-i znTrNDeC(~fnxiU8=Mfx_c(&hszV!C%lY;0|m}WageIZw=aEf;d?w+Qd?IaJOm(Mn| z=LU6|>Y4^yGVwdu*AF}KLtqEGxYb@%QEualGYqZsPnkty-qXnKD!xAgyk*kCi_dJh zbq-bU;kS=t1p3VJ0t#Z}reCN)U|Y#l1v29rLD9oQu`au`qlHMb|ec;dCq0Wti~IM|XbKI(%Td!IU8%+Aq1aZ6GeHzhavI1?IZ) z@!o6Lbb5u(7u?sBZGtha4;8kWc5M4aCA0V;{(`j`kR9YcJ!ZS;I~zi(fsRv*Ni?X= z{wPJhahOo${!JxlhR~A_`7n6DekXI)lOo-7{5^;qhjXo>Kwcp9VL*z7HUc|8MM5zC zPHTsB1<;!RTpE;M0ryr(l4_Nr#>KUhlArQ0ACou{Y?yA9W8Co%h%0Y)cII62VwUcT zegf_bvY34veG1|`CgEf)GN9C%w9{M{E?TtU$J&nW+_)_UJi>#OAqYQ4BFuTwZMPaeETXKp- zm%mZ@xIY{@JQ|7Jp}gKv=CzTRD6UW_eU^+Eg)^QqHJe>fLmds+#brrEZOt+D&Z44H zvlL%GbKE472$h$cDbFoom^rldrncf{O!JR(2;Gk=SH?7=o7YEPjtnIaazuQ{bLvey zT^51$9W6I^uX;-4#h4D1)YeM8{@Y7~Kir9z?$ML`mzR`1plN1I zrzt$^XeXKa=lnVWA%rE?=1s+}E}u?*$>6_=xbkqq>!zWJpct6tQW zeG82Ie(@Sko6Z3t@p444L$oL2Cq?ylb`Be%6xk}Aa#FIPmcWdL%x-<=+matjQg@2> z?4t^K9X}2%RwS#>Ciil*qhwi9(#oq>HatHsf@I$C${1azUkJVSw!0O=WHh=qiDg`rO4+NaO|86kX~-tgT>8L*1q!s5|nj6^)rg5IB$s|2p-&P@fcFEGpyfRIS+QL>P^yg%s zTlCHQiaa)!Pu@SFLq1~(dfsr*3ji|Se%IQkPTd;$oM7R_a2zPqhVkv}hkOIx+~;SC za+Lq0UV}Vu>FPBAdd#4&;U7#g?|e~WrY_>OnV0S}NqMOt>a_bl0k+aJR7;x)v7^aB z+e%5vK__b5Siq62^HpDNRn4NGMJ?IJfHZ@aZN&Y!yf5RM`0BQIS7&AmlKFcOHx#bM zRgar~pw^@LOvR#0&tI#hy+BxfzPOI099S={tY>Z<)yi>YE$V7 zhZxs@ue;TEQl3#QVYDh&!{xg6;#QxVRCsJ_xM0ItZr=SoaB%Vi&2zO;>Sb5Hmke{S zW*n*zvXq`%Z0z#wV-&{u<0qlxNBoZ%R;^YZ5k$E^hwBWTbu!6B0w>>~r#Tk7KwjSh zWJ*fi14KxVY>UcgU+GEhzUcV#)4k3~92x1hpzYQSQBj!seYixBDYRGcxr0{1ZTvLH zrIS9}#Lra_pX_&*`mMKS$wgjY3L2hvU;EnKYSEE$+jBL|4LnSXyF94a6z^=uvf)9u z#QPsrQqJvPDUo3C!He^>kQeSt!>zAXpkb!}!r3J>H;tT{*A=^=-b_BW@Y8}fTFM)g z*&~&bc=6gIXZW?>UTu)wTFX1e2gxdbd1tfr)k0(^aaE0WDu(=>wvX(0?x96N3&tk#G*M1fbScD9$2fUN67mPk6MSebbSka z@yrINXsV#>W~j+8n$xhNnZsg3yK-&QK?mfFvUX-I2cjoDW^I9UoV8a&zcoLYG}jo~ z^4L9`r9QES$PB(x;LotTU@JNd_bD3(B43b<6+fe>4m^AGLc+CSlhNJg7vCe@)Dl@< zcwYk7G>l)IzQsA#OPM94c6U5@`i3f?347Xg#jT1HXO06vL8&NY(W(K(+_&rdox+`)Yjq5jKbI}sT{KHZb;Lmm}0!01+7eK;9bj{l~>DZp&&#$Jc zXrt-Kpq@fd;9b$_VRH!^u9YJN@EuhdTcZc_4- z^GP7RV=I>XARu!fJNgu^6FHg;XRfQNOl`C>b9R0zHzqTTGxwTTy^wWzh*bIkN|POx zNj9sbya07kpR#qi>abq%Z~l=sxtG>66I#U75sXH&F|1m8>m-AF{G2!0*jj?K%!I*> zMsF^MJaYdJgAL^!Thj*M(K=_mZ>y!iQ&jt2taG(T-_owDmz?FplVm2mA4_>-sxd>H zoOl#MbbdoTH1GiN(JuCd12%Ov+4Y83((^;2o;xBADqef@=JCRj@)jVi$1QT?7?<|k zfK&Zmc?#)BU&IYKF*4`j?C|XR=Exg&llT(OZ98zsM%gF{8(Y>1#S>FJ$0QUp@~NkI zCZC?^p+1w7_li6+Fii#rBE^sZH;~6hM3k~E#`tS~DYN{V@+k*c7<0Eh?quUShyS1$ za{hDjBEhHulD!2Cbb&7dp)qgK@o3b$zQ-P@dN{5x?Mz1%mk#xKM83}m%!;+GhpQB~id>r8%hS3rULY0Q*2Q&~vE^z> zi!@uOO7*`T^s+Nkq#EgkC>D%osrzK<+Bk2TwS3i!LYI$+k-@sj#MCjCLH)yhiNKTZ ztmD3ByzExp(0bG~p`ksizxN@!INf?djFtl^Nw3Dutr1e{S!?dPk0UNU#V2*Wd)hqV z%Pjs319{F)D)_JECW)*ZhO~3O1D23Yz_%{1HjkWz4AyvTb#jaFEV|15QKP>cNB5`8%PZPfDzk0Gm@nR)S-R8y z(SMPdqV>vWFK)Cy~zjolliF_K+{o%>lI zhs%^3yV%VH7mkdsPW@7GhpVy`A20u*4yZz&<;IHY!rJiI7uz^ij_90G$Vx2@vNP0M zFL)ki4y|t{@T}_CDGB(E26jtI<}3SA9o_iAw35yu=ol`XE)`C>63y%MKDu<%Lu9+h z3r<&)=hJCQfip~zhO|EFi`IqZ-bSX`&iu}^@7wP_vk}q(?c(gkCvsMFf+s}h)$qmL z;0C&w(=F10d#Ig}H%WqL7*4LG5N&(|88CsAJ={Xc)=FZ2L1LCJXbB1^Jc0KVjk=K} z4MOQOfdKD67s|t6y`zia1pHT>W0cC;`n{55?2Fy{VPx}Rx2Ik)XhX_Kwy1Z`dOpO} zL8_57%8EP_^}^*!K}>lC`d(LJ(XEjQF~U_6APPU;YGH5~IsRVri&8|hg?`kK?RZC28c{L-Li0lwb$a9ub@ceyTi4g!+VeiO!^aovR4#=wP|MldOuam$ zC6KE_&Ju#S0ZzL7H6+Lh#fW1<>R&E~SwStbCxTdynYK=rhn-VwTh!=^N1pH}yJYSs zd|&T-1gK0*%gT5uy%h9OhWbYEj&d^5(?lTAQVcp5Iv$dVdn+8q3nDtp^p8c5j4_j6 z(R9mBI_e-PY+;}{9sM30jtUFD!DGV>Z8vH-rw6cB`3DKh6AfO^Cz<%Zf#N z81e%%I0f?8ICcSX5>AsLr81sN-ROseQJ(~6d*9@-LRR1t0VA?3(p1h@thi?ch$A_i ziSzqw7h1XPjpNi8E$z+tX3_J0sa+2dTy1r}W4bQ3?i63XCO!}~C(d~>9q!sdVqhEX zL{dt5?D-3_8!X*7jc^sc9jCjicFe!p>(f6t)f2TCo|#UqR&UCUWmugV__u)8;y=1% zkWZB4;k_BwDXZvxDN`?}0yTp`Ec(bevW{DZ-Rc5XT>Jue2buQI7v(pTNsiLdOjDqs zoQi)jptdi>L**cNarVXaCr`dbnnC_;(2#zfWyuF9CvY6dF1f-68DuJ#)?-!%F2>?< zTAvFc?Vag)*_$A&(Ro_d)j@$u;XgJrMmQ%18>YjL7+sCB1v{?~oqM3vJ|LXJKuGt%l~SnS@iZU4xRQ75;xhfCNJ zy8NfF8zyA+5swu{@bjzxhu9{gbPKq(;Cj<#6o@JIN}K~%p4LCBd@(+6evg;x2ieUw zNJmXCHf`k)d)D<{So7-dteTgaslUKXYT37g66?;e!;Kq-XJ*S6KpTRdar*7gUC-De zKMF5Jr_b|20j%|)i!T!0X4Qck$A_TBWs9aKADY>J`cQPOnQv|!q*iwYQU`P{G9F0< zp$FLm6S+Kx%X7Di*Twcq>wEAKf6h0+dxuKc4%m;)L_wIhl1+cK)V*>_@rrDTyrBSs zjv&%}#MS(jp5dUB-xOTAyQIBNH<3{~P5ed`bm|p?y0Xoto_1a70@lLm&O>*PW}=ti z8$05eWu6|QF)L5K*6s{bG(IOzZ5`%Le*4(TD%C`&g z+Zfx0K%^qJwe(O|fSY^V{f8(^IDeUYrzNz0;nhcqpkZ52(U@(~`lg@fA4H@x-+ee+ zG2;9{_t>}0cRyXSAEc07Jc@l1Q?byn{PL+Wj){XVe()j}Xrt(!m^%@&j++}0|Ifw{ zi2sK;+^P%Ng^a#=twImCQ;pi*^lod@y)veFt!wrO_v$}enC6?^nwzZQLBozUPnWM= z6Bt^WyK`lBAd%|SV^;AX8)+f6$%0@KD=1niB$v;WpDoOoJ*O+Cb-FWjB-+n6uEuw&IZKZYiI;VvaY&|Fi)DJ;`j5egLTXcss_hBmX@|xpNwv? zf&IJPsv2qtcz$S>L7?>+v}7>d2%3vT>^t2`-R-+$>*#dP_6(Y;%?y)Y$eIi$b=S@FFRFa_wr`EqB-u^L@%Tv54x^BuD{Z7 zb?Yok4Q6*XGakb`Po~s9n16nL~#%}K7P zn9t95cV&yjnH#;n#84>-_vO5x0%uPzQK^C$minCz&%zyIJGP2kxk8H8^sC(&_LtO? z-g8YWFh#8(OcrmYu5{=f7Q_gX7CQwrk#ESqOnDh$JpGpDiM@;krtk!`o{}hFHu2#1 zA#j3(bkrm}5&{4@I<D%63@)s|fJiAVsibsw31g z0wXOsG{{KDNDejd-{bop&wGB~_goj8VdMA*x3?)`&Gcj%rRE_B zxGQl--vdgl{J)jF`Y@Pg6vfB!H3k5i^mr^8$=LQ{2fiMgZCHPZKkqvK_Q^0s)QwJH z(Cf*XEwHccxoc;F`dXj+?e{D4q1y~Et95xvw%cN>}*1HOhtW81dV*UuBAP~uM#x8AC7;P3Oy z3C+_5#Glw72!}SXn3>+VC`{aZT7)Fww!pgFGlTMLko$*F2?lq#!@or1`nCVCIun2) ziiild(BP$n60$0CBZuKlj>Yp4JZ@HC2Zx~58l2@r_SO}QCUL2jssJvC*k3{B6B{38 zwVs&Q8w>`AOFEzP>F%mOASV!|tPRG!Wh#d;)<6GDgPR9D5)h~jEr(iI7KrhoLfyaj zJX~I0ej$+&edJun=w;KigaMy7+Q?AH4X~QHI@6u5MDFkV{AZ1Hn{D5Vrsorlyq4Fg z=oQ7+QH`-e618R-PCPx-iq=(^peWYHB-88TU;yL)Ue4<7{>ucI(s2~fZ+Av(RE7Zi z?c27dstL;*v66gc*ufW3JwSE?WKgSx4Dy{h0Y<&D-q@>cFSE|gu~JrEE5DFCG95Z& z4i*)^S$EMMJZZg&f42YbEVo_0or^EyR{kRb+nQdwSR-|hA;>OO)?TcM^MlSV&f2m; zoTvtnz`Oy+lsi@H#|UqVxDNqcCR>w4`5_9gXL-Fd&u8!Uu)SUT6_~7bqE~Y#hZE#Q zWg}7y=W5Z=5#XYZjgRE*kc_DdttC*sA(+X7qrid6raUD(Nfb#MSLc=>B9nP-rDjx) zJ>m+{%)>!^X;zU>kv>^7QImncW`|e14CYBRZGeZcJ4fu@+jpw}r-K_|sRBU%Qi4E# z9d2rL$;r`qySNhV@K`Bv$AULEka+l2A)w1!DqqXy&xsIQUs1|eAo!6Yyj4VPs?yuf zgs;bPif9_ql)D)$IbQGNWOIhwpXu*!4pV;(lCtSwCq&6Zl#wt&4yYDTi?>?kb-p%Y290<2#rX)Y0+F@r;F1W1NlN6!=IFj3-LIXXC z)&B%&{W-fzZpGq}X9?BJ|6G69VRQnOoUc)^U7ciFxk#sG=`E%p%5dE^^P0z9FIJgO zq9z2KN6V2wq|!%qpFa?EF$kT*7ghGB0a#!3GPBfv?L4`dscmR_{gUtG@rWLx9O3kR zjV+RMP%AutaF|j{!xGz90wi0oq+D5vE&6-qxs{S49dO9>tbXlwe3Mu*rf%6$j#N`y z_c*REEy|eOn?yjpW@zF^szZ+lO`Or6{s!>mgUIN6Irdd+Us|cF> zxHDD=5#xhKz_P*C;mq-C^IL+$4~QEn&tJ-V{eRrwzt^dx@owSfm&e1EkT?VIHe+bc z**_#Ha^fCJbLfbjw)`I=h=9Z^D0=lR%@St>xs8@2B|hGKo+3&?`>eA4h~J8i3h zk{X0a-G*xUFAtBU z!aXl83T$;b-mH;H@Ol|=QwsZ~P_=GjZD9MWWsMJ?cDYMifukK9B=!h|VlYTtP3f@i z*8GzSm+z5Oe;N<`J~bD7{=;liyq{83sp>2N(QjUdKzs*;=Mv*}k!>tCsesNO@nxG= zmI%J?i>4PJ;G0BxZqk!CaobnYCEG#kn5}&Qm`oCg9b7!+M>(GHr*fNn5Ie#GiSmYi zn9_2b3S1(j&X=R~Y-SowN4*ihN~p(ZnR>Q3JuO>TH(07m#`8w3YO6Yc8U_BnKqFni zq!`nL063GDrYxNY-lNdO!u}nSs=R7LfUgXUNhSZXh^q5E{^!_(SKs{WHrma=i)M3o zeXF#eu8!=|R~)xJ+0O0x<&tqoIj+*%SZQoL=Ujt$ zcagjGzwZ63zP&HsHSm_>)4SoPnpJ~iC+(Tj0J}?y@@1-TN@UCHGszB3zSZl8-_#?y zx|z0hL5=U*^wlKo#A!Y-a=DlLjRVBsx?-R zYswTb27*IyNKH#>Mt=>3eo=Tey?#1?G&}2S=r7eC0jL42ldS;6v>Y<5%QN zo^l{D37?yCEYf+j@Z-rEZuEQ!TYRWZ@up`hz%y1(Tx*+#4HQ46fX`i-fj#XIjwL0wLcda{v#yjy}`Sae^JzrLiFT&ZuqD1 z%4-!bGV7WhVc>@Q{Ud?J$kBTHLQgJqZlkM|j(*wZK^BpS%d4*((CU|_vn_U6?D`EK zt5Mj>(d!o$3@O)rS&k)gSTu?>0e4c}z)P!cHI$U|HacNf?X zA}e7%?Ze{nx{(>Zw+n_VN1@<;bq%763pZ?!j^hGj(?*8L+0t+P>&9mu{1J-Jx2+-f z-U8FjcY0$dVRKUtLDjCk=GWcd|qi_R@3^lBMm(k z36-W@G*?O_CYqV5T{CTdT6Wt8I&PP~)Awn%5rY)cylQyYXMfqJ=@>m-J#r4K&wKD@ z`sFoMgIu*iYRDZkV$apFWp9V_Y_d7ZM|69mDU60e%|LIPv^{s|cF7&1GXca;H-D$u z|J-{(MxYui!3Qiy%P(Y=p3k@;d@7X1>;9zMj<4TlBS#KyXWy6LHESk2a93`A9$;P0 z95q#mUZ86D9F1&#?-25)&$-Xh8i=46QwU!yN{p1OSyp2Z^K9wf5%MQliM`n_pHsKs zxKYa83$3%HMHAzz{SoT=29jSkkwnz%v3|XZ_VnX+XP#q0p#ExhWw&NI8Qz#DO=2-&olQsxx@(B^TGtqCWi7$%F6&0d$Q8p@bLZx_6aM#o50hIsb)d-!E>6emG7s z__dgnV!Q&im63TKf$#z<4)63@`96Kg*tB6lU~mEQr@%}#aP5VSB@E%^7ln4?CN(H zK7PMw6rCAKGB(H{dG$g5ZLaT)`RZxXrV*@>oX+Ots^vg1&PUY6(t!_SWGg1N7qD;0 z_#Ox&3mN|lLf7DcOuvR4hud8rmNu0F>C`lR^T6%v-&}yY_D95yKGFCY#8VHXO_cnV zz&luM8`j3&eDsIuLfhP-NJfC#=Kx~_FYfCuAgfpk3%@{pRz;&|m2G3r&72&MU&Vv2 zoL`#McaQG;>oK3b_)kY)b|0{5rvq4)wl(DS&Otm$0{wxb^cdWs>yNH;h9VVThMXFo z)$A8x>0NJ42vprXBpw`XmX0{pe1>S@b&_^@deHMlLai3MstSlYNSCDAWsVL)sk4YB z`K1DV+~&*Ew*?@dOSEfPfT-+%!#gGxM0ckkJX+v#iXR#O9r|tHzH$7-<)L41%#zAF ztXb_o%lh0(Qv0KDWHReeg8bys{~--HD*R(WVi=glJPHJVRXC*Nm%ob1^8?i_-*+rk zoXw?VV<%@G8;f*DLcahs7RBVk?wpC>q5Le(b>Zg9R+&flQbu&37ce{OQ5&(AHeVzPC93y{2UO zV?at={#I6jd3x8-OTj2&*4JU!LzyN>2%TiC+(t%R6@CIhRog55`d7PJ&;8qdeH#5A zvF}KySZknSq}NX_X(&!Fajm!m1Y#Ot5gWGENc!%=8TWD1uL^*E{=S=+P*7^^R#!p7 zkO@p*9o4KyG8fUa_|O8FZ9clhcyeuIFYOX-K!u7nkP=S^F@^&JfwGBMA*YJ2V|voB zkC~Szu?s*8i#ewTyzaFjYEr`)H2hkui0WN%$-Xpp$FDa6D0e`uNRO%asW8n51mqMQ ztj&faE9!K)8SlUKt*p|YeaN@CR}%P|2p#1&dbFXpyYC`kW6&NjekV;pMs3P9T~*pV z%f{te7=U(zUkBqn_(ZO5A8t#dxz*Fd7lt0sKA?PI#4dc?#ZCT5N>o2q91uQOz!N4n(Nt1Q1jzok9Q0VMaLsLv%oTdLV~IH9!>C4*fcch(yyLv>6Zj(_C;E=I(cKSKhif&1yNDb#Tu`w|AE|Jd(qPBra@{GqH|g`l z$-z`Sa(*kRfm*bENyv$y=Kow^swu%0ipzSO;QIomCs(#&`sS2>H~g{u-NEPXvIDAT z1Jte=W|@P10flMfC|Xr|E68261)FuvJZRTV%wsJ)<)LBG==AbPE#B}LpSW#|zC8#e zwV0l1zNI|tj^?Audnpd3WD8Ss?#mygU`lWKSskqeJ0r;|HWqw~XOQr?3IpV%z1ZYI*(Gyk8|hZN&xu zJP6^%c6*u{E8%gtoiq0bNZ$-QCr-{N7>jg-MhxD;zQ4bRe)WO!Wg-1J$XGM!`#0Z( zVn0&K_JZp5Po@~q7VKHB)Iq0kWz*=W`*U5&?#$9>%TOsE*St6@0hluToE@DLVm=nI zC{LO6>bf9$?;dAPv!rD`JKWyV6fr$1gri%D0J-ZH>fV9b<;}`nzv)@h9MmDGH_pqe zKyUkheK~Cj100(Fy&eYrj`HrQf6uTG69*a|hHWnh3Wg=yF4?wg~u;`oh+L(GAE z6Jr461^Vc5;B&@47cIqfMB5~C{vq3!7kSCtyrrTTCA&3HR9|7s_|=AA{`B^CVhKBw;$VVyrd$U;L{>sA(+p5|xAD_FRams%c-m;|1Z8nE;ByQ(ZgKkRf< zA%P6Ir~>B7Wsf#rSx2|rUXyk)$O~g2SNF~+Z@h=|bIlv`&K&dnpaQ5O%!-7v;Xx-L z>x5eAYmOFOw-F%z z+kM8!46u_7qUjpyhSZbiOuV~o9R=+@(GdOiA-&DI8|RCpWe*G7US4vb+Rq23w&~ql z+>1C46Q8SfSU?h3`Dm#!JbrxW)roTa|2%a25!)5uhy>iec+PD7^6qV59PMkk(Ya5X&xNf|&DOS17;0_ixAUBNbKAXLNBTdx&ZLy))6Et_) zC&27;G^gkJ(i8{$z+how^Q2^eo6h8xbr7-)2{r8cT z)t{HnAiQPv^4VGGTIqUr9#hk=Pl1im*DjZZOE`paKH6dt9g8l5_q=|I%*M&S}s_3qAA{g;*pO$ts%J#eHJICuWM|(mi*@K;DpN(f|fykS@iQL^- z>HqLuYXg7tldoI8qR}2DW4P{Gl>TY~)F2Lx;foS>?bf1}6H8XB1&=|egt4({ zl{}eGs;3`S{7AOhMLlHx`INXczE@OLvN$_gLsbwO_cdgTU@w&py>Wf<9`ye1ztwQf zX?{ZIbm%&rSveRD`0Km#cyp~d)2-l-D{JS_lYCe?`kkzb9w_K(TB5Q^{^=TeHw%M&3 z8G}`I<0s!P*NYJ1Iyy5|nxLD!4gixtN~zu%iCcn7Z;>?%8Kcioc2psAx_2d<4ZmY+ z@Ol=`H~x<+MCd*0?KB zt)Tm9w-2@SF22RSi7^4i?k9f!4gSad-1->1!Yb;s5`&k@s+v+{IM%Dkf5IwerR;a{ zv}!*sppnov3#$P67b$3jYwsC0fAWTfN%O6?C0r+NEM1}a{8`_Q-y@g^8tgyUy#&In z0FfRg9z+)Wc~l0(&}`S(8iH58eCQJg`b6CZ`?ihG{@f^xZUBoz;RW0@KR`vJ+H_rKKk&R%vJYSp;uz%F23c|)HI0IHaK@QSpDi~ul|Ec)kFPv zVNx#+wUqX6K5V+FTl(ybhTQcJmxV}WuG5XiKSjc>^D-yRP5G=(#3wCmZOm-^;$3i& zg5$a*aj7XQUTGeytGCxApLD|%{@xDgbqWyqOP4nASeUfb@kTUCmO}FFH(#6K!caPg zMqc~Ijka%Qe1xIVErMu+_-_+n@EkM&VflZ1<^TUG7{@5}nV&n>cCVpowx@0f^pxVw{?K_Z{Yn@P{yv2m%xA2&`67{Q2}1@~>~`P_9S zYU>w*?RU(N_kOTo55tr5uRlQH`-K_>U{J~ z?YQS7Y(hD1(P29DnL=0AIZ9r83R#NwfpHw$O@Fong3p&fJuOI1=XUM zU=lsjCr5-?+MLz$9v&WrMu>WoEn?;y#;xmq^;PA$$~Pz388qJVsF0D_IFHgy>ltf8 zp5r~suJN~r(EgjAzFSjl;bRNp(lFLOTCvWDP_F0^-K8gs85kQrhJXTC&z)WT*ys?0 zxY$`%X5;a%)5t4|lJ7s{k~hz}I(J+0%ek2t@zoXmgdDk3LgnK1l*T;Ny4?b6cYCk4 zmBH~&g;S69_Ns*UyE-$Le^gzfOm-{ang??pS zie%{(wR#}?1ao4tUr95nso$>$L)z*^SaaJ=Bh2}dMEpM2KA0cVhq)kzRz={4vay|( zk=$NU=KM<2e>y6E5FTohy%dm77@Ew8^+buA4CJT`ai6(Pl|STF7{gVpPygE3KIZp5 z_eF|vfO9g4{uw@IIbKZ62Kl0H^`d%uUXq&bW*4+v{8e1szpPd+ZtGy}UE9OvM7qwQ zEEW@naCde0pcvszd;y8P+*0RGS>k=z_)KOg&460lwjO{ma+h%e*_ac7fYUOmb+xyzj9Y$xM;BIH#t{rvH8e*%0^h zn&S2KZ}J-pG3sKFvHRHS9z0jLrJF)Re;e7F4}M#~)sUx}-yR6->WJVyqM6gg{fZI- z*)_dJYz$(o$GcI}34;v#mHVw8eTG6Vu17POnAtcio>Lo?TB6IU_HBKCs#&x&M5V>; zEesn}^PwDJ#s}8!sW9_3WmZbKsEvK&fS+VI$)6UM0(|X-Po7X}bwE~l$>rZDt5^lnXUtldm^zG|d?CY0u_I65OX%E^V z;>^d{Gxurh&&F}j1*PyMEuXcbk%;?Co;91**cb9VEG}MLUY5FEUwC4VAGS^`)wlHU zP&B^k_V&Aq5WJIo#I3ZPXl9wow3TteaB^~ETrh=8v%6qt(63Ij&X!e7X;qV<@6fX3 zwSr)4D_c(l7wp%=CobtOEiJlYrkaX7^b+|TNZj$q*`%HE*&mj|Z5lQ;ZRt&hvMNBu z&|R%)yAa+s*5UgurQ|zrYVS7IE#HDvnU(oKZlzo$Nd~>cp#|D0%Ed*Af1K z211kr3c{@o(J8c+cWk4T!;0Viy-Lk9pqc93HwHdyRU7-gFl4V2)*Ib08^%=}Qf7*} zDhTuQ^P~4!Epq}>u-h!9wvs%5#wyH?*_1?r$-~IOIHI%4LtMy}bgBj+Ij>?Pex2`m)L| zY}jqm)wPyC-`Mw8O(`%5@yAX}CU&>@B&bH>Zl}?vc(}G`*qqRu>M`f%H8(RIqzY?d zB=~l}ueUex9-mLegpe?LUY9!hL4gy?$n5WCf>#?+D!SWsO3l_Lq;Bnw({3E8lW%AmY#>XW!SgUBvIOkB zO!dOe6zeTsOM^~G`%iA@m-VS;NVa)*Z5)&8(i6%c?!GNzvAx*m1ke^#qu17D@crFzrmj_eUCMcbZCr`TV;DwVV1M? z9^9c%O@p*Pl$*J}{VrLfE~W&=3cmd=CL$ff5a9EdU&6Q>qNa{Sy$&7qDE|S;jPu~` z*83E3Bnxsc_x#P9nH2@%^*B$5pBlfC+49DSW(?j*1vfRigUI9Wt$|*z*b73tEBOV* zVehzfc54wC88?t8c&rXH!H9g)e!)j(NUTUWaaMn2@`_|}Jl2ixl=oAyGW3N{)=H`# z^sCM4OZ)K+JB%jTJ||sTR91s(3tH}O7GL%cma(4^gK)0)%9&2~w2X~0^W?zno7r#) zmp*;8D3RFxKq_$(Km9De;5&A3IuV)75U|DJ`DZ*Kv~Bilvg~Yg0Wi{HQir3xyJGXp z1tn2mDWrV^I8QyyZNEiVP+m;lyjnDI5e%49RLtbJR=3_9eZkHP9fdXROH-gO!I8I+ z+aIS}b`8@=wGtu>(^@@xi{AEJCT`At^L}gebE2`om+feIHfoJ6)lsGqhrlv4he7>IAD+AM7H8Wx zqp4(`JIq=1(Q7cXoJne%wB8zh@u@vgvbQIyc&|U&pKie)Z&_AxOEP0T>auLjyT{fX z4fSCsK3APbiNr0tnWTN2q}6U7CW2EdNc`4MvA)w~lxRjEZ9+X$9i;}Frqx=5Qr#r} zzAI=+>lj$0tl?xqo7wT{WB2HB{v>4sw;?TJ-AniC)BJUP3=ZK1XI;C;uDl6)nCRT_ zR?>#vx|p>x#J^9KcDDvHEH}daD_iZ+NWde zsS)np6C2;QHc}RZDMpg5{vwM7=ArLg6vyQ_P+!1J*X`EsAGp!&1CLl=U$6aPsfHVS ziHn_Xx*{z7%hq>|O|6BxC!Go0HH)6Y1FIjSkCtwiopDqky)plC5lU@;;Jdsn>oaO} z?3C`>Ty+H$H?QAWTIqjN9i&@frOFPqQ}{aufPOM}2dSJlq8;?gWdGLHt_*^Gt9u z-wR~&Cfmf55gDHhFO>0^!@rkI+%{53KKA3Sh%&CVru%p;mHWLeeuX3oh7 z9seTbpZ&!l8C)GN(lhYg3!zTb!#v1(MBB?`Jhf06NU2YmZ}#h(CD)eJDpvnvGOFaC zeh4uZV!$w~6UK&1;I{`P?coAe>bLc)Z6U5xB6pP;frIOF(&zNGH$99=x}KHM0I%Ly zyB}>hzkI&#y`;S^z0h;dRD_vKs^`w6c~LI$U7yZ`YY&{1W8Vs#IcKvu`pulb%+uNC zXb;V!Srnx*Evyn$z3WNS;Mq@^s^ua8@Xt7r9KdU`a zeeswSoYd28B+PGll}5Nxs?YoE>qoAi@66u<%3!tbitDdGDT+nK9qi-NA8y(=;dhN{ z;J%yf#G0hdFL~nI8<(4O-j3%9%0Tb^<~qor-0LB2Gch?)nI)-Q6e%OLOj6Ii-xZ8D z0S^X~r*lKHQxkQF1FJ*JOqxRLSMxAH|+lc+NH_~45XzE1Gg6Yb~;CIId zyFdHmEn1V#j~_}(0jD9blRT>Cc2bPzo!9qSWJ>L-@J#xl(B{k1KM~D6<9t}~O(@jo zcz*%Yr@*x42Vo_>w?J@=gkNTNc+jfJ_i(z*w-F5ej8P{B*H zX;z&7mx%6LQ$zPQ*O7aZ5fT zL@}PV^$jWI&BRU?Eum(jTvm7_@Df^I7YHXvpk9#{k!rU*yPKKETAmc5p7JWnmNRpX zaXV9;K~CvOg90QH-`>*hf@&)pP-qLw9Y(>VkwV8mictl+lgEf!FNLG-6E6{auNmA% zkp}~#TOb~0&&?vDub6!{K#7#EX|ws2#(ZRCgFn9%a%;;nZ0zI}h9c@#ZWO!sq@*DF z9d1b1#ZHPUqhA!GcNtzWPf?=A8Xww=uri9U%@19H9cVV~rU@fiioFMp!i?jMe7@b^ z7?ULr1KJeC{pbQQUFywI8tsMqT=*xUQP?eo?Gpp_?u+)x^>2Q?sgnHnzx5sq+%B-od6phZw(y{bw?D8WWl9`^%aH;Q4zWDD;*8BVK7J8L= z0@{VsO2mbA8g^1b*iPfCfWh{k z83BuU2c3wqFHEm-kyZP(N87TP%6-giFc&Ao%Z+vcXBptUX42HwXqm zqVgcyb8j@V%)YZnCz5H%;J04gt$p72IKE3q4}c=?s!nFxi$VvV6oUYaN$k1z(MgR| z+(@e6A?Yvf^ogtCY>7DGTYkG2Fo`zp_v=JV)t&BdXAytHze`x5|NC6sQv)c`*$jdo zT#ui5O)-UULKi-z#CrAm%+9AcaQjRWpw5kinno7nuRtCGl18bNaGS$NHK3Ai>MdYhFV#qH8%R|6>rcPN{mP)UXaU~FIjz>m z@d*ocw^K)GRjT}8eos<*TU$#~k~#?UMM;et#f@N#??qnd8rqKbT~aF=r!_R3+}N%! z8sc8l5^GR8&y3}~@y%dFZLzej_@V-X#LXx%&u5GlckNs?8u6bLo$zXKPVecBqMeOm z(_GCD`TeP|uD5%A07LGC#A$Ec2ACyrMKPD=r~Fy-iln`Haf)b)M%E;fh`%5T z2E{b2T8eaW%Z?lL$DocdF@W7qBBK*(skTFSoVRswi1t~pV^bAd${K0(a**31w2w)Z)o zx)<^_SxDl5uZG#B;ECjN@MAv4WGt8rL`C7FQuxYwrMzb&fN{}9>tB9Xw7H=f-`n=i zlAe|yC4lpR$EsBEf(@0Z&f$YQ1-~jT22o3D!g>l&Tzk0l(NRqeAYfdE6^Hdm9iLTT zlDH}5Gu)`@ZcxJYb2biGUY!#ctx=buEand?b90pEX0AFXh0MawJg#!N|CyK2DeL!@ zWsuX*&@#*oW%b{RmbhGD*}LxKBP%Ogs9Sb3N@O;~b16IVY*x;B?%M0fgP{`gZ+h9a z^T{@6vyfT^+O1Ixhwh#!z`Hc?m~^8uhP#fHn=84l<(e7^r9`&1wQ*{m&U&Kb;n7%H zC2llvjDjJl$}eG30M_+TAt1_?YtFl3cE6`~{$<)b?ji*pMh!Ysx^N0hKb$ZahRlXz zdY|i%$Xy(oWY;SFX?9+#VKzsr6+hW@%;u&=k&LxlDPH&V*3gkaIqYPNax`5Plb^CT%-> zadGiTrIp6eFk2cub@LSMO%s#u0@!e!q>09KqRHYD2XqRW94r8wwza(=qKwX=`P_ZY%Mdzt8G;+bLV$u9{A`}(23tv z*V`@ld6W9m9D<~LQYxC9YP?#Gc|*_%)w3q)ehItgUEycLw?fS|Fu6uULSyC&Kl{)6 z+`S0eV3A)q^a&w`WI?;6=Ia$}bK)L8mF{a}x()7Y{xw5rG%7pMh&Iv4+iGxVZG0&Y zfsh25GgF{aHl}b$;dH;<(b~P)a18upAAVT45~su+I@g(qny7O*#D#-l$XY|Tj(Y6K z4XnLNV2DT0YJ`o>yorA9MaQy7_@)bD;awLj5du_N8f`v{RCTsq3~xjonRooV539!(8dAnKs;9O{xAO4zq+&B_Uh=2?tjxfSnqYW_{zy2$*8VqLKut|%J8T6q4b zp~-y32vj;_XijzcFYG)*URGWmt3dSZzoG{Pm=OR}KCm#H-tcSu7A-J58rE8AHSkDp zt8zd!oatzW1h{`AD+Ghgg9M<%yGo$AhzpV#^v>69ehvR>ee>AXTPMPX9adaJKXJ`c zZ7r-K$F)^-pnev1XFWvPiYfK}O!4ItgVuF6Po1Z8u6?S`ETez4^yC z=;t;DBhTYDM@*wzV-*;muJK*onGNT;icsTD5HB3kD?(Sxy#|FyHJ7+=i z&)2~5^BF``!*YJXtcruT##0+2=&=`xGs%ojx7Gv-gC7$g9M%mHaWm1W9CAmU_)EMz zqnt>Fi738$&O*h9Iob*L3pi>og6Dm%Ll84j^>AG zu|nQtx_CvVVJi0rOJ&1}RRY5DE?<#5w~Me*aSk#dtV!$`z|@fj6N7 zpq0Hn%`Z11b~ttbqWKGS)4OmQO$VKQwL;eX@=nUmX^(&mRp9oi1}L6Oc1)rtK92FYQENiBD>))#hG zK*Xc3eHSEp81(DbhPq7d5rvKpZFl+sB9E+04#%wDhs%~dkpVE*L z3it`|-Tb1-$LvUAJ2mUAIoQsVZ#xpG8>YdnD%6aWz@z8%NfTIH<}ONcQm}M7q;eh- zM+UvBPu`rC6(nu+5V_0jhAe4+=RN__TJNQwd)^eha?7~&e_TaaZ9K)Z7%Ll_72JqN zBZh%0?+1uKEKA0je1CoZ?Jf+Tg|1&C=m)loM!s??$j$rTtUjj9!l%4Ej}~t!Vcy7+ zbNV2xIa#2iFF6cOTg1IrtJIK*j|JxnlxAv6RGtCxL`eSpKr{EItyk37gm4Sk`=|d_ z8TUHs#xFmMxyEbqpsB5@y1MN~Fui&#ZIsl(qEU^9n_DXZP!B64gYNN_YdwN2`PyCA z{NygX3~lq%3){K67`UuI=XLN^8nw|@vea=RnxRrFil!_<7A(5CP8Ak1%WR7g93=!p zr>KQ$DnDzF!AQFD4gA|)v9`Z~{Qy^&M9Svt1O5G%17$LLofPPu9+>gHt6TD4pQ!8m z{{8#Pd*B*qnb`s2U~JKM%U0wdwR5Pys>;n4U1g81F<)qY)SDWTo$GU;5R4-&B%QMVEGkxc={L-aAlrcz>|vsDVivorqg49RiJh&${Ccl};ak)AVv`kO z=rPjZ-Kl0WQdjOtjk+6cAcCm7`P%7LiZzCWNrD@>VH}N;p4>7koGh;>q&=%{sdIud z+QOh_JyxpURjNt>ypCmv>hdCVJ4-U_XL-^hdpYsm)H!ox$%>7$(aGkVOp+x&T)ptFQH?M261 z4!^Sj!4ynJeYAS|`aY9L`^oySVhZS_{%@uRje)uwiDGWTH|2JyF@;Ts-}yx_J|ZB3f-3Hm?p7b9J*4fgJ zN!|XD|FFV0>BnTUwWQ!pBcxH95X^vH+|F#G!P-uu*4y;ResWlPIH9+#i?^G%2Eh`Q zEOxV8?4KkL$zOyM{;8~tmt1_cRJY7TF4}as@Ttb{1w|klqn<;MrgrfoqL~Aka-z{n zkf>4f0yBz)?6B-!(@nmU7beZQZUaz@ZazAEW!)1A?C~j4-2Blmr8slSG*_vK@_WFyGDor^R)`R8ThUGv%-pi zknNWborBouW9~E%JANUW$r7h$dNJj__r?=lrcq$n7UQ_FV$t^bV;F^Aw0&`;TAEbu zDXLhDId@3);5q4^KL#k&7xdWDT-E<;B0j_uMB3xky%OV{r$kE~e>ztY1#Feb~xW8FP^E zpk^sw|ECF@dEMmj-zNeZNffVu&gPj$iLwIk+Gk>_ukVt_l$Ry=(?2L+BP+YF$;H@N zRa13itB9b7@>ODxF!Ll)ZCCNzDpHTCE^~faA@&;E`A^n~cYi7~3|$fSpLxGGxa49o z+VzAtzs?=bYZoc#G_f7)w4_)un?S)x7hH{#zS}hu%d?e7G3T!TN0&V_{*82+n^la8 zfQ$sj1%7A{ZF+o+J&{tC+!=g;o&<>?->sDCRX1hh$xtHb6Vlqvsz|Ax*fFE=vEB{% z(R4BU_x*e z%)FN-+{f)|T1}%R6Bd(&Cmdx9^=pdJyq2j>@|iZLpqNHZK}gk*WaiNu?c7LfPOoXj zTeJYau*1`eyJ?!XuV~6h>14k?x2PeykR1~8S|PDU`p@1T_7ed}G6lqIses_Ofjv3K z9!^dT4N+nJus)b5@%2SP_6cJG9V^;z)f5qRP1xQb)wzSiyyOgY&wMWbEjZO;kb#9x zhcj`@VTIWvn+cp5mZE#9{o464OeR`2`Y_#qnxbfmrpe!4V|8_P3?Z4=-trkZ6yJ9f zL`)v(cO9&pJj`D$pQ}ihC9x8Oefd?pl-Qflc=9C_Ai{sJ(|e$|R`Um3sG4skihwai z!;Ua}<4ySSz3;(Nn!{q?C~koGg2%}7N1zeP5PW~aex*b2JQUE;sm%dN)Yl31?E{bM zOxStzvmv;J$lxjz8n*dhb#Zao=NBW$8;Q6)_c5zT5^-J*A$+yi6lA?3Z;sK+?P8!a zKIn5W#Z(*0VaE*;qXFuZcTelj8p@^&b3v~sGUdW&8@GB^+`1H`55N?(`jtmU9}5b& zrts??C>7z!!IfG-muLe+1T{CsK zZTrJT=3+qNt?ZMZvz9jlj?MU`eaAgMd5VH?f~02oNxL1S(u}La9p(PqO6}I=XMfd# zSSGWostUDMa@v!p>1cDL%v9lt3yAx-Hgbd!dB#MuJib59_l@WpJOgvGmp{qdyY|#R z=jHrC-i*;-`B;_lc=Ol=Rl}^?&4j=&wr`+wd!i0xrWwNMfM3vhEx4^tLHV|Kn!!6U zQLLJj+;g*M#t!eLxuraY8~vq4GV+9&bdVe0MNIGe1ake^K$_$@2UFsE%Mpx{V#tk1 zhn6JE^ij-vLN;=>yz_So*ubfkY9mOvF#}z?j)k2Z?(NnzF%Tk!#_fJ3zhTE7(S;WM z>4V`oFz@}@44Lb~hzvI+T++s9cFTe(2W zk2^kM;P`gY@)zC|L=dPi1YVS;?eR-;XB;cMTf5=(2d1{l!Bz#;R1g>cIWIvHz=+-W zIRHO)Ei`NpLLTpw;6&XIch{T<8pp0?QhPYrWuYgMz<#2oeYB!`7P{y5Hsyq2T8{}0 zhk5!gA97)i+0d=SX=#TMc|1R7L-Oo4gu!{q`90+oV)|qG0SnJy zH%OGK!0N+K^}$oMAO5Ec)V(GGmT&{W=f@jNC%nrmD;O^0{YR~6{d!lc3D*IYzOgaA zjVe%!pbd&00GWoIap(%+CS2X!e$$vD$KBVbrqqooHROfJb%VzUd!G|&9~M2m_pETL zv%RmHYAcQkxIsNj|IYLY5b|=l zbb<*a(En`nHe8&CD5!J;gF-bObvCsClI<0OfSHbzK49%h?@loV2kMEA4mChv`lhBB0joUpE4lb>LdYkwJ7W4VCnsmD z39JRFxN}EH?Lt{q_L{ic3)c~q2CzTeW|F~wuwLjx6G(N8+=2I^`m>cxm-@2-0}~3k z;)!$8z_b|`MzI-9s1N$H(K|mTBsBx`Gim;J9q8Xz8WCi5w}9Y@Nci|y4pJW=db2K( zZ6sC9%d^UT9>}<@qT;c|u`K_GKLf?MbJUX&hDAM0`N~?|w#H;c%hn_H3GD=o_>|k~ z+uF5EjER}X8lF2uU`Y5W#{OgQP^)x$jfjx_I2A?76pdQp zIub1&Da_J?f~2RD=N=1^=fKVEwl4w4pr0gV3G|(Vv(zKh~_qBGDbAR_f&%O7r-}BtFpYQWMY<#>19xKB8>Zg-R%QhStITVgRVY7V8Ph`1^ETv|eM%YZ5eI+Y~~CEa!Kewd2H z=z6bxUt7~*5iH~{CiCfy$q!W;hUoB<{W2CkIcufs&^YiS6pU5K;f^vj>5@90m|sJX z0gauq=$3ZdGqeicV%fWdc-h@AcGhIE?S!4W^0IomPTw>#*;>-l%=2M^5dybmdwHxS z)pcVm>_rQ@rpe{s8sGY(hyCU4fty|(o&n|cPbWJi{@Rw%q5Y3Le0y*z9X+|I)`y*R z>~(lnX8q4&r!zl~V|$F!Xl|}g6M6m=Q4$&Zw~Rx>GZ-_>6Q)dd5qYvU6Tr=lIi5bO zDTQCh#~~4?et+ud?+g3om26(sb+PAN$ZFSRJ|DULXN?`{ zkZ6u(GUspamblH#s27r2R>=-{K)L$wm&QKD_;dKtzzmxeGK_Mi6s4grkISZLjIYQV zY2T`MWDPDGLZ9R@zK4JL@Q2vAtzMqMdR! z4IX7`n@0bRjv1s}5*>{FV|1a}W#`Jk7HtoemV{BL5aDcB23Xy-l2Cj^Y zyoUefuIs<=jIYtZt1-S74935!@qe`%Y_HVyUJv8aSlQ`3&!=+W}-x#tge3@K$*8Ot@ zk#yz0j$+gHz}ls9cH9Or2}uVvS}eVQeCOX2`saH5 zyF&k5kN;O2YTtpEsr`Q#rM%J>l?v<3O1~$B$e5L`NwR6ynZR>p62FYOM|E{|%%Fm@ zvU0$>lX#PB&%7LdhSi2jhWE7gNiKTcGK|{uDO`)@)y`09euB)hG|9TL#HkWONv(7z z#~Errt31?ZOmY!8{yu!~1NKkjV35J6D|qzVi&6+vc6o8B%&aZx{O4scGSdIwHrd@< z_a`%4^fx2F4GjOB!q6F`QV3q{&i;a^^VJcs0>(g39Vw<5zgghVpc1Kn71JTa?8a&rqA7vg;9cx?G&m%S!&4L{^80LyR~a(Gpw%+FUo)YRfbCQb;H7Ourqwo?0~;{OJo zAD86+D?h()5BY?qh$rS13*6_fy5yzQCraI_H`krKB)ls?wd2d1!y%3=HwbEE7Dyl4 zQ+W6%l`WDp{^5bgoDG9flnbPxGV@Kq+7-d}-yWQW!IEo=1??$$uCXX`9+bt-(-%mK z?v|^&207spE7|3Yr9Q_Q4UZiAS?K)P0LE**ghge_+4>;cYP88-x^w4_sF>KLgcBuO zQti9$Sk`0}fC4@Sr+22MT+W`=#P^q=jaFy#N0}m_B*cZaF?a7SRqFY4;cR1cVs(XW z)#ZCT{jwlXG6KOBYu|<0LzailK0IE&?&OC#6DLkA2;Uoe3@)}Qp~Rp7HHA`(^ucQC zMa047brMW93Y~X9_`y%_S%2-?wal9qX?)^oJw|yU%F1(B>&@TkxB7BdV@dX(Gx+b| z_~^r$i$!o(>@Jr|I@7?dpLE8pr6M^S0>Opg+!Ggzi^pVr@sk1UTR*l_RrI?dQOI7E zSWdc2W}gR`Md^oWecxmoqv9h@NiwW%oFzP-JvCX+|q zF*l{<7P4y5ZiBq34<|~{%bq059YS_w~DJZIx$0PFXxl9FZ z(om*@Sl6)mVw>Jy(bH_<%nvo3g>TRll_DK1HG5TG8m$c4;J5DGyZ0h<+sB_CsZ9u% zgXqik!TzwUp0=8r2VudNiXt^Na}|Tu+j{N|-STqcJiTAKz7<7YUoUwDHdIe7h9vM+ z8tSPrO^<}tNtl&Bny+Yo<}pMUA6omxaN)Mo`PZ#n2&s=%*B5&(txCrGD1Bqje`iV^ z&2y#S#rj9q4g7s!a&~QwPh?%wf9$Z`*5=SIS!>sxBXSt{K%@PSYcZxMcazAF#Gzu! z{4SSzI}6ooV3YlcVf_cc+_X>kzCZDh|D-)q;DF~PRymzh3zU_Bn$0)<+$_0T@3Uxx zsD@mfSr#&!Uky&@eD2e1X@xQDVe9#Ro?m-Ag+ zsZ{R$>!#|KAx+4fgUh@a;>hyUY;B(Xcx zqAINbW_Ju;Fv>7psS>pQ+1@%o4x_Iff7DnZY{P{~5?CqOrbjO#s?`~{&d-$pdh2Y* z8=1&~a!)CN&}O+}r)OPX zrE63ap%LrQ+fE|mm3mJfZ9GjC9|_a<;g>uOSGP}EqzE_2Ymw5n#Yo-Bi7@J~X}xbO zw!o)`LJGN8OKbkcix>Cm=?R=Dd3f2nvG`^6OZUT&bG7|FS?Ivm3Fk3F!$ASn`zs-a z301$X#FAZ?JN-o!vtACv2l4i$j`{$_O>hC*Zl9178hZDI<;n0tdhGp@sZV zUeNl)h@qd!EIA49txG86ujVWrR)wb@`M_N2cqB9D%OA)!9O5Pjm1Pmz3WLVCWu{J> zwnAEp;j1}so{RAU75Qr>Ts zF6f4WofRTkczL|vU${oUcXM4nJ~_$1RnYo?fMaKY<@>!`UpnV1)TBPegtb#jMqcH%y0g7(eg1R;><$SaZW$`AOJ+_gj$&uVufA`aO+DalJ z4ps@3%E#W`qR8hPyxfBEt`!^36SH@u4;yaSuwgo%&gElubRs&) zgYASV7T=IEVX})NtmtPMDoK>%gfCvQ)zbq-swJ^u$W`Er)l~rkUOSp&=>whm8rq=v z6=vz%)%mtnu?MT_l;*ia>@Ar1376lKC6hM$XTC|T zXe;*sMp4Gnrg2t!6(g4)rJ8xfj%XZ0!evQ55&QCWQ$t~xx|+Y_Jw5f>z6gl@vtqLs z^2en0nffaNSF{!DT5RrasaWBl#3;*s%qWK!pgn#^Gsd7GQZq)j^X;b4&F*t09Q!&s z_iP|FK!>x4ZABA5Szw+Br%)+ZALvtb;*>UA*gUFnBVY-$EU8&2Nh!fK?ustg%@O_0TR{K@0J@$4HMtKC!UuUM}TbT-f(1RZHxr2RO zk)7J@NUh(A49A6Oq>#^)QL;t7`|LnlcKndH6J*AR2YTAv)IWZJaH4v$E+gCtKF~H0 zCTWSmP+2gOc_Ge2b}8(kehH_6o}L_aCvJpZvx{k5iNdd>T{?Te$fWamDYS1}sr6{l zpO8P^%T33)iXdA955e{84p%{uakwJMTEi*~`!MA936l>twp*yGVxQE+I1ip6k|DNr zmUGW0IN-E*-8uX&Np*;YV%EKha7UJ{solb>?KMP(Q*f6~F$4{OP;txNMC|^yruh7W zz4Uun{m3J|G8<|8EC9K{2)~QaB|d}^Ho~lOgxUfu=#Gj)U`Q+jKleFdwHv>*rn8;y zwQ$`sS`F#Q*}jIb!!IxKwxOK+GSiKxre2wC*V$U7Y*Xdf9k4KFysm@HVG~RJ*w@I?o=iUjY?knl$p|RKz78LZiDW7ZhuFnA~y+ zmUdmcwK!ULx{y-Jj+Ug_t2^&te;F6s!coB++WMAHROuzfKZV7E{XTJ48}4)6&BaQ; zpptv&ty_ykx+@TQ_|jts0l6YN6~Wz5JO-@xE$w)>Q(WWQOu|u7de0=C25N--bQ)2K zCQ(Z^&!GEAXiO{z6eT4La`aQYNJxpnT zEp~37Cj24kU)&Ut&m5aGZ=Pn3BcnK%p0Zm}HfDycWWwUTp6 z;+#`jbMnJuErbpKt}T}ryu>Enf6sQNpuF?~?4hHBKI%$t@E)2CL5%l~$fjIfdDImo zVoA^2^ZmuFcqPM1#&-)HZB04S^B4}kY7-VM z=E#P!g2||94H$;Uuz8IfYqBnDhpa-3|C8Vuz@eULG*AM~HK{*)$5~{=ungG!>1=*X z_YsYE`u_LiY=El37jAL*XU3vbBC-!WzqWiocjJZ0vmRbQCl%C>jNm|SD&xIAX918; ztg4YIn8(X&?3e~jHVp{GtqUpW5yvMmX?`ptuaINs-UkUc&6Ae1koe$!w2tIu?-~J2 z)S?VAT23zDZady(-1P&)?Xq%}VVVLap*b&Qbz%UMP7Ap;oFLK4x1qetyNWlHbgy8I2joVPrsBNy&eXMEZ3Pi0-h|I#Q6kI})6%OE~HsMn) za?xvA7T_um*1zUwq(w!E$UEJ}X44K@VZks>N638X<IoH21gKlcIB9tUlIwN)p7pL}4 zQL)RBW~8lwC&{#k@^bx(uAX8O5v+HzCrpc^`LCnq&6z_PW1PG$k^u9L`g|`W-Ot|Z zgzXNhMo7@ZB*$waEfbIw!l%MF2D`-hJoO^hrfJbLabooia;$r36<8a8#i z&l7(*cHuo}TMEnSFc` z{k{*(g5a(I>72F$bQ;##xW9*Ut}cs3;;NNuZ;jx)>|05U5FE27AbA#0EDxCh;&{Eo zI>3A2$x+hAeM0aCPXWzh)NP+HgTE zFy+h->#GEun%O4<8K7yZa$zq;oP^3*DiyyLGF*G=|7yI6H~yghjbix%07tcaEBY6U>ij6|w*H8(&_F4*U zAW^QBeZk&6}i7Oc=LVppYCst2_7Y&ziM25MwYnCQLJBs1ubYN(r+DkvHuc@IJzg zh;xqiE%jUa>6|FIv$-5VT`oA>47oAu=9=F&mfJT*6N6x)H*~qDeqQ}5goTB6wO3@J z`V7TplsNnS69sdgd5L11fWS)Dx2E`LDSvXAkj9EfR<{{;d&eX{*b-S>HvOB#CK`PP zkyusDbzO6}C7!a2i7@G|ur;Jc&wU-v{zP+=@Z2(V?_!B8H-?}u1^thq?`^9f{i+y zSYea<%>j3)ySe~y`W zt5(WcO96bT4ZVbEJ3{8CA1k;sf6XD40rY^e;-SdV5VdP97hBm9Ji6`w@F~M+eBAEab!04PhZei6Y8Jcaq`3Q}8qr zo<^R(hMb>AY8e4oU5nJUaC>vSl!wk1?@Z#j3vqq6@6U`|*R|r0?lMyJvv3k_`y#^d z2gKIb1yva6Jk%QtK%AL&Wy#iq-!8ZV?8Lmz&2IxIBF-i+iPcGB@3j6{bA6 zoCy}G^x0{XgX!Xg69yG1R87NZqU}*K$KNd#IW2wigLG{0@!bq>FgH(#m$|PV5?opc zsQnZXl!JFaO(O;{(B{K&OA<9hcxiag1i8!yV{}Zl0Z#!|B1h139_)H17#>I^!{X4b zUX*~Y0Z_;ir@kT=4{@G3nKlWGL>cBgxMiFZYHkZq+K zK*LKUKz?o0^p-3ZRu2|X23V;nNguMlICP!E6(;=7!7+$At6~lIc;9r+dwoXzz8sgz zeXgdYV7o8=J=k&nr9OUs^T3C;-a+{AO@e9s(w1NH`JsL?1svH|HsG2d4OWw23a4))9}+-2oogUZF{?E z7O9!%V(LZC*?L?G@pZIERgt8}1t47CEd)s^#To!RyP~Te$*^V4GQZ3jGUdNuzYXX( zg1^25f3$+=8rk~5(|5wdMYnh@6eOJ0R2sXajR}fGv9G&T2oP1YN~oR9Nlu(N#VeJQ zwQtlJ-=_LcdUPTH?J|LA5eHWlSZZ5l?Dw)QTgb4XABH%4HZi{B&sHZl#Sy}w03(6! z3$gVS>lWgkc*66WqTkFfEB(m zJGuFZZq^V8P0h1P9EW1UF?xTcrG{_>fq7RNf&o6h9GS^56~{F;_96qVzU#C55)$ua zEJ2&n-$+lckpm{zB}NQB+l@zLONf$VHT;$n9K`({OtrISE>w}>nzZHJlWCRLI9f;1M5MWdLm`n z3XU&6sRNtJi~a^j%F_>cGdCUlq1YLqCj_zFHzn;TK}z_iS)T%Ik@H_ts94wgX`vjhT zr@={nNow{s;O|D&X7;dHd`U`|BeBPE74c-m5H+OB_2=i{b`&(ps^ z#$3Qhc$Zkoezn(F()UitZ7ea$;ow(W4!J37X;cm$E^&_4lvxRnElZZ4uhefQ0L-EN zMwGa|Cm+q-5vH!|G*%?r>N&K%#LcYcn7N?*8CRG<7P|EL;5nDaTfDowJ@#x{^;aO? zi%b-m8V(ecq{85`vBx87Tev1n$^;iXf0n{`6@Ntx4co33AiaDyM(#vuQc3d+S2GyU)p;pNV+YXaLfw=1+d}@OS;$9(+D+4^q*&B$VqI%rU&3Y-c&N zuiZZSCSX}Ho{baYBZnpM)5@0?VIaySQDqSP(ZZT+FZHI}{CqE1;!8l#2!}~_6EbLW zjYVqLK`QFRT7d1LXmVuWt>JO(nWPy)N($>ND)mg8X;dq<%VqNzZzW)%Y3OK8q)lwS zn@Di@cOtigNVU>ZNy9!UQx!|449*gBLWEgFo5Ne_J?!9QsUaNi-h{jB)}@!)>)#MO z3?ah%A0~Z^=&5LR@{4UvOdmYy(0Z;a@;V>qj#ExRV^nLnzoYn9t(o4ZaWS9na~GPK zR~x`M_ML!fN419;5v`Tsx7PH%C^@lGDck^xX&0H;Y7OsENCnznq1lSNX}C&i0N_b2 z3QkBKB~7h|@jsp+7%8_d?8LylSWNH8v>y&Z?@s~|4yHdvjF4hsTE(E|z}KzH5l`gs zRYUwVO_EZk;33SafCDmCS{ApG)<+3*2%lm<=SHzX?mc+B|FLNRZha(W9Uh7?DeXHh zGAV;NfRh0X+nkjK%9#*nLf+djOmN%zimDgSn834RFcVH;X>p=?g-)}D%R`+6F?jLo zr8Ni@l2?v1tV=lKJYI@BU5Ral0l5OdMCh0x<8;s_{|Dv-)j!Rn`REc{2*xAwE$2Q` z=peZCAmP_de`ezT-l%aCqr0vF|7eIzM?Ti%@ADIR<%x&YykGLw)s?CkI&fF3x)V){ z#88H~UK$U9k`)0wY%O9!j-Wg;lkXfYf@#ogg?c}e-5lR|%bYWr0W<(#Kh=E+-Y4WQ zK`tJ#P|-e9+a$=hl-g0J(l&i(f^ANe{WYBx$X+SBWbo`Zj3w_&D{tjy}Cq><5XitQg(UU76JU5SbQ2BnJjRA zMDq~FkBJoLb{v&rsM2n(bsnmB2Ed<N1Z0oqueUMtyx&JAuQ_A>nnmp$9l3h# z`ibWHgpQGL8MH_tP$W43zug;3dGu%v=s1oW^sQJ+&bJSBE~(0H%y1B)8`lPgHA6Gu zSi$1hG*IhPLulC_fR^Dq7jceDwy>8sNAL%Rg|rP+l{YS)hwT&HO=J9G(?Dx$HV&eU zDLLboIfXjfWqCb!Gl_<5NoNmHzFTmF2-=O{AG2i`ZbJ=%(y%HM+-&Q2Q>3#=hf$wb@-paa8 zyJlfzj;<%;z`lsa#A+s1IL{yrAyYFHSoYODsZCliu=pG+N#&#tnq(AXb zkb?KH5Xc@H8kXFH5fStADH47$P%HoFY~)#Y3o%VDAl3vtE9dAduCD)qs*p_Wl>_JF zA(WP1j1o#Uh8?LjQ4&(O40?q`8iK^}0P3^(KqM%DtJ}M0k9TMe@ol%HIgFs1&>c2v z?;N#UnkmS1w=TGQjUF|kR45V35>HqmCKgf5hl09~R?M~*4v{d-#?cm+Mj14(4_RO} z@KN~nWJAZUA{wN`VQPIFKMHd#+K5{9Q51K)3U{wx#o;+@X&N{3Aifz3q+b;rF@&v) zz5$iP(};(DMAI(gC}JFnkh0y>s=|4!aJWyTSg5DGSZtbA-D?gv^G|yrIEf)!lCkxO z#yFEOHUFzx%HT+Ns%}hl5eKD_P`Dx{g`2v?vqY9G#NOzm#>vzIBDJKQkJfmw^4( z+Z^Z5P_Z9gNTggx9i*`7Vm0hhqN?=QQidoX6l9Hty$HiP1XX-NO3VRda(fq@)&WyN@_ z3b)RmsrW5C^bYpuKhEkd#y>18rlB-clkhF?LIKKnfc5E;!+J%AgTLB@ZHcp#dKMvD zdD??I!Ep7QItxj^wADw$1E;W6H}@yt+1+t28Vx~Y2q^lBu&D0GSy0BJAWl`_9V(0bu#wgA4ZvAF$ zNhZ>Y*HMW8R(NVmx!AL5F8ZL#x5W@S#yQcipoOMH7rtDfGQVS z#+n0U32jkOm*B|uOa{zKUPbni84SvXWL08RFxwV}ZS?Z{=NCNZR;PBp%Pc9nMEYPo zB>irR*rl)gtaUhQkKw8xRdhho08N>fKfM9)ey_zJex2A&H$~!(;am=WTgb3MWdl$L z@`bMeqbbNW-5l{3byVM0fo}*2&51*7e`gF43|Vhr1upi!Z1dwnBk;&>j#d4Y-Q3Ej zZlH3@(K#p4)+JZ#lgv@MVCIA~WJ7M8On)P^GzJ+gi!1aCwDGK)V{;`oU?OgK!QN?GvsEXAN*$D3 zAmO>-@X{N{jIvH z?hAn(!SkLz6dRK3J{MeH61Fnr&P_vQ2-slvl1#9~3oX)mk6Qgcq-=tksRPcEy3sFn`LAOKU&Lkht2EFcMs9&W;39i4y0hz3=W0a&^6W^(xg3keb&` zYpvnrGnQ!RR+&k1LqXf}D_#DtU%#ejB~*8(vj-PO55C{8{!%lo-8ZVL$HVn0O4g1w zJT9qUut~fkA|hmgE*n>|pMWj}>+>Z4n)8xC8OHH=+;2i5$Z(frc?k(o6+&-l=4X6^ z-kv^x&82K3!3NY7{+r2s2}cmWi!c(S58LOh{&8T356^)$lQYy&`j(iaBv~ z2azjmZPkW8hvWV3{t;(AHM4YhN8>3xbb4kSq$ZHJ}x&9-sVZ<5e6T73D#}$(h~l zoK468`jLw0Zc=8@2!dm!k3KJK_Pg9M=~Kp@a6FK_K7~s(1<^c?X=M%$1>!j-r|3)h zDA0CU^IAd;B+Nqst(e?3?Xprg=(F`C1*mXxvXz4s9|xyMls45hhRs~2^6X(!1rz|T zdgN1~9OyBYd=kkix>}U+X;OhnAM?JM{5LL);k|Gw>XLE?G&FcgP6CwKQrrRZ%adlq zkeZfct1vXoXFLf8%Oug6#}ed{5tJ_l$P`l1D{AnnbJmw>pMRgc&=nxFxl5iY?ee@4 z9A^r2G#5Q%-N7G2-6drecfDiMt?xG7tx{-sxJ*S4KvUwFJm9XkfDyR^J{V>Z8W$(| z#H@^)aPG35*E3OeXZ6heOgx3Vc-nm84DT534#MeA{&V9z7wo@_eh(M}B`6PYl)5O) z4%D^E5Jg3rWz|fgIk7n}DGxTN6COI-oKV7&%|<-Mt33?2ZEu)UEsgP)JUjDtb2*&)K|x|GueMNAVoX15baDlRxwIkxUzV zRz204x3;9e_?dBv0di3rHIcQ*wP)jEBD;Gb@OcUMoc7%bX_Y%{tS?K1Ay?{NJ^CDt?rScVg3OTzGpz7|1+o%OMS>VU!611h60Wtj~ zyrOtWRFOe9*QboSku#g13keuWC`g`k4Ch|SvP7Zz=Xwkxj0BpnB+V6jAfHW~Z+ns- zc03iJe_^vM*mEI1V26C|M%9T#T~J6cbNg^bjBS&N?NFfF66vPlx?*aL2Z<#?-0|zS zc=VHt)C`xUa5*#8jE#-y&^ItlRvMLn)_!b&ZRcq_NdbhCQk*J#Zp{sZvO%q{3kJJO zimgf(iBCv%ZYTam9y#}|?{iRwYQGEmv<;JsGieybv8pu3-Nh)qITF81UrniW{fXiH z#($CuH|>8?A`w9m3aI1OY=^vbK=W+yRI`#1PPk&ot8kz8uDu`f> zP;wxPn-8tLQNI(D5O`Ri)s83-5=17zFZ{+V7DQc{RMtZnQ7MIPD61#t>u7;QS8^7J zA9*bCXO;-rn{kfmZx;YAx`R{}FMg=cUj^-*Rp2iS8?TYoy1Ewi$fwOuJ{ln>Al=!^ zd=S!<4HG$vU1Alt6*=OasHl~6kHFizflACG&GU=}b6U3glDU1tLKc&h3JxF^LKM$%i-EDXcH$Mowg`?!91Q-vVFLC(XZiaLN zZa|p)A$^{5jO^{UUL64WQ$xd_;Pv)b24m(@NS{jT1Q`+E z?j$A2Q^HU58KNx}o;f9T6av0tOAy&A;n4G)p!n_dz$lnOe;R4#aSf8p$yh0fj%}=d z|Av(k^*}8@8%+gZ#1_*%p{IM1JO(rj4@g)y%mPJA+6m%;iTy>Eco}$h3$zP&aCQaY zu&6c!Wt9RpKimIL&rtLRM3OQ((Aj})NFI3BaR261LGji~XiJX4TLu}j?{4>* zDhNi7UZTIi^$)+MavpF645n|;N_A_9ttM`}7DfF-#(w$->&;NEYD0xgB=A4OU)VNb z{JTa7xoxkOc)geFN8U33-o1NMM8rI3J`uG|=^IpGh&@eiUZt{l_{+E6j@kM)Jq#7n zgNV+WNsSq#mw)ayH4M&+&pizU!J!n;k5fcO24GIzHQHzHl1Y!=Aic4?Nn*LxP6$2L zd{(`PC%pE2Eq~UrI;I3DW`rhKsUkLV+&yE*-FFL7cJF}$2kJveuKc#m$`o~G%fekU zMRNR9LPv!cSCK+hm!U30b^@~uoKOu4UfX3yMw0H?MzEIin)n2fo+H!m{q*+*9yK3l z>XtDpe;Ugy>qb`cN8w%0%yFRZ2dCFrR%eDkcrgAuqCfl&^%X<3oYgyY01se#F{=i$ z*of0M2=???L%&mZI*$SH>DiPSTQl(o9*me``<@zI*YWF{YKC#<+V%bWxq3+bgF7p4 zQlfWy*YG+uSb^ohcoo4yvGd zyzvt9)T=YDZ6tN8^FX$9)M*yxU}qBw_}~3he_?YvmD{uU&9Wga$35O9yH{Qxln0*) z<`%LSqI$k<4ZtnE_WWmjRUV^J?<`b}Qp|3@pS}Y(##b8j=K~5(xxYOT;_EEGw9b3- zCR9nI(%_i6T)jVbDJrR8Hd=)WNPqY49qADynGl6n{#-bG3XJXhN2e}`-ZGo`Y49_v%GDL8 zZ4&6%6=`@G*@p0qqg4_ppnJrlQ9}|~gIf(~n_f#FJbgPFkY^qsNdoYgN5|l8h8|Kd zDw|6(^O0WuTsUAD;>gk_{1l5Eod_sWyhTJthT^Y;gV4}RR1aZwYT3c>aKEudrvx== zB89T@E5pAWCIE`$RaI)_s5yJaPTm{Y9s!B0UKBmK)qI4A;zQO{EVusatqawdF~4)= zPW-z9NdGpZp`5lKK+0I$@(Ozk5dWc2I}>>6Y4=MPFzkEhX9Rpgd0|T3NtB~FV=p<* z#~Bh}-Vr2nNLk~6E?!@M8D0`be>_CB3e;ku+Upt6)iiRmF%U|emxTTB54pW* z!v|IQZLR2;k>k4zR-n+sQ$h9MnP6L0yQ6Y(6UlY*)#Im`jYCC6MV2pS$f#;-YvW-i z>93CW$}GNf|Gx13-9Zb;FH*m0*a_zrQp^AY%A3F<+d#+9>*;vc;x;I3KSdpL#7?4iMqxK`BP52Hv%YNnK^ zkjIdv83(?(A+ZF8#WQB48%ACEA}{oaT z78#XDUd%Cg)%)S%)o6yEzP=#%HnmZ2;r&PT#?g7Nr6H>fQe@i{3r|h>j?zF4wpFgI zGFp_{<65cF6~(mZ?q@_hqPRMrZY$9QGz6Gn__gcTw?LUjT3QgF0@MhIby7t<1zjmk zT|mIy`8!!^o{Fr}s1BspS&#z;>=_v%wP?!N?zfW$^?;r8adk{SXjDk80^1xDEA3C9 zhTAu-*$(np$J^a?@5p&r2YX#@$0^k?*SF^Nfvr7R4K1h_9wc{@SiY`jP-}x^z#cL} z>x{GiD($$XPT=3Okje7a)zv+l60#ZXSH$_Z!N`l{LeRZdDK%nzIr~QUmbL49MHwKw(mfG1JUSqI%Myad@oQOpy+QN-g9qnQ zp8VVMKW;z>RgR#9oXjItCthj72-sO0d!q>*_BgbAUIy#4E=}KL$r;i^?Q!Dh(g|!C1azc@I{o1u_>5C|A zqxC|P?V6sJFEIS&(!_s!`7Ffw+U~*q=lje<-)!Z2inyy?Pj#K%;O(U4g4oI=FnM%0 zvc&sY>X%0xIco#;=E?HQpE-7ZdpqgFwd;`zzU~dCgcdcWBY{;I3PQTzz}B00Q2{gw z1jbqZV>GJu8C!?*)aFm*QC2T_3yKEVUQBrlL_-6XB5D~@OepvH38xsacI|*66x%t5 ztRKFrN3CN~W!oM*JGR!HwmhOMOwbwE`kla*?^Uw*r$a5 z*$)52p{m=XfWZ6K#cA`71`3{eyMdHMSlDdB70eC|M%wr1(?Y>AYKQnMIoePZ16*q)RWztDNA$5fF zFcuWp>SddQA3S`>lowyMYM1E9+(2)O@ugWVE}k!6WjHmXi+6A1inx|&aw(`6Q6QJo zwxIc_n46G=0-+#@cu6+6S6kcPC!t%_F+>+Ab!=BSjG>}!uK>rTm;utqxxrKIq|?__ zePhcdyO_uh2@_@@=Mi#{88FL|i0p}sNs}ic5^`8w3U($ZO0s8U4BN%2PvfSw?Fqlj zIj*B{0sDQJ=C*;+=xa_3UMQ1k&;NzEXeVY(gOefe>Y<|K@hKK9Ah zW%ytjLmNjO#UidUbN1!ZbaO@vHePWr70T7T?MXeo#Z!QfijuCb@J?A2gQ*W2wk1z9 z9;i(?I)Rc28nHZpPN}?|#pqe#z(hO8dnbmk>QGg6$>_BHrHkMLu_YxAWw>CgY6e&^ znD@~=w-?cf=1UU+&Y8b~Jc;Bv$z4NqG}3FP9Eog|ii|lkl2$b7j@}{$w>Qvvx-_<9B7L|5MCPg7EB8=YrF@!=WNEvPhB`&Gdf%D6T;N*0gExcc`-III} zy!0yV9*YRI@D#asfDUU?z|Hq3Q3 zBzd{L!Nb3$^7)6~LVh2|?C)yy+jF({z3q}_+-sg4SI5f>lW(v3dA zBS9fh@5@z;av=(1Zc(8hniNSU*kB&Dt5Iez-y`dx0WRl{TZN^4bVoJhZD5NGK#xZ} zR3)2H0<=mR!6JLkj#+};_2w<5#41-po%eI$QW01%Ry{0{p^Sn&r8;$HscMxd8}ICA6ms~Xq<81#}On{N}} z988^mHP`m0w;5x98B`5>}X-0?T| zr_EGV&{81<&lsqOuv)*X4ExoI~aXH*noD4Wdo^Y44JWF}c+0P`@6G z5+-6mjenFL#YK%O_{2-|7+nK{g~Tik4Ad)o;pyMfjq%t$m*^V2tV&FPmI!Uin`r7; zZYGs-SpSI6Z5U%lyj|!?08l&Li0_&-ef}>v2RU8w5a4CWqp4`buD*ZM{6nK+9Ip#o zhpHgx%cABDP8y8~LIE-s3kg8sA~$PjXbd!{J6}ScoJG%*LNG~AaHjMcm4%tg1K(2z z_YE1LKvDn)<IZ|4k7 zAkA=4JXBK(A`?GVBmlCJ$`pCDu*r#a2yi6u2)ypRWN4u5$h$-f!#cxZb13!tA&Z@` z!Ed#GHH`+Rrotnsz{Rykf|io2EC97AZ$e@Qv{Nn%6t&&4b0;wa&{Ub!Iy5iefB#4z zNk`BPB7$>BNSHI-KoyL)}c6py~izh+uP+~f!uUfG>!q#W#D2l6~w3npPkd*2=VA^ z*>eaR)rIQH6_H(N9^faDIu((?qsD5UC<;S1N-czE+g{G2+MHb(r-?qRjE2^rP@I=L zn(xccDJm{5o-02BwK9G`hAAl$z-bghz%^!4;|eGZpc_8Yz&DjYi)VJDh9iDm+%Wjm zhg4hiM^Yu`TObLtNU#6pNC+fkE1@^!6;JuTk=RfgRTUl)@gZ_8BFF-=Z+cWCNxiqg zj;*dHtOk=%fNEP0MmyR1(Fd`aD(hHnps98YT$Y7%51R? zoVHSo1SAt7FO6{nGS#qoSDfI>m*#Fc4aUM?DjAuEaJUG#neBJ zeQM1l)&$r_gga+sGtKcFO$!)qawH&w+L~DgjwBRe>9cCXX{vuBF>4H@PRKuJ3I>c3 zY{zFz6&$urj0UHtR|ZRbObwOa6KP|d5opsup(ZB#QjPD zkmn=fTtZPgit*sxXZU1Sc^0 z{P;U;)f6U)QAkudFm3pQlYfyJP2s$slB$zBr}Pb|Q-T`Ppdvfqa^Rvhrd(v9N|~11 zNNu~smVqpo=FJ)A4T}EfAAW@N)({Lm&TT~WcL#C%fZ;ZkdPzx={a%h9fp~4?Q5K&V zHDf0{wL0L$LpQ)PN52yCo50)D^ZL_WF%NhNIa2E6HWJNC2S?7uwQuAWU92Ae4I>l) z$fooSVjetj!(K|mv1^c6M8^;Cx7FXg>N|Smj318t1$?<1MILJ=VKHjbcb@Ng7Yk+kqrKk^NKNV#+a!$Pw&(Ql7B*|5trKpO}Mzqog=9r;Vg@_O^6Xn z$ZcvgWZQFbkDT%GPh)31a<{f!8Rs5G-eL@hk2;>wcec&`_npzTfM(*~)fiule^+CC zErtyHZC27>*SxB-U$Fl568v$?&xh!p@z?y>|C1Wvkm@M=IPxKv*`x4(^jrV_$p6Wj aOv&JW_@?fLL=-LC_RYIhA8tH!{(k@z|4MWK literal 0 HcmV?d00001 diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_y.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_y.png new file mode 100644 index 0000000000000000000000000000000000000000..e16be2d7cf3043b314ed54f6f4b2db5d6cd38849 GIT binary patch literal 209620 zcmeFZgsi}rTI!-q zHLahUm|L3|YTdBawX`xcH)Ez_q+_DFVPI|joQt0R-~Uc$ZmCay$LE6x3UveZMDT%} zef0c@u@{~-DSAAPt-UFt!K;vgTDC%2yU4gcIPi*~=;v!$cz8dg-d!22_e&th)DV2S z_~^P9c}n3o@{vf#ASo(^$2jkGn-?>)+6A|KGJc3zHMLg<(j{2wbwyaY{#yIwAboVi zxkf_BjOL4dP_LDT50C#pultyI{AP8(tYw1&;HLhP>%&s z7ys{f-kx*E_&?vdfrG*Df4+gbO^!m2{@<6o;Hgjleuexg(Cfd4LC)d7lR-`aUjN0+ z@j3jLO~>be`mfF$AH;tZ`1lrHOWPqaM-FdeC z@K+;oWHUNbbHQ;e?CioHq-Iy}p(u={41va!9>-_x^Qbpd{O*Z)q^pUh0A zTO&Gqdy7U2KEFDP);QYjXQIDXQ?XRdeFlrLaHL?V=7=x5VzHcw{sfGGUH>~A=SHdI zK6_BP+Dy$G%g(|g=;Go+a9zIPEk!K;Oq`o*zzlum@rl;@IOQV)Uii?ZGS&bC}W&}Jh z`3)B6hgnGLjyTN3tn9CKY;Bu0_N!WnXQ~w4!}NF<5eDqQr()+4BIL19DBG(fBqS^A z-I7~7hb3dKL>I2nco}vlV|~AedL~%_e+p+eR~O>j47@3zHC$?8vEC_+?i3~?L6bU} zL|ZmfG1|@#c+X?Fi$w7{**fp9pm}38+zvJvje1g<=+ZOuw9)WeGfy1uEsZVic#^r| zTTQpVeQI7+)Y<~?{_N?$Jjg6r2k(}u$w2NnJ8w!}o`riK3iVFI&dzRsZ|ulFIXSs> zF1unPSd{Lq#biT$s&wMS%L{Z~o}`YHe0%c+5G3yT24-gdPD@oK=(U5bF@Cf1pUF&g z&Ev&GW|*J zl?(KQkVM&sc=ei|p2iqKVxa18c6>7Xo`)v&(aI|o=!k)PHyN!gi@T12n(FWD#0lWr zH6VuPvDh5cM@O<6-{U=x+O4N88J1afhC9w1bKMIyY@_Gf{{CuqexAlbzxMTcX*D(8 zc-U#qvbCt!Vw`S^Dyi!@nhKGe_z|YDh!#Sj zD&7NgMqj_nH8l;5J%!>nfs0ycrp{TnSEt0)>dREtRbBV78+AzO=e|lI zK~op(MPy#dxcSXEhqU85ohm-HLMCO)HF(bf(!XTb{Div8Mz4XX=}20?fr-g{3M;%{ zHoTB9OQ^1{mV9vqrPDK1am2>L@})88R!gCtaZ4Ee(uPFYiSI}VLW1>AI^-$&BH>K) z6n^?Mr{9-&Kj*GwEHV5_y+Ge>*AJIj+3m8bJFnDlPe+;WYGR@8kIgr3k#KWyX+hqv z)L+;5@~y~NdoW*jrNixznbdjtbLsA{4DIH3RE%0*ykbWCy1K4}+!gm0CUy8o#wWXp z3(;Voqfv*2g$3a{KYfi>1=qZKN3V&yU&GBMqR)g{7DbG+5>~UHG_{i;#tqZoGP} z;R~Zr3-rWk)GIlVGgB%wkS;7KIhqdW9ULU+PLT|NNZKA6J1nk?!ibNC+A6#149{-S zBP|RO(FeJw)tfGVXGu;`5&io7)#gIVi7!_rea8+K?eethy-Al^BbX_!(WxpGi^F3r zUtRjkX;$Q>#5&&N;^r0|rNYIufc)FqRq^xlJ7B$licj$8nD7c`)P6*xTFSr&!5_|T zXSP3%?KbeCe-}yyDf_6sHb4C-_rooyKIq^(q9UUad@hb~JjOqoL!ti5uS!7qhNlWM z?7XI^?x5SW24zO6#7r#$Y7goY{XZ#rVNSGgFNOagO>$|z!tzJ666Bj(>j~83#O!Q3 zx{CRH`?WUqNeEkiSqaV`>@^L%TfV=h|<;vF$ii7Vmno-DkGvTaX^b0zHHSrcpGhG@}s zvm4Q9Aw>1}_SSn`S65n<(AL&A87|EeL%P+o3;!fX!gPDg&|J*POB^>2x6%BMhPv!&C$WqWaF&>n(hQs8*A$?@Tj7r1WY=Q#ljgri1`%Tc0Hk}AIQ@d9d+0q z_iQOds#5XgKcxF7y418Zs=geJvAHS@;TklVn=`T7{z?@e(wtI?F;MgOpj&HwetFtr zIzoSQhtuaeJ<_HyR8OO7+C=HAa5Y>uG4z?zt0a7}oR9EvMo%ovR z9HhHd)7sJDRt<88Oj*zf+`axlhG!i;eSOz56m$HGjQbnPZRU_-(Fxxgb31aGui6@w ze)^PXZ?VE0`s>{We-a`zv6a|GBDTz~0?kiF#l;O!qqRoLZB|y$WWrCMJ}oRN5`u2p z)6*jeWt7@K6-N79{<)z2&7PbE-i@_n9!DqrI4`gBSMPo~PZ6El zI~K)es?r+CnlZKZo<{jfR#q0Hq@7c> z=?%G$&t{_31MvnW6nP_ysUYEoQKu!fpFihMK*SUl7a#7kZZ4FJ9qtbl8p_Ja%h!MX zAn+UPK;KAwxDP%InZuDojm09Wd8;-SB=EU-H zNB91Xk;UD)05Z3Iiwrk1Hwe-^*MnVXO1|yw?f7v0$Qg)>i(e$+Vu5BB#{n%%dwsSO z`IYb)wFHy+Putcm?%H4-m>%x$RE?%tqbi+uR@IlpqB-&|iaN5{{OT!%K!ke2@8&8N z$&&UveFnOBNGKqJ++Dvyy+)!zK0~42?QktlslwJ2vW$_<^c(KN!h$pgW!%^;SygPB|3j;W5v ziYBse=3INOMzpeo#HG!pv4FzB1Fk zh4vPR@LZcYg=h|o6Dg8$4e(`Pc(~WckGD(9%08pfXAch#QLwpZ)$29$k)A4 zY%=%~4s!w?UkX>K7vIdxELAS;N+g@9_azdpcmU6oPm41p@MK*rS0;q!zZG3@+MNHK zCY$nny!Q0RAm69irMk-g~QGP zPYeLG-qoH~$=5mm28$^9XLxb0tr!4gPCAWhlZ_2Hz1|wn4D!7b&v z?Ac~8W~mfCtgu~R={P9eXDcb1xHptlZ)Yzef(iKQH5~HId-p_aumIklyKtcnc^LI7 z$1<_HcYT0)Pl`n_)f@T3Rhtc$uJlCJ!VmI>U%Bnq9JO4kI~>rIkEhZ6NX7LymrVjF z1Uj+>v5yzN6?LXal3gU@Q{6T9*?&Io+yx=aX!?yMgHbkFjIofB2V%X#ZmF2Cz-mU~ zwTFjc?A~~t=Qa!{dAcpv=7-C!=H=x@&Y(zLwyFU$;&WQw_P$P^E$Uwh)eToPjIM~V zzmc~S3;ORIK8cmm}>wF`Ik_QVC~Izqj5&8SaWdGRpp;qy6jytzp5^5y9Z z(*(xJ9jdO?i`zRhaoVlnj52vp_CEjYPO-_JT~htAKlwyiSy`#f^3F9HCHGsx{l?^ii)m^dy#(`Ix# zbk1PRP{?{1$LC@~2;B;KJ;w7m{)3m;TyrQjCTd*Lz#uhIv{%&w6Yuqq3n0Ig>P0+? zq`zK(O^Dd$PcKg5VPj*bZArEb>|{MMwzRZ-=W*fsJqY;xvNI8J6ZJmSFjPtB=jYF- zD=N5-(Lc(a;oV*9;169Ksi3~*BNVbT{_|&A~mU}P0Vz}!eh$vWGtyuetsi$|H;;f}tVCAG+5 z%+RJ~(L(VIHxDzjYy_+Edzl2m^KHcy3Rx=6P(7^27WeN`Pza~Vr3Eh^%)ybwYGSl7U2k$Q3|SC`kp?+7J6hv?dP|mj4Pz1beXjL#N2T#y3M%b_7G-yE}nxo zSXktgy4z#8SzE#)BhxdL3m*N1rg)2I7CI{1%zbhv%@qbr(iL=?~te^ zCs2BKeGoXSnWa{4EzLR&b1pS8Gh}26?QRa#=wFA*?{}z_a^r&|A`I7T1qB7qSy|8Z ziPzcr9|r`bdHaTvJo%p&#TJBhqF!61Ql6H_FN#&7dIFz`LtO3eJE6Cd5Aqm$@Y zg-(S4kIqU5E6>bQ@)m+kpMpK$RB&){UtSjb~Qjp=r=DMjn*>ubXlz75zItK~_9 zBY@Vg8H)7#t1a~9nRiXw4)(TIHiyg;q0n(SZDxKbYkR$?q*$AO< z0BJ7(nNp6*l?Eb%k#g3<{WZz9hCAA26%`pO3$Ej}9=mvJM`f!!!YV3+>JC5ftd~aB zHZTiS%3Ke)NO|nP2M+sxr|G9sb5Ni0K$9K3e*OBK_LVDFhz}1TS1C zV@8+uXqD6TvzLf-31utoEus|b@2V;<`7qURGea_tFIBZHUv3_La!^pvho`jJ&W9FT zi)w|2-Dd#E^yxb9YP4I&bcN2?sN3&%hKZeIKoRrUOU;O^z7Gz52>|{4Pj^SMU1qW?Nwl-fO5c<9?QIH*L`cl^SpOUf{XzP68g6bPXbQDk zV{SQ4bVAb0OKwL*02i*0UQS9nec>8{>j14X(9DDYc6@VP-Tw0r#oNo9o7YCeL!+Z< zRB;5d07IsF_a~l-koVA4c&t$O=UxC|B*NJ|e)6P~SJB>{!*SzRlEX6K zt;k;-$8C2Bp?l$;lbo`-?H1!rhl&TvtWp-s9y?w0ISr2->MbrJ(v^kL7}~)vBO~** z$XL;nZ8G95vs#Mv4~LlRq;BhqNg{af?#YYb&ooZY0zG%GKU=MUP!=FvCCr8C4I}xw zJ`BkK0Mi=^g-lFn%tp$SoJa|vauqsVjMy>(kYzh_^SB^h(LBj;4E1n=@Zj=h`*X<1 zZ`~qM6N!yZY6zuPoCsA^XDrNHHN+MA41|{l&~mjOY&cq6Eo`+Ld_M!!y4Y3*NMnDJ z?1=uT*VM_%t>*TUt|<2OC<-59MZ{?fp|9w48ZX&~92_W~YuI zEZ~X>%ky{Pl9qGa4q9@Z+YO*w%VgZSM9QOte-)+&!2jnbbrgu%YN0AKI;`pl%n%3N z($&+``s9wmVL9cMD0(x7V~EdoL)%GA>|$+g?Ql->%Jc5WNp6WVW7_ zQlhz*ro@|VTDrS~jxw)K+o{W&{Tcm}D=DL6E@gZL&B2s`;{NsFB(R5{qB*TzTR{7N z@Zq7yN3=Zd>7ioNs|_9=9!~-csr7fFuI0L&e&&w#35o)|rg(UW)lh%Wk~s=0#yXZW zGQj`?FA_$FMMg%ZqpN$9it0SvR~^8Nz@VVzj}G_JHK>h&%m`=D ze3{-4$HQXOb8ca%L>Ridbdiz#J8H#Cz=~2T<=%jB3=9l(2XHwKzzHTRpY*7{VzUwN zl}R*r+r2?YgZ^w1m{v_#@4{I?&*{Fc@#xVTarUo9$^r@s*8ufsvnJnval)WCJ@oEQ zD_2Qd`G^D1pBI2Browv)td3lo%xM_$kOwB^bN1TawjVCHxxmQCm~Pb($$9}Gz=OHI zEcu!~yhfHuAh`)3n=*UsVY<8KYEH^+dl7+(2fG_d4Lx<-OO>zS$kJV7qN0dYicQ`E ze)<3a6Pf**-_u@z`>=O#xJgTk1tgsy0g(Wuvb=A21ZBw?rkkif}m7tF?q(HnDZromuCRzN}aZ{t+Sy` ztj`Z#?d2hf=)8#V~VCKwKqJfhB1(NSM z%%kI&4O>fN!eMl3&-b@2p0-e&J%90{;HxuOm+|oK_>NRLl_Zy`9qenP{YkcgNtCNf zh8wqEESve7smv^wrGf`+gb)DmaTqoqdSKqXb?YQdtoF;_F`zHIL$Hklox)-B3s)kR z=PleVr%-p=EshodV{!eGb&~;k4njL z>$tU;Wi*^99Dq5axH3@>DCwh->QiD~N4YIxrs0thX`l%z(1yTtR#sJI@x5MvF}L*j z_=$AI95Xw<<2sbULv@@+f;uXS*{ag0b8Zg>1W44|M;ETpuWX_u!{E7xHiYYL$V z#pc_-Po6x5_QoUPoWw zxOilz9v(JnG>%F(`EdZj)vJk+&*R}xr#sE-PF3$Ma`%oE04eOtWZXyd1DZbD46n;> z;VKZfR1Y3Ja3dNUwYsg(Wy@yqq zbA8GO6})%u2<-s(_YMd;s@T|A1+?>|AG_E_gjMLAKg>w)VwvGxBBxmDc7&mjB&`*h zkEsvlX?u>0;cP9A$U^F;tP_E93w_NwMlU%`_qLS zBNJ8Pe~^h-tGwBl0*}@%Bcrzwc;=caEsdK5II)YJ!NI|S z3SfJYIO~tyaZj?>eu)7`r_P=ovRT^<`4ef4-`c(>iH0da%S(2wfj)K*q79GDjW2@w z=FJD)3pK6><-MHC+X3}j(uYe&hmvJbOGX@^Ol8VtD2U%PhslU_#7y56*WK(rQ)7oR?pWIJ9z<;MF@1(XNpIVX?vE)}JVhjohEjC;-$SK>EmU zkW?G>-V-n8pFe+cnJSMaBqY3MFXTU*Tv*5gLO|e& zsAzYgKmXyj00EbEs!aTSjML9f<^~ZDqExd~SasoqMNCXG^(Ohvpb~ds%jPT5G{Zo| zlJl9S?M47I5*2C(uWo-UG0%zSbyBd24G+i9@Kc9rI!!*~y&<1fw&jQg^x7^f{iDMJ z+ZpD%9rOnQ&yTCPpcN^Xn8l0?ZL&l}L^Q()9|{cKK1Eyx8;ZNmMufTbcN4dV2loyO z3w!=_rY%ZeNgP5+1Q-VoRzEWS(c~3i@u)%39LOUy4|RkBh}Sm=l~_1zhaG{BeY{#< z&IyM-IW9+Z?O1>6lHj@=MBd)e(c1FzCs0?sp`x&ue(OoLfW&+Ym38nbDGJ?Rs@Fzn z@~!ZRQ7g2LTTDz>pdA#ZC96WcN543ERtlP2+V;t_m%an%TST3r;y+5i^T67AUG~UL zNeN#fn&ZWTS7$zJ<)spK*VUbbs$LH?i8N?aY5l|1E<`XCN`(sROf?2c#+;Od0i6Z@a?=d5VNdJMcU{~Q5wcNSWHWA zy_9E)l}m;qVb<7RINI6WodC7t3-E8!KwS4~JKEbngZthFLPomuxn^2_YaG9ZP3%4m zv=C5MfqVr49vL9g^Uh+E()jMo<I4J?_&oLuOw7zl6Nr`pzlbJ~bO0mb zlZ#l)hVfy%cm!DOQ2;3xJw3fRnqsCaUsn`P?mR+yLNAp{79&tw1$zD@G|$(i78%*`F-N=Yg9)M*AD#gre!<1@vdtlLWqJ92ibPDV z=@1+6-r8Tha3YTmW@)0wxsnK`H@X`pSJ3vSF>wPUyJ3`KijNfL+nv1yd}^B!(1E%P zK(ItL9Kq1~nh{vz0z(s87&OH26Q{$C-@)l#(1t70x_{?5uypiHP*>|Xph*CH&ml< zF;KaueMZ@Z|9V&t7|&C#%_re*k>Bw3z(QP zyv2R1#wT;d*4BYb4T_93y3hJ202KZw01BOVEYswjh?^P-!(eKK)DfxAR?2($>&Z`} zo=oMdzcEnlGpb^HFwcz`J31mxf>fywFMCU)qlsxWs)ys#Rj+U5*}(1A0DV_|bm){e z05%td@`?Ph*p+kvfjeytx6r|+(fKJa#%N~9pk;XZ`xg^V0usi#^(d7zY6{;Wri*56 z_X*D-$9u7p&!HeqOitS5=t9|PY;4RWT!WDN#&cFj;mF3$P8i^p3898)_An|sG}L1f z9Y7?7bv*Dz;QfOY9veWL00=L!!VFBcXXRPQ<-D|r+Q*OjQYkT^N>Sl)Lx+KP5D4Rn zbz0;^fb>0E5CdzYOxFV;i4*a_x?-I;Aeb*RudV(4YEU8Xdg%`nGR<9)^I5Zvc=!3y+A)Oe2UwC`I)8|=zx$n zM%~*+F5vY7aqCJ09+*!6@vs)|ggwTFX|_Q>&gHJ}9;nV(sc+T;H8%68Nrs^Rdd|O zrtn?4sp&&cRFfk=FHL>Je|jVe#Cn^qSo(HIOBXXWnnjS@m<_F!aM5>h{&iH)k3 zYcBv36Gx}Lx4WzLHU2?uDKyZVtgP~3gwX*0L<2)YZuy27PPB=_NhJBBq4vBZDlzQ}#4Wj>y( z-d`21So@(1tmeV>iw5O z5fnTD$Q1+TxT#sDOs4V%-In)H>cyiuq_=tpoSmH+fci;O8Z0jgMzW+gRr=(uN4{TK z(J;VDgE>ia82Ao&1T9&h{?DZmW$TzZ_jG-Ed)0#xnh;k7cV#H=;#bo zy{ssZ#TEK>W)-?+B2ag1GZt1>br9Yj7Gd-n4RBzl?YAZYQoU2Lp}u|lOLnq8x&CeD z6i_cOroLXE$lM#~^(*S=$IOwwZFg50LeJgK%vb8rUn@cz&C7u=E-XT>+9B< zzC~6B`7xdSRBbFdWa!BNt8?ei<21~comdtob9oJ^sO$&RA{yGefg%E_HN}8hS!n*? z0iknV8)jOa`*(_i9I$maPahYppsWFu*dKJOBLvpEBr_?S+lj`lO-(`N=bJ%)2c*Ol zPyP(#eMEpy1hH{BJGK+b7|gIy4QE@q5w^$(Q8u6zbh8R0ERTXMFGv>IHXPsJu#?Q9$rzrw zkDz;Q3cPt--{kyg{^s7-Ys_O`C9*}6gN}eLJ0thd(W1{~-Uw|Q(MyC-?9kM^7gfmx z-dubDqn%BMz%G?SX1JUx&{ZJ%$pygSV@I4lJzD7?>&O#4={5IGFS0)X@E>O*3yO@> z@)Rd0XXH$^{R%mx%`M+Ouqh`6&^wfYJkHQSpnz&$!urItbn|a_cr5vEug^ykn^G#? zJ+URXd6qDMg!>IBzL=9Bqh{>=swo4qBuPQKxwW;&rM_HsM{|)w&;XsXB%>z6FQ9Zox06_;>if3&CX0G*W z8e=hKoSk7KAFBOLd1v)e=Ts&*T|$BP`US%@I2X^zO>pG573a5A^z}fV0mQr7kOfK& zP)D{iPLUu(XadJoTMEYM$1WXLf3Sni;7WG8-LD?1SLru-Ip+9mleC?*w8&xdxZ_L2 zVsP2n#bu%SPTj}|36iwD*gsRAeSX=M2M?Lvz&5nw2?&f~8p!9q{I|E#Q31e zW^Q()qTjuH4F%UA*6D9w?gqyYsOQ6rstNLMUhEf~cn)EQmHLHE6(jt(su27ATU8X+ z7e|IV@0=r0OBAakST@+WajOc9axxahY~RvCky?U$nQoR)Bn&Bo#GGbytGJ^i*Yocv z@KTtwHgtDiMMi^Pc}15A3Gey7_4a1^T~2D6T~m0QzS+G^NtrpSTuL~@%4-zZX6kng zim>?k`O}u7rs^{jD`*Fx4zPe*tu2L8Wf*A(`rtsZ zX;d%1PdzA1*T4xd5K0a5=dbX|*)!ikyHG8C{@KVkE{+UnNj)i{Urm`P=cQ5J5z=>$ zj*G^ZGtd6aEeSk;*-nW^vRGIXC~zh;z#M%+8{!vBBZ!uR10U#8+y+Az*^cfh&$7vj z(2&dwszKa3r#&$-A(yj%qq}ktxG!941+m^z6~n>&B!&igB6nzQ)RhrtK+B~oUMqLr z$?ugXQ7JUQAR~)A+P8!A%gnaa5yb*_cpLgjR)ZXvo(EL5{v5vF*RN9J;(IEf5&JXT zrK4+i7a>N9u^{5Kk?`qq?;-f>1?Y9N+5j@i$cAAs^lh)VukSnW$vTC`P{3gWzm`CI z!xECdnEqz{yUFj0&4g`x4~$Gb>02rY6$?Z;R*UerF00ee3S!&^&@3g!ZRYraow2tZ_$3|2|8$L8RyoItHM3@t5Z)j#egisdOFA& zRjJpt>CVSVQlR!O$fD%Q*{^ss|aXHk$pF;n6s*|wf;25&Rk6aHMCoFE7mxu zbFA@K(1C{e8!$fub;H`C3<9q8!Z&$*yVkcbE>66&=Zq3DQ}eF44t6;Euk1n6ckEnEZ9Ro+kX zs09c5Ax91dsav#PYYm>kAd1Ij*ZO!A2htlcK^g~3PHSp@O7tw^3U1|eg`RdX^^0x( zlBT6)etRf5tKb!+yh11VCz!8bVqtkCP)e+<^*uEwC?0`%iIpZS%Qu@5NXycR+bEDw zhuw`1vtfR&4TrH3p?&+g5Lj3UO5q2o4-el=XG$l&>1mq=l%c?y-RgY<%A*Wx@_TPw zsuN&1$zWtR8)ir)oNOANqU;vih?{AL<7B z4L~@0SU?pQyno+4xlC6Px6cvpJAmsn&$dFNUXkuf!D0}RK1VR?=W5ks!n}MMpvrw9 zm45YQ`5+Jlq=n_xRTv+MXs-FBlSSZR527;pnHP}4A}lO?LHp&aR}0OW7lfy7o2DxF zDw-yS5_IsZJN~?rcBT>NUa&#pfGE*`xLHjy6H}1LW^OljN0aH_DmbwWZyfmUosM1h zKZ7u=QCx=HFXSfsbmrNurbF(3wBE<`|MtOV0Z@pE)m{d6vI0+u=bdnF(x@-f@II>> zh0~;xn3!+24N^7?AVt}EQtGvWRMZ5g^{RfmG@xF-wt(UMJ*g}<7*k4i_rRnuH8q7V z=a;7w`Aj#`(2C0YCAcl7cbxe7Yf|`5J&^PKMhG{Z*?>ra@}a9*zrBbG8K4}L`yJed zlC9|*`NnsDYHz6~%$tbEK6ko|+veA88`)LBvhrD86o|tDY=M}Q#APb@5kv3{%fLM( z0s^B{$ixQ%_7%)k-!nNOVj!N zjD>pZP+QuKA^0VM2a*EvD1#9I2_lJ(lmWFy>+JpnsNZE6w+3UV!%PaOh};(__DGxA zbpIIq((3=Gh=bv-;dh(V2L4t~6=K#pd+I01G<0|r6(q&Y*jDIHovqM59WzI{f?70O zNYVtN$2iI}(7M6koYfZ=6SI)dPFVz=5roy(-dr4^b`jVDz6F%Sz?mgj=87x#77M*6 zFO{byByNQ8JkR6$G88+q@r3>iKX1+6^#!+zzXzMy89A*?;Hoo$0KrG`;My2acgC&EtsQ2eRG@5GNmi zs-RTPzm1Gi5a#4eOu^Xb##aay=gM)|x8MUZ@IKtYYYX55^Qk+4fyx8!P;(eM>-WV) zGsSFlQ@f<_;-0VX#qm0}s;VlIa`MuPgJ+&)|3%=A{|fQaq$f_CI8KP>%uy6aHiiOQ z&b;lwJ^oe_;ex(%KW8hAradF|H1%iF*_(HFclm6DM$t*&cL7KyGx=8GS5a|SPSKd5 z@+-=)i@%lj5*58liva^LZ5Qt5zEB0Eh?i}klkpoUg9YYsL3DoH=X~83qxT_=k*TSa zhyeru0^-Gt`Ss$YN_MrW-Y`0#v@1_-+BqA58>L!#Ax7^$J)9fVa>CfKc?zePco4$U z8(7zNgr%e|{~jkT5i1Y8>lZ|f1;HutaS*vdUnT)ClAe&Z6Y!sH{g&<_aIepy4Q3il zWTpX&$=B%>Ss57y+j%8TRp=z0FcUN3gus zdb0ePYSjOyL7vsn&=3y0p=0fbP0ADKZ6$Zo1RTj9%^CtnEIW05aj zUTn~liUUQK+IOhZp+FB?G03#*`4{mu9XiOxa4wsBFqXanrH`{bIz@9rY}A9d%A`H$`rz5pMmEg3aj**3 zhQnx1AobQohsa4+5%Ul6EaUSpSa$eo%*sj&PVzczRyY2GSpgfFNRK2`mV@Mam$n+X5eE z+Zza^8O&=+ek<$if-sSLXe%EZ!SBvoAtLetE6n*xz?yFW)TkK;88U!tzX4*BrHNvX zJu)sX?(U9P>|IVy0;q~7z}_+~m+?8+wlqL(2;im%qdynf>8bW7O*_LdtKE|@J;~6) z?+(eT1z!I0OsR;N7(c`W4z!mL;2RvUl|cWFF!OkXKx7;Bwe87hFbPokzV-1DfTr^+ zk6yjfi_>cQ+$2(bk$F5FeVs}!HBc`47TGRkH)F{v$QPI6cZ1tpss8}9@Em1{BiNI2{v*EpZ83sc7M-_X-)}5J4RYKY4vU-6n~%= zxgk>qDM$H^eDV{I405hmQtFDvK(!6QO+BHAsJ+G&9$sD~^G(1G(-98DFXDR!1CmxO zV*;Kdc=_lvlc1C#O{9$#@U%cUfJAMa-xZIY^Lm7y3d}api+`$%f-JK4QOAi*7PO8z3KkP`T7K-wQ}_tvIa2BO4-UrX<}Lsl06<60r@&mVMotqHtdB& zAr!IlALTB4Yz+Zq0rWNdS6~r}1e{9NExM2NV)|h^$O#O*9L?`GYSao{r?bRd<0oT( z)>8@|$usWYa=8dyuWK@W98MH$S{x3mAA9j(*n`oMKrUzjtT`Vi{;7Na(@Sukgp^5B zGBaQGPJjsyU#fGAbI<6)x>sUkt}dYuYG<0f%IrJ&0@Pv&du?@l`%<;G5+t)b(P9^hV4qNs+|}z*!y^e0+T2OuF6}co@J@$yfk^mS2G}Ff{ZOA3*zC zxGGP6>o=+$;O_MWr90ix50n=|SQ&z$3^5pir5xER_&zshtVj!Ly2+(pjIBJ*Mq)DJ z9Vv!ED;Z0KpnD(745l@?-{*-;G(fC(Ryo-b^ScrQ6IBPN_;Rj4XD)aNjvlyFS||!{ zfW4awuJdjE-IvvG-n@xWQN8%A)TordLsu-X(?r=!YzV0$t-d*m&u%fA!49Z>;&1r$ zqMN)lkmCQ21$lq@1TU|TO>FJSDJk5UO$vHH6hLrR2Xm9aYIF8Oa&BQA!cYjAq^Oj~ z{7m9`eT2>-At70#7nMK|hyI9Z_4>`5S|Aaio=5hhc*=Kjkl}$#@J}A|2(sUqaok@1 z@aryHRhD`cAuJ0-s8NqLI-hwV%sytROVT9+&Ku~O6eJqp`0^!UzXZQM6W|2vOy9y< z7ZXyZ8B3%BwpK9dxfUDu)BPNPLZ3z$HACiL{52i}@t%SiY67TIWCs8&etB+3u0Zq% z7w~u|da$*OFM{>^5Iw<9LIn*CKDVAckqe&soC7*#YZudRi6TNUYH zSXKfqWb2q*nxwgQVHEZeRV(dr5DwqW?}NWeQcI`>S(ImM8Is*3F;OO0!8wno2&X>I zITK=kcryhudwYie=qG%Ol*7D}#xb~X>dco6oFSE0tpoXgqK_D4z|bZ0=J#r!Ip`64klZlLH1o{@J3csV zH({A2OKuo62L>3d(?UPbgT#<9x2^XDf(|Its|_5#5zLb+Km>x19*NY$x|PhvHqTM6 zI8+hDL5|pYVU6fB=qI@#Z^EwPMcw9ic@D#1o*xHgwvx};D z8EpL^zC>%&%|JsY+aCQkI2_%`R4^Z;y50Pvo~ryiNs=4pvv<~i`7-k`+pQ$YmS(Df}!uSOCrt~t7uvF!N_k@;)y(p94 z6XD&NWylKd@>3NHpl5@nsc>iG#fuj*79ct2bDsUd@0jz>ak`Ztn#Vx~ObEjq7s0OD zuVOh;?J^X|qxadxgpO&(3OErVJ-uXr$}x%U9!+dWRIXd30zyki&+K@zff3OMY#~~} zRe1UN)d$@YUIsJ1D8K4mMM!wQ{bhlebQbL68Sg2==sfB{Rho@(K}(e9Xom%aB!$;~ zFU7#Jr+`wxJq;GU62eK)D&Sa&=0`x-o~v#Oq#* zgM$Os3XAsR#Pf&0%9+;tX7!|#0tP7GJj26Zj+`BU6ppeAv;hoM8xB0e$$L9FKp_9* zIt1m{gAszL4(1K(tXqmuf)01*=mjhzPH*LvHAZ**n3{Ube_u=#C{j2cRv!96GjJHn zSip}$EFr&E91cGOfFYj?eki)#Ee;v&n~JJ^AkX-<~6&t zv^0Ef+sx;_@aBo&{z*3~@GQti!J?<`?YnnX{L-Wo&%kV`BPFyMWSH>&U=idR1{IN3C!X zv@E;^2qi^0RY{OAJg7SnZ!3VWow%dxI5-$W(yPvX20~*L4vvlqKsrUjGCE*l4={nr zi~dmtr|h$HVc`*4D$vA3$^DK_PKhvq*Or3IXn=+9Egp@M6n+S>F!%2SP|i!S!&+fh zbu|o%+hDIT&F;Jg7lYTJTH`w6E^-*wTGP#9GVs-1q!8GBngaSi=-K37GJ;&@4khJd z`~vVhL%39cd+LHVY<}OY9Q0hD@oIc?L9Ffa@YN3&otAma9V*oS>+FkiH2VRu@H3X8cf4XiWr&Oa?D{Ho?#lqyT{_< zMUdWYEiIz>+Bzqf!Dou>Mi^g;IQs?ptc~)%0$!{W%(FXkb{W(=|F!`i$((K!!a4%7}rk#svGg zum1QSO^IAyC$^Q8h-j~*mwLl?u8$U$Peky;;$mr*ni22l_OFw|{=`A$c~Z$u2NrEn z?AIHHVM2#{1MvS-AX!;ad@U<1>^eAR<@$rj2;JL$o3y7mU=RGEs%kVtw%gI66mINlILc8(=_%UIq6G=v} zEPD^xLba)c!tywaCGnWxjUpB)=h3?#o9v@>#(-;U9;832FD?0?$Jb~#MH z@xW%Y_3Kf?AOvfBYWQ}bGMr4`p^va?0InN|gae(?3RqD7wo&qD_aW%q|J2D)!22*j zVNN3Mk^8JicZPUw73@+FXu}5-yqOMBu1Wy|FeMl@(kVgpE@!AMN5*@Scwu8efE&)xxq1QW|TiR%i9u}8eGCszPI+f7Q4)lx6jX|xx z0Ez}2^4w5KPEXx49kTXS77(VdA|{Dv@EJX9GtXJ{d2QiZ0uh{1pU&~f?ui}ujczf~3K&MTgeKaI&}m4r*b4 z=A)+^PfsqxFniQ37!wA(6QP{n!9OE(`#*aMh^rF-_Y^$Ru`JLY8b}BP zpHl9#7dOlJ4%TJUI3l91#_54xUaLod`n`ptc%@lV$IQ$+x%ZJyq^{lk0CaiaL4x$f z;1h7ZmRe|!{Ax7aFH#Voi;&kd(L4s8lTB<*&4&xRr@%{zbe!5!*h(Sha~?=0hF%c1 zd(jn)Upt%3vzh4j6Q?obVfn7M6ejpz>ORtKH^6yV8xHvLr#c#bsf$&NV`9*!&~0s4 zz`fx%czAl=0uT6>BRGNlpi9ridd{zb7ku20eKgQNN9w}~ASiO4n8mtrkVSYF1={FE zBjf~sguFW(rWY)TXo97*c7Rd4As&F1$~(OR#BAIOJ3vXKe95OH)}WuZ5JF+->gxK) zm%+5>{zteZ{U4y->$o|89=KV}VVIh1YMN%@Gsx<|66j$;N=iCAR#TH*6zB-s#9yn* z?%cbF3De!x2Kh9Z`stJn#Z)N_XfD?qko_-k`yoC(s(=E_bLTEMK%m#Vi%h}3{CV?- zyrABLJN)(b_BN09w?e~{?CeAI1+ZK~03=PmN*%B)9&tfXyAojQh^=4qST~OH1-_RL zco=nj#VSV|Sj260_nvBEyFFBn`TW_l8|BtN$$eq%PHRCye9VjqPw6U!5&=!;Ti}Wu#D3a=m_2e5602aQIJ(?02H2^c>p+c zt=GHZc$9j_|37Sp+}g^@XZWy#dw6>dMCMAS@daq;EFb6a8J?kFuO>^BM5h8KK42mw zN>;2aEtg@#R6rV6bKVQ*)_gOo%`dq$y|0Mt8`8n{hb0>bhu0dws0S@08u>&F_%ss* zr0g)j-^^fSqCW4VL?n=W24yf-T{U8(^oJOpY-B@U!e_WYBhoWBT2&z@`$dxfKxYkW z20jo4fH6+P!dML%^!Y+6&s&^pdCahAgKvdY|Ff9`;d)Rvv2a zm!Nrkhe#{;l^jOv;a$7-#;Eu4CU4VUF92*BLd|*wPI9#pF4%m?eLnsW3|V`ysP#cH zN8NsJp(H7rXbLuMuW;GUryA12&Ae$9I0eSsdqtMCZzC)aDtQ>tn%nmHS)|J0Z#7ZG zakSN)-~tuV7gh~YFhcLAM;yVYV1S8a4_bsMem9tF4=((HDBarskjOZLQ{Z(-=@Fp- zq5=7g1>n|M+v0%BhWMF)7F4SQ3JiP{&6Do^kN=Oo_YA5k>B2@gqBx^s03*=|DheuD z;wXX&h!{YSBp^tZoZ*a_tRkR91tsU4!I3Bek|iTZ&N;)k`UKCJujW?WpSSA1r{3aa zWS_lzcduUYSx*PS9BYE?WxKD!6T2WO{EqB9e|MWc7?F$EToYlhG?|n z09LRW=B{4*sSi{rwrByM8*#7XnCo2%*HcKP3*76G5z40du3;ecfkb)CRiZi?VDEQB1H~ms+o9gH+X+B&RSevG?`>su1lJMx1v;vtZr*N$fnoSw zg>okT%brSovpqH|rp5pvm4G-hu0+^j;kv*zNG6_r*d-qKH90^A5Zc@^dnLxXFeX8> zq7NaKO6O$j&W(!@i%WUGErf&w-wD-h9+d5l`T+zvs2wSV4He{3BEZh)31B-m@#@!q zKgvI-1+f51*@kNwHz#ib-pPWGn(FqWya1f59}DEx`6doEeLRBn42%Ohom+zxJwT}- zuL9*s&lohGl2tg55_#ay#vza5N`jT%M*9FAYHI3F3f|sP7sJa>a)I)^!NJ>7L0GCK zzytf#%NB!M7||x z&aM(wDCI+LzG3F`eK3+h2KBbDKTA6V+@5aeyZsBc<5{y`mm4^C^6AxX1h1sY$np+! zV~oIlhUAkZ#2bk~pK!5S{n-vy&a~<*|FHCLXA(l7>@W@eL^t}+Hv&h{JqVwyRIBTh z5x}|M50VNED~ICbZlcIs2Evs(v4iZ;JPQv6)c5G92UsetEkx((Cgm;VH~OAV z&?|~sS=xt_8o<|h8d3qu|4T(h#d~PrLZ7m4lv^4|dv@lp&fU$-Dp%EMNz&SkD4QTO zzaYQ6VG&$dgldk_-v)bu3!fv&DzibDVPGY3gXjGamIS0c41PPMwxaTK;?kgzXVz9IK{@EzYa0Rf5XCXs@tOTNYO1$@2*11&F z13Vj`sJQ=zQ&suo9JDh@g5>UEWQ;j4cjE>f>W+a0=?2x|yqpI)gALTwx4mK-p#h9@ zk2OGKU{Q9$;`qpNeEAd+p#@ttQZSwq#WxV?wqVvd6irbFDVe`zjBperSBB1?7%_^|C!cNV^NtKG}Th zedk&iOCfD@*0fs!iZ9&&LoS7OBcxFE&!vYRhjfDo+HsC?deGix*jM{^b02SEj~91J zznunTAwCA=c<^ZyV)wp*rL;^y97Ry!e|3hFk8dyJuuC8xW;)u!+dh0lTIZ>zuG0fX zf^o>&>lWHjaGi*(kJ)5!)gcK(yoVR{ z3Itrg+0OtW>K)b9M9{W~^A3m>so=#VAtw2#hL#T6GWP=KOEEYZh;g7T$69V78-ih3W8*v^bUCRQ zA3GFYj$#jxbsJ!mfkK`e)IR=Hd;#46Y^dwdzG4%G7<@}UUhxLvCeZ008N(zHe;0IB z|Cnh3P{5yx3*TQK=;zajAGJ#F3H;U>Gq zgDdK`j_$t#dJp!>AvG|-gErtGxij!?L5lI=!!yuQ62jmIT@2tJYk(`Y06{U-<5z`C zQ3fChnq}|xl)_%#wRbO@>TsPt@-3sEg+W@UE3HWl?d$8{2nx?%gyj8pR#A6Is9;$R7So0)X0f!5GT|;nqkse0_7FM)ALc_T%m3XL;%6J&aAanQFQ&K;20(j4%GzoJcWV} zumFvG_7=B$--%7IA3C)2Anx$-Eou{V8+YG-=^APlbxU`UL7eG?W}3oKs%p%Tdt8-! zm02LKvTn3zyj@I#=Hv~DH;;bweoAvSbNR!J`O@{BuWtBAA3XZxWhd)eswds$e*~9D zj)qh#uXwMH%{y+_ea_E5GVXLu;OCR$r%%T7w-5RyEP%1)+;Cc(O^=5u03P@U0>5k*I(1cAIt(I<*`>hc4CmzxL~^}) zBIOz|wL%k5HDZVj(gLr4KX|DV-w~NK-61?@?diAJ!)y~z{Vlvs@xa#2nLQ8+)$yxg zRpWrW1n{{K;(R>L$?5s^>(>RyY$9UUB;XN}th7a}%3!0z5)%{U`vLo&$CY&>q#z98 zEJ3qs!EUx^Zh}4?0Z0UBO>}*hhb09X3>VO&5KUbIGLW;rh*B?i>Z(kLXx?XjE|9s? z;FZRK=W_RPRZPOr&`>7y6ZO2)4Q@`b1qd4pxa{sQ6_;R2!r*H8+qd`l`1mBD7D8|W zH6eKe#CUU(l_BLXe;xBvp(|LdG&y%pQT5!e%q10o}pfQ+NuRTnI3BWh#wW;{ld_u+BhJHW?YKdvVPys=IVm=bfeb2td2ACfNf%f ztV^9;rBBrA@k)DL#O%o=a0Up4e{`8cMw;niU8Ef3Oh7f zabPjjjnftEt#H-(;aG`BuYnLvZ)RQvsvzBZmtJq?CuJI!Sm=RJ3Yh=}(bs^gf1bQnHtbf#82V#av(Tj6{-EgIs6FwVb8LM6(>M7Xw zHt*T1`6kfYh;_aEYa6ufw)ZPn5;TbJIMqK3!dcQ z=&>$XR()K(4ine|W~}m#2q|0rXvn%oJ3RC)k5VL1U2a(Q+ z^3~ewS?vZstZu=qVb`cRE%q+-@fS1?gwR42n-0>AhPU4H-mT5GP6yS`0xakY0R@Wz zG|$;#`_*@?&Q?Hl!cwp{o51Mkq@`l>^XXaW+mw9z8tfbs#P>^1an6lOy2W5^bJfig ztvh;rN5NVnNK6Tr)1;eS$W7RLkkYUa21#DdTZ8#)&+K}%b*|a*Rht2Tl-eGCp*4kc zU;oVfRZ-^^b?6ZC1Xy+AUqNld9AF+0X}J3n=jI$=8`W0l+QHPiYX;Xb0r(5tUj5_w z6~@VC>hQTeSTIa#BXuEU&b$l~^7s%*er()XjY3>(9y# zQoUXT9bxq9(3$YT6cWtG@;PbiU|}+W)lCZ=qe<_Om7{xh_)ISzSq6?1W;E*u6(1>g zTN%@_-s9Y zhXK5z81Oy;-(&-6X>0cG-mQI%r}pi2Q@%%Kv<S5kF2x_X# zc;D4Qc~bxw$L9p&qoeghf?f=TL0TyMS`Y)GHuwJX%D8mPd{x16PJtV!*rTrw)?eDE zx*O)=272(Y!RQq*EYJ^lz-256XxHwc2t*z@3V!&Xem9?a-vE|sWiF$@16ZbyruRYT z6AS1y=}T|lBtTf^26#QZ_<-~05n!Bs0+~(~zgb>UXKgSYBHf?-)Lh3M`h~JMKV8zl z(v-H!?#Mugje)Uj1EZ%D%Vs_`J>BEV5&vWOE%*sV5OSrcNkfRN2_u?aa{TM!?0Bb` z!Hy_@AaMrXOuGcFe6T#a_l;l;BBkqAPoF~4A7zP7=>TFyO)$DHvDSz(97+#8kPMAg z+F{Dcwpg8qy=)C11crT}bGs|hQLcQekX4XJ&hQp#c zy9|L!ViK6iiy%l&rpssHH&)4A> zTRSbcc6!2M90Ggc>$B+Q=GFr^6E9@{`u`e$GHCmbVqe?xO0^7#x~m)9u3U zFZ(txYJw%haMPwuXZ317X2Nh&I@%pTUr$1aDgib!IeR&u;TtMhv1iz{cf%U*(muIL*b69OCq3(uVwo&$?})OJt7MwR&CrNs4*(%?J~t(w#n z0GE>#Vzg6{?_25GEcT;cH+nOR&B0g7un&5mkJR0H(a+fh!a?^+A<$p$m9w{(mvVrJ z$`Kk=&Js3N@E>?K_m_JhXYC2;snVNrB74w*914vCpaz7O2Eyba&Q9aKT#|V2izd{I zOsfR@wH?NQ(raPNx&ZZtep|GB4c%{@%N_HGeZUmp-crEKL#H%9%@}BsH`@qg*Rr|b zSwRr}1gOtc8ykW7!Wtb#@B+e35p+I)z(gT+N_yiOc(fjH;!A2rPfEk-c<}Z9Vn%Mi zfAlr!(}OK*$-Yb3dVvrqWU7IK!RQw~KE4DX6~jE^K2>OYKqnn&4YQaQ?K%sZ5KS$F zEGLJZO(05fhpgurFpsS02#At?x#bSff4U{EdpO{vkodAY4-SDXKzag^=BvOl4hP^SzbU_UEj(F8VM$_Ka-UvPTXswoolDjVHZ&Tkx%%{M~@Rhnk+uV3*3cNz9| zsVHhS;c{B|!pe4Cz7M%{U>XXV&U&-UdAho~N(>?AXMMqI{RMKHArK3AmFS$lp%D2< z;Af6le!K6d%BBJ*@`!hn+?Gm3a9egjB38nWUw2>j1 z=m9TZ3LBLPUI$$D+X+=~o6i7A%mPgN&4i@pEtr%;qlXPtEoNB)BuU~FRe;=Gn7v_M zD>#uwDV}W_`O)(o_9n;|3en0iYW1C*-Av1{8@&&d4@;o^M-y5B!Ty=RQ30b)m8}r} zqg8SkzT4>v&@{HjI8Jc1p&=7518`spCsGp&qbAObP)Rqe7e+H?5TC`iG&AV^^eQ+0 z*b3C(2lk~02szx~tfc%J=l)V=YZZ59AwF~@grlg#FLa_0*sgKQZ}*-vH%6XcC_pwE zojn9y>86l=EOK6La>o0*2KmU*1LhMJl9#X9=M2PBtecrF zt|LJK25ANeMclvx6GqV;B(h-|-VP^o#|t{FEv&3AmO8JLLL=;5AU6_&5;Q#!KDt11 zy9Bhw>sOXgH>B4MvQ$7D4jr}tQBGA^uC|(aX8dr)nzy}myQLyHs7@h0WAJ{l)`nHj z(EGE1Q+ZyD-lRGCSh&nPIw1oX!%84eIV>Cu8VIkI8{v=&TwZxhd*}KhI0|s^9FRal zr0)~AAPIa6yZ7xwAx!s+Bc3n9JkOs*p|!whY8^U-#n4Q3@9w=6a`Nv0qkgqcxNh*~D1EU2jNTxtR)t~J!^x3}63~F~AfSG1N=klPVSCW7# z(k@8x)~(%0W&+`4qO$;91_Mr=ta740PSA1f4rI7t%Lq*ZRio2nf0&o3>(tcLaV{<| zC?lY?gI3Oypwm!Bs|GeDIw+zWq`?#30!pvqfeusUHDJR7^Y_llnP8MQ9H}gJMv4k`_CNgaG0(<@8tzz z4VWWe4LEfPn>awF0sn^`oJIBoQm-hbT?Fr9)s>c@Mv)dO$NGR-Os4 zxE|=VZ6AIMGhPbyruL6QCktRU(IH5Ao~VTwB?&&b){X*30R}LmjRp(tO?T#a9qiJi#)W3W64)Y=TyOe;B*Y&go#P84Q2^iU^+AJK#gfPWC3s8 zo&zYi5HMNY=%0jsjyu4aiVVf)=vrNfBJh#}nTa5+4oEej6?}9Xoc%)e-u`SfSmLMb z8Dh{$aGH&A^vnUh>VIj0|8O@1v0iY@O+-~sLqo&lbjZ5!XV=<6IM=MzV8I$3uzw2R z>%ZP?FC^Ut!+4~D%EATqHRw_ZZ+fC4g0Dt~Y9kMVX50RqmhEgRDk@A6q`E-P<*16% zc`zi0(1}Ws(a|kElTctnFNRFipNdG$IDZ1l=ii^oD(Gs>te!A|dQCSt6*7^bzXC04 zub6(`w6ESaH#GDxggx;aIj;J_GUioHm`D_X!**(AD_GvDLDKO~a69poWKiQkaib1E zX3K;gq!u&5X`qijsRZOb?qGOIAOkaRlMBiKqT{vT5w_^a92N6QUQ3ovz*@DL zRh$MX*bZDE=0UrEJu)U?0U#am0?HX`3rNOqegD^;dp3(L{M7~lrad$AeIdE-1}PoE z57A~}Fb!a8dSI%4^h`pcpa@`XJ&9koOJ^px*#KZMG&MD~D!vRFb6ruX6*1%ZAem_T z_Y6Vg&p*Pw!nn({-Li>y875N#@+9c!I7^m<*jRT)!UCo9=))zyDx2;P`v{^Q( z;zi=)vww+%9uz)2kq?I=j}h~cE9^nL(Re{xH=dM!4z(*GHAr2Euplc6h|WvM%Z)#& zgiI9dHc8ctYe40-hGi1^R|*ryTw%Q90Zl)pgS`Qc4@ z{vN7D1!GV8YXTpt#xnW?&96a;kKN*4eI>>6?%{2?>vew0 zEqx;*I{GAX77{EC;~-zhnJ`1P;9m9C=b4r-4+g>FtqCX|eQYwLZC1|mh z>=Q&r6n2&?gfi~m(79?aH~wq5?DWhy@LJkz))xE2pz3fS5+#cd3T`Nb|08}rUWMcN zP61e_rXQi^je*h~Wmv#y>n5IqYjE1Te^IK4g=9!hpaZ!cR}aJfRsmOgQf_@l4p@Zy zPu)U$_2ssI4WbuL&WoMC18y#I1RxQK&VGVpM?wH!<&3N$N)<}NpC9?)=S@lt&WAFJ zM<;?&enh=PhSA?CKDYup3_Xzi!R_Alzkm5X9sl2(jT2>-RM__$$YLWOCBZQdpb&t; zd-vG&_oy*A)($)lNlVMwru+^F@F0D4ar?;)2lZ^B0FsskC)6oF0(B+0jzS5Q-6oR(Ue+`ugYXG}2i z1rPMF*(2DsfqFIQEHEX#?+;`CN0w=^D~X-38~^WLc#J?*wDhd@1ADt*Bn?hwCq{#N z0?gdpP&`>nOPC*O;DBO-?_<}?kHsK@2UisS6_J)eq6YpId*C_3j~)H&L@iGDfB*75 zb#|~$*K0mx9&Wd}0eiW15e@ubpMQHO=uek-QEt}%{mcJmgDf!rlMV7*{BNgF&c**` z5Z(s-w8-?h3``b535(_mq~LQQqi)S>^wVv?4wtS<+0pfSws64^O68z>o+?)g$F z#9&bsU0~>SH~8+WPXy-zr$YbRIm9tFE2MD*tFFk0RXI+1SjwxW2z}W@7^~hva)c;& zW3D42$-vqutg2mJmA<0Ur1BxkQ9$U(K*;UmfA`GIF>Q4UTCWPJ;J)=I{_ii@$iBtP zBk&62O^ZTSjoOiP_&*<%rI;EizVRPf>ivquJBp_qr5Hi-{nGf=^UkGJt3s^!uU=*+ z8>zBam3z(;qaby5%5Pap%{m3C%bzCxTjeWqIP$A7w;`nH?r{1@6O)hyVNP&5Q3sng z;qMPW#HEwJ8Yx82%^|MN!=@|})q_s6%N{rSN*Y357Zfp-ZP zHf!LodEoo672Iu|mwHa?XXhWpfj@|+czLQEeXG)o33+}sf}04^^4^y0*W)(kuJ%v4 zZ?>`?Y4fSU$3hs+0^BD2b09p~n49-OxW{~m^q$@nqtlSG?E8|qToyjX9)9$a=F|7Ytq(KfDq248Ifp{imaiR5lsJfd1bj zrrU}Q6Q^G`m~#4csUK&p+FQ6v74S!X9=_EyK)Nc3;;Q%2e>3Cm?)xQG@Z~(8O^|;( zae4mz3@g4fn98k}tWOtd3-TiDtiLo8HfyaEdGFJG|BgMp7qfEwflpJHrB%a!K2Aed z_REICxVyble>rJwC?swk@tYKz=g$WZHg`2{T72c_*VMK1;jA$;Q7)q>6v)O~{HfFr zKkH`9?M~IdgWVxX{u1R}dkn%s=<;tn6Yn}i8<2Kd_%+HQcVQ1>B(1QHIAVf}$C6S! zqy3+4GI!e|x&z}M*&Cut8m%|QXq6Q1-ff-OUbrrXslb!A7dF5R3fHy9J07#eR0#bo z*6z5J_wAby^*;}9|FyC4VTHt|ZO@)2He1qWXUA|v6{((mx>LfBcEIf;zYRT8vcNU9pO_bu)NUJRC?QaarIYL1a)DhU5oWf#(4(9!f4d%krjgIVyiu0 z@#eLYB9ODHG5lqSjp-A0oIJ&}Ies6W?G{nboa zjbW?G*kZZ!7L0$`g|?8Hc;T5L@>0Lwk)P#c{$bIjq>i@Gg{mu_MgxDd{S>SDeY2Ng z&}km$u5a2B5tD|pT4 ztrfAZ+NZo~#M*`){Ko_x8?dmSWEHcuZ(I8kVb-a2IHvUW`dpE~()&GPOG*mR?fswg zdTe2}Kvn%X%>AU|z7Q5Js0Xk+`J#~t5e56qP;EZTZqnFne4kqJqoG}x&z$OHT8~8u zM(!l4%!a|eEd=|%UzDu;jt`7UWfVK)+?kkr|E~O!b8s8h)Et0!T_nXef3&xySlL=m*x@!)rsgC~ z*C`lT`+q+0Bm?HOTFsPSY7j+R7&~kF&kh$N|>2jkI9O3_nQc+ zg&oebZ!+in)ESmf2iR0K-LKxYy~8`hVQ6llJ)zB8m|#r){jCT8;(SMZNw6kKma!#h|XzVshHcPKFW9mrXFI788e`@dLAVS^Wf)@sq;ZJ$g-D z_-9H!v3t{1PcKa4Z&cVtp=kb!qUzGo>hu~7oOyIxp5yw4wz0XX9fYa6NPx)V zzqIMJMeT+{?>}h^IU@W`hunhwvTMCk>8%M@KBL%YTdo>m!IvLko-Y;(3xrOD2Y7sZ z7m-HRI~1zoFIaYZxaF>0T<0I!I{XR@@q8C`N{{n!C|O=4Dd*7`yS5FJl2{q0-|ms1 zW+pkM@>}&WQ3(8TL9DIJ+OWUN=Vp@TxwuW4$B3eGgu?V~Q688npjy!Lusc0CJ8Ikl zwFCGRPEbxxIc?!4*bI{T*d3CJW%$3J<7~(t6H%E?-|9kKPKvFt!7fkj)X`^#ZakPS zyz6f@NV%zS3Z6KlS2SHZ-G(v0MVj)hFB`3U9RGo-$QfbRItlB%pTf5}uJJ(xETTU3 zL(gZL_;=9Aq}V;U(UiDf?+(K%AAx-sL#%{IQh21lELv9sdiup2q^H^>G~LF%Du!IB zG)NlTjC`+y&o>9R?I~E=yv}bYIF)vZ0heOe5=&CsA{0hAvT3-uI3(|g6_n7yWMTiU(5V~ZES0s!xaB5|!LM|U)PbglAfpW8-Uz-&EDm+{#A2K-At zyGRxcy135NnC~l7<)`Ki8!yvh1|;2lgt+eT4Hv6#Y39{@Lum_97Zv(~s~Pm9oRn2b zZ%MHr2WzSp6~>x-cHBKsNAJ-#U71aKLu-mRe9-T(M$;v|-XO*?(*a96>Pfna_g`13 zJ7`^9B4+^^vMguN~;QPB2VgUS1$ zdl!yDL?vAPv=+5>K`8V;&m*QP#XCRpVe9|MG4JjVT=^%mq4u8~xAGzMdO^lN=QrYK ziw4vY&e3Y{lV1r`g`ejUV}Zi&qnEc~1zolkSMA4jK!l_y#eA+D>JUu)0Ax*U!rukM z_Geo~Fs8&^tNr#(TcKqcRPhn9(chMvw^u|7(=e z)4X*RW%#69kEDU(3#}Wy)JW8wIC;=jh345koIZs@)!u?)~FvfmRecdF+3S3JNsf_ zcXrb^ZE#fV>@cvjCAV&FAk-@*FFAtObzPNpZQ{8W;0oN-goYx+XmSbR4p!JTVl3q_ z5MLtp)Y*+AjVd!Z|7Juh$LK0SU95q+(2$2VN-vK1OwAgDh#)KFTtMx!j9ehj9`(%A z%|l7HqIr7OaynPHVf>7?3^-!kr||~VX=3D7&dh^4y1F5=(>f^!5S*-DzgJ{{xX6*O zORc3Gmdnk&8e;v8eXSB=U*+G;X+2Fjf-WV|*(kYUS^oCafi!8ZJRXENp)w%|4|Yai z$H?*dt*>^d2_ASJ8+dZmNlC=9Ae|)fCqUv?o&c`kaK~)C^=Z3N1e2}c%rPuvBt#t8 zw#F|xUum&|?nvrT1&;CHN+#OEf<@gSO5=Y_U@(TssKD8{p^%|2KGPxo=!89~L*4Ira-pYnGWpfh|#wOrT3jD^XM`NFS>Myac%>4>x+HIbTAZZzJxZ3PW-*2=+JYf zb6p<9SA7=NULj_`XyE0>%k_iHQ^@eXjE={Y@6uThyESlrisFX(OB>s_CUqveyyn}0 z|I$}BY@0X&(oQCMIU3d&h%KjxG44}&_!-AfxB%N9Y{f64Vc+7md+R{GrPVD@6{ohZVj~t%6tFYp@*6J~=d8nF;;IroD?}`|P_tLUYp#b6GZ{>kG>Z zW6z9^8EwK}{s!gWsz{&0gii=blmX(FHCP6Xg}PXyG6JJ^@UoZzRI%=fg(k zv>TN*vAdbO)Q~_H<%aLqzWuZP2!`I%6fLt|+(KTyQ+2q_t*wL__$^oLOd;J20HaDx zRvS%D+ZiDwEA$iW_$|Rh57_xJ{-u;MwUw_?Qbi%^Ghc1W4{<*ox9q=oSNaEGYLC0& z?*pi95$K6Z8c2(Y&pwIZ$G>;?b>_GtY@%o<11`j>c6#2eAbVkEAt6C9{<|Zx&{v3? z_&#i@JDQ@)&DA9U=E)pL17I$%(`b{E(eGVwODdts%__l{hg+}+x#)2UZqAdhA8%<7 zYq%mKLQv?AKD72!7)?Ja!o$&0HZ=xHzQxeXJQ>;K*I|88#eOsmp(bWm9RbQzFi;Jr zUF<>dj?T^yedzFRVsRcT*ouAao~FV5HDOC#cyJ+?N@HjGXd81>XH>z@53D7X{9?5s zPwANQL-zt3N3Xx?x;U>BEhha`tP?x)ho}iA*&4j&%!K;{9)!l9S-)OO1IjJ<&P+?f z`cgtEKrDE=JfiObv@!`gtv=*AXS8|%3&OV1)hM=gRl*(iZw%qbwmqt5#J<++OMRrl z<-{!lU^AX;`J=$s7x5^>cDSx6B%#idC*XS!`UlzF5t3#9?@Jx`l2Mocd=0`A!Kj|EY7>B z6%0kkbOX+YaYCUX1@M3fvb?k=imc+|;-c_D%zKCvBm}E| z*x9I?p*32mt&pdiP+8RfIjAZ>V-sPUtwvDo*N_Q9;2$9&_%duY0l*n^|F$sE2GdoG zncWq`-4*lc-n#53_hZKO23HbHtm__Et#$tZ9T7ZIqy!s z!y-nqN|EUt`4-k=2yv#}c-%C=>?l8GO$<8TUxi;vz6o_qdJ=qsj)`adMFwiq{$%Z? z%9uXl$rbPT@w-U$4=j+k)=J+p+p&eL%zV%1FyKf`kN{_ZMh~&^l;)j1Q10YJ;UQHeI`SZnqa^@>EBCbHRNjpAca?apQ z;*~6hSvXb)JO%WLe1nAidN68Ss0m4cj#V~x_8$6>1qr?JGypyH=Q;tLY;1P53fgr9 z`rc|?Z6(w|u!9ZpPpv*IKGtE=>b02l?BW@Q5shBUkPE=y7_+@KK1hvy0)V$Y+WORv z)duB)>WGO^wZAqFaGsj%S*Nj^;U?Gnj!TxIde!^;eKFB*YGB;Kv)e zg(z6?U%s)wXu1q}JX^JAQ)#;XI9-Up;`*_$Nr~SpaJ6xGR`Z?;b)ma^6a)$LH#2$k z@Oh}fTX~e>hbr!@{Y4GK)mT82jcETY5D9J5AsS1Zgxpx5SCjg($B#@$QCq8Xj2_s- zlvfll46XuBr3#J`$a_Y}pJP~bI3ziom%N3{o`ToQmLgfsI4czv%yP^4xAuZ};J89s z;rAP@#j-_=RSN{?S0W)FB*=ghTi_Rav1k>sqm?k3QU7}9E{<8B(rDIrQs1WKOO5+szAw$MwCv#XNhQ{ErT9h&4m-Tw`w*Rd=O=yT+F3Hz zC!#LQ+t!s=bLoYxRSYdMLjJT-H1k+?yITF$4r29AmnZ-A?~J#Z-MEMKzU}MzD_wTE zPL)588Pz*)j(>ZKr$8&8*?jcc719KfmDT>c2COY~&SuMBo{pIg4H*a8w@K9Nht)l^ zFN=;6u(_YKb7JHXQ3-7WADOTM7^XGs%W8O%XWf6FRkxqlSV?lXtEICsTPv&6 za*i1h_Si>qy;Z}oeXX$X!gNIJm``eXS6+VumkYJ8+^^se1Cp+|N1-bWMUu2c=M5Ex zi)B)Z?$eAE?(v??>5p}R%xBZee-Fu^bqq36S_-qFY8tP z`8&sVaoA0|J}x-|b-1%WVN^EppNQN385uNyOG@R{T^^_M&a)X#3MwlZ(5}42y}FOP zX)iJLcCVbGmNN4ty?v0X>#=V`cRPEk*5SM}8MWc&JXkd+QPC78y4TFVA!)C|^$bg^ zL$-aDTza0WfTq_xDTUd@w~u~d!!J@{K85(6G76D3!PGipXYYCctf0q&P5x`nPZ_lb zv0!SABVP{hIny8`#>SIFvXlRswHDt9Dgnl7nl2Yf5q+0})U5RXk`O%uPi!KS4{Op- zduz=1T1RIe_#1>>@`I76{a~aeH}t6|zTMh8Tkqet>zvPitdY1rU%XKWMEo4DyO6`U zK0Q7LohXeLub3};7_5$qz5805y`fJTtQq>8IYs;hes}j+<{x$6Dwe|MlxQk7H4;6j zBk?hf#_M&I3)%hH@1L45OR`}&SAPS`?osDAT+mW(f!R37-jAZ{G7jM*jA4$PYsMu# zY(G8Rv+UKs6+r1D{37z*d=1=jq@3|Hie2*4WXvh|`^r~S6U;cAd5`}d;<|sJkn~?h z?RnQDS78AQ?rX7NRW}%MIV8u7a-t+Vv|9VNboStS>5m!SP`ybXMNU6czIkpCDnHpY z?^^atykhx@AKOZ-J|&Xv)tM<*8l2*_`=;GLW3IM@`-l7MNj)WM1q~Yt^c%=orr;P&9mORtR4N=BVJ^V;Kx?2xh`{b>@)5K=*=P~1(vNv6*y0R4b zA-NxtPME}CX-ZWWsS0@UO3BmlqW!wv`{aZnX{*ed9_>5mf+|-<4mkl#OaysxB^L`c zevQ7B-hnxfe^o5jPPh0c&Ra>uRwurJ6tW$-dJ> z+XHecgctw>XUggr4NjLWMbzkqY8?y;Qn#%CvF@+tS4*wI`zWrj-HP=aV83_q9Xq*m zq-XADoF2WlvUYmDG-!v3tp8onq#4gj8Q!{_4W#)M@a^#4M!LM@0we=E7rL!`+zeQ+ z1gpYX!F6EsbV-@Z{oAy=vj%WSoW4P)&M?Z+1P+?3|Rgkis*577!q9UH7eT5^Kl5c-;Ty4>@km>&et0oo6KTs&7qZZkDnLinK z6jeJ9_-6Kehl(KGxL!=nE2uW6FZ0jeBfPeT357WRspzygmN`{1tT}%nNufoN z#Zg??d42G8Is>z}(vtj#gxJ>o1a z6A#I{TPd#$#`xDqa+2&ns7~?WSE`WMosItEx}JI5H7MU0e6W|{XPoRealX&w{39Ah zEL$f?T_`uI{33_Xki(V{|4j`!it(n}L-tJ}LUDj)-}*miU-2^eywmSn7lGN*JY-0? zywf(Cq$0&XjRqRP0NoT5j^FdHvF>s$Z%bj!sP@SuxEcSNiq!V4LC6CVQL~+)I%dS( zqGnaJmZjU;ZtOw~psFdX*wxndlY6nXV)`8(_vw|cw7RF)c_{_igSGnan>RnT8f)Ii zoGBdd&^`%fwZ&=dEp?Bj!S)K?R-!|I`ok7NQN0TSa9dt{M0Kq zHzHN7&XCQ*trkNtN{nhtE0GQQjz4sSwLR=|f4zM7@!eBW%(s6xO8uGy_ll}m>39pF+ra{6fd*xVA)yPJ@qc)GF~^#mlq^B*+U zd2UZ5p#loYn&`S-P9Fq-75+--R^=46(Bl-hX)%lmnz5rTTxK&k3g`los<=)mJ5uT2 z*z%m-VH2WyjW;PQicL5r_(c<(Nr%3>J4$x&k6-hr$2$0xj`02tU}z|1z^8mZ;xt{=P^1DD!IoWTT71-xT21}Xt$LO+2x9K?ChtXM) zl7QPFMNOI*pJe+(>X=Qz{mO+dM(6BbMkR{)hYvz_o_+(~*x~*ntI78_rg*Rdo7t&_ z#~HzN&tv_EzDV{&z54+^XU*@~Jct4|(#NUI5MrQ$+=ZF9C=7(5c+8C96e1Yu-&GMb z#Q?uE;|}8G;-4TX3+1X4D*+d|rLatr4?{!Y@m_6izq%FU3MgAjEw?e?(=X?aGtSsS z(h`&_^bN2$a=dBleXkmbSRwJ-lyja#PhD8S2FH_?!CU>t#2lm$h7&1qsn`UB>ni?W zg~=7ujTBq*K3@`*4WPL=l|)ttu9JWb+n!KNawwI}8F&PFv364I4EN@z*Mw*4$3DKh z&ww*8Zy=+59+RA1h}Ms-%+9m8)vYf#z3va^!TMkK>i;(Pf0a=Y7PoKGW1iye?dSs=rtulUb4zPJ@VZTmRIQ%VU zIb8L$YSZNnR2MGnKC|&i*}=>Ex2f%HDlEIS>$z#)dz(N(f$qt&hSjIu0ymr`s2}K(VgSo9BG}_ zVuPHqX~~_=t6G(PYvFTmYj4Wv`H$WB%5P=yVD#q2$@GL+S6QLwH^CaBkBvY1^^8*b zCf6bx0$R1qypEjlc<>PrCe%lKGFR@#gsGWK`4OU9VRktJWEQ^tAmDG2-tc*W68l5ECi-h>Zw7CTH!Js)dN2E6i-g;@TEy{QxPCF8l9A1k=*cc{7&}4{Q0p@rr+8I56IN3a@tqEs=4`Kfz3k{b$( z*%%CL(=)hKcdD$F_J%n4XE`#p-ujDfzwP7F5JDfd}(8Tj-7ei>JQHsFF@E{Tr!U+Hho_CA|p_M zi_K??k~=}pRR1EUy3$W5zUIaJ=xAB97_1>o(dutaL;~n*nb7qgl18Vd7$z}XF#WN_}7$eD; zat55et7ndO)LXgn{v7*MhVkW+p-8rEwuJX1Z`V}$WA`wDO5Dk6g{x5@`~`M~QY&NS zf8Qb?QEge^vUV^OwC8eIZSy&DSo7h>*AH0X z=*5$Lb?b`?`sEio@ZZIe_v`_C?Fx+&(q{58KMr{%F*a}|f*e^pcB!4yfBK{NOT{yXsFRGBx3Gl2Ujyo)3{2kCbRi|)*kiisLi zI(dHV^(Rdl+6o`#)3YM@E8f@HlGm8cslf8gtVqg($omNw&}GrYqRi#1WHFK%IT6vi z#<)xVqyXIQ1{-Z5aV1~AVLwcI4Q)*uo>lDO*~jn(dr}_!HW!p{Q1md%cPUte0mtog zh58}y>O5h{7U$(8NVh2~dZcewqntDgi^dp#|& zk$3}~%r>trm>kciZ49^=Vw(8i*?-+1#y`0ER&&hD&(#?!q?Cj)k4+Q_3-FP0()Utz zh0=7%_)HD1JCIh-jAHd%Udb@vm_h2!y3us~KTLA+1B|n`ZbxLY;$GSc(x3#XG)OOf z?yRu?Us&cqrnIl?fsL^ow~2qc{FR=Ve8#YIXH|ehPj@fX?YXZ(rMeDygHrhj%$>^xRGGhLf#S_CtLCYB zu`kVk%pZUKMdxEayZxT&!OgheQ?Q|sH2RPF((A!C6@KF~j-5)5d1u#gC!)qH)QTOJ zN?pD-DF5E99O?F?uVCj(AIr^@4vWoC%gn7UsI$;#sVvc^jody(68uSVviyY$=Nkx! zTGl-_Ep0JMy03B6+kR#C%Jb6UeXN1y9V0%Ms2_e(@UqL}B%-PQq)@eqtZnl)4qakn zZhybJ%C^j!sV=utr_Slg&jf6dTVP8{typh;s9=xRP~uRHA*5U&6@AFd@W6|Cr=E`e zarHNv;o!ohZdrDwy}NdCv-xRG9;(y&85<>k>SO2C3UiM8yKCd>hvZLbClkdolORP(gC9&XdVFMZcvk3U z`}DERa?+M!uQ`5k>tpfZ`*!191Dr91ucjHpAI`WIB=~9fR^UjrlzSb(ZFGZenUr?W zCJXar!|5uKs4?rw6I&1aRfIeG?lV?UH(@%bWj3^|5KUarmlUp~OT*CMrt@+F4mvBV z$@@N~vsNlu&BWHv$JXmdjT7SPATq8RS5&KSkvCEFrJKWfSy#TyV4az(!?~o!bYkX8 z)L0ZTLHL?%G7cu`$7PB4H%s@GxE46ycbIDPE14<(^d|f;Z5_K`_tt$Z`%;$dZnmb> z{#qu?O}1=OJHeKKB%PV$VHh~oXKp&H&djRIWPbfC{i|^LzH!#|*^atyZ+?-TV#?Fn zhO7)m`UO|xd~3Dw()XR2VnSkD#NSWv**fR7Bhc1@iQhzrhW=Ih;LWR(QPXM+A;K9f zUgItFUgHd4a#`bS&&4k`kJFFdjv~$N(SP6S!?1^6;O<2S&eeNmw>bUWvbfnw+YWex zd1-nmXp3cjE_r|-!hpge*&-Ddd8bkd_-*~!xn2GnyO>%1Wi1~3RTkW28KRSJ8BpH6 zHoD(qg|p%|F|z;HO5LWX!EN18$Q*VDyvaMnz4Myv5*|$YMO)|@W#KCMPus;KKHCVM z9j>akoB(iyN4n@?V``r+Om+4Ot*?&VnH`wh7LHfYxGIV`M{`4AdrVDd?8OUhG{Bh6;sqrg+7SN|(L{$}F+{}uq>fu&IFVd(?5Z+UZ3 z9~K(2nNM6JEO8K-pa)k3Ayb0Rmo|+9KKGX3FP*2r|GV4rm9mO)lD#-1{s`@wLgxY@vUvTJ?mF|9KoqKpvnYisKQ))+jGpPi)u(s1`i=os# zGhw>y%3(x3`|lw(Xj64v=s4?RTzm8K+%hS1uREnpvN^aSI(}>)>@x3Q&3`c9=pn$C z*X~d%+^eR@J$c%L*zia8XHcy*N*Y0e(E z3{ko;SsEU<4TY+gh@J@#x!D4z8wI}k+_3YW46$ThpVcV{e2i-Y&S1i!q<1>hT#!oA z|KIoITMQqGg3<@Sx;F{m#Mw%nROwRRA<2jwqFg%M`=i7j`2u~Xer;i|pr6gd% zLlh|6;M5~HqecsOhviT0)vEn?1*ntV1qR+f?nX5Ez~xj7tY&y}NjPmLrQMmC@Z5v< zg{;7T=3EF~GA7k~D?#lJYyi-U8zOK+I6Op0j+oKT3J5GbYV?F-uHhWInfdurGz!3x zI@_FvFdeZ;nK(@c^cb1g-yH$MeWlesgs0&4wj|{QE(I6oZh>`b74NbKydnNiYv8=S zf1C%jyIzbYxo3e?=1uw9tepq|_B`Q#LWsKb1p=Fi0vAguQ2cRc5%UY*8HAplL&3w? z$xoV7oz__=iLt(%^xEwJOlCiv7+|3Dvr~*$SeOY;<+jWnxWt7hDZ`Hun;5X<$?x>k zQR7imnK?7Nx41O9Zy^={Sz)DLM#ITDHcdGld-{W{)wb=}kzvn7oU^|n!?I8y=5UZk z@?_L_9RBOxtkMi|L;)$RgT*T=$|zVJwV91kXMX(n@hA&%``A#;y@@fcv9vDsGg)?I zTi%LU?<1=12iMRJ`mVO50Rk3Cq%NW30D-X16fj>U zKmi!4mQe6MZye?e&)A6YgAN_m*9fC6w3&M~-o_fkKlasd9qgy#i9N5^^GT_20LkMx z%_lx@E`{?6dVv1h12K{V6=i5f#{8y)P9R5wehu2mh6E>GSlUkE@mavudi8t-?sA~% z;^!t5al;=mED%;DFz^LoTZJ9aY917cX>Q@ZqmV=;?N2T|4phhC1Jx{x&s;f1cp zh<^z9=<|1tJI&|x!04rSuK|Kc#NJB9s`);i$8pN9fC=!V>(lXBQ(rj{H6-mC!3txz z*wupNkQd4#t@aOK3;rLrz5|}>{r~@in{GoYN>Wscl$n{VTS9gyB_RqKos2m4X=k?y z840D3?5(V1%gEj%``G*ZU!QY6C%*s3&*O2s-Rtvtf8Oi0U$5s&`r+wrQC-(1aUl_{ zQX`6V3BgPji%ID z%wd{+?fLkIZnnJE?HqcV^}5xY7@_k+G<&umHtdu~o^%mK#2Ix1r61UZ;vWK2 zuq(Gj!S{A!A{QA^0kdw-!}89^UjDR^(15(v!PjjtQVrA~#5wCw2$(R2mI)kFj?&8R zV!-X03IY(~FK2&ICWI_~y|#3FdATc&FRSCq>c|)T=)04ASsXoQa1qsYi%Vi-s+c4V z41|+XssQX$ss3RAsk>Ek7+X{B@=#)f$S3ttp2AlHynY&?E>9tryN=j=UtZA;d8D33stZjY!>Kb@D?Jt>JR30MJ-mf-WL;?DxW%204rX^~8B_$2uva87f5wFV-c3ly zVyjc`FvIz)6Y%L zH6yK8Y_lKq&oIBp@&8%xtU$R|`GuNRa|og;)n|JWg`_UtrK`UK05w^snuRMRH~~+r z{aq<`G6OFpkPyN2O;u4kO0zPt4MXSS>LZ_OH0-1Jr{6*xiQpD{@e^=}?JFxQXycT0 zKxpoPd~H7z<316(vkY7%Wj5yUuTII5gn{6;L}Mbw;0dTrH8VLyrxjjQtAXVL2pIKx z%#-aNE zr3C6smb0S2A&h}ZCud=sp^ql0qpXM5VD@W3ic1K~2xRK}3Ap`HdDCGAg=$p`182^h zAp@*VEeXp&BgWCGsvH4C$r}nA^w3QDxXvm11N-T+9y49dyHmz=b%vBAgZr9z%k2m; zC~SE;HL&4DnbBUt?35Fo+;J$x2>d-eL+U~78R4LU9O}+17M&ajVPd&ze}11`xzH#( zcOsx=AA>yfU#UxwJ+)`g9`lwJ*05{=#C!v!@F$}c73hcMPV`wEJhbz{u}^*QOsQ3< z=l20MyJL|VPm~(^vp#tU+U7Ks(+L_ZWYdK2a&1Rcx2EXDwQ(ZVrl|RyUw9EzDrmN3 zGZ^u>7*LX1q_Jw7u%K>h{6^E>BWBuML{PWNNk{Bj>T1>*vbf{W|hK{Mp=jOq(X~_wQgpK7OpXKta+a z0P3_S4(DbG1vimxoY=kec>heHUdv$fi+<5MB;-pRMdnGKBP$Uy(51)^N`@T55}+qD z+NjC|z`D^+Lnth*)a-8)0rPQG<08XQL#Go~G__oh6H}Shj*4&pz$>=B^?_{tkEIXK z0Hg!`v4abohbY}LS2O=Dxg0vs2}v3D0;X3qtKf&e|2tPA83`$PY8d{Y*j zGf#fMFjwn%c@Ex^R#bIuzaEKuzjsHZXT!95&`vkEhgS5o=EB%p1W&%Osx+5>kY--p zghn@AE`%Wiy6*Hq7aLEg`SEjV1ME~56tP?7bZSqNP{}?fpj)SgFaf>fqhp}Cim4Xj zC(yPZ^z`(hGXrjJZZ^<&D(%`KMDp4C%N*{+mOAdIOw_IIV4k!-Rkl>Bkepehmd!2En!lv_rSof&M1Nbd}~&hUB14qy}XzpAaBHf$HLTznnFt#6~BP$Y^^hY z4Jvy94Rb{4tW21{fNR&5^Lu)(1Vb-}y(FlrYxqu`4b<5Lv`-BGmXxTiUTlBYb3`OT zM`=|C^QVRfqwBHQEnu(@EjA2nbe+rUu*OUjR-a)^xlQqWAcMCo#pc9Q+_fM^U2$Br8d;9mmFJtq(GvO%vkX_k z-g_FGo12Svc__&?g#+aa!j#C&7M$3aSMa#UyDnhSuH`Kr%3e%0amo+%&kR?R8c%iq z9ep1Sn7Hrn<$%aAH(f1>ZyX8zY{W3)DqlmRvIDvE@lwF zslsyFO(#K7e`!jwXE?9*>ED6SjU1wADg^}vf2Dk8ReW1tdS{tq;oP`O_MaSn$%P4K zu6s|kax+YnIY_HP_^%!s$`lnYe;$?dLqMU$u5LqhYpOzK72NqD2=I+X&z*EBZIyt3 z&_P^fSc+WZyJjG!MD$L%q8&nUHWiBl2iHmi_9J8%2H3XVSh$!l_SL3jY@Qgz9o#-J zs=`tjQ+Z14p{G$osIi^mEBBOJiptpioYzHVt^I2h@E3)c&+Z2>dvof&sJ>eJFUfsb zz~3`Z#>suEAU`bdWE8i9|2FaLRnMy~S|OCfC>96N|9(hOcCjWfVQyxo2)Yb4zq?7< z;P9;0yo|g*(gu0+oy=T!&0LzU2?y!PYJH5tj=;x*7JVCvrZ}c%PzYZB0LuzN%FESf z-HAUM<{R4Bf}2eid$slnrf^4jcD_+Jz{_b5D;}$ViMdgU0Br$XT%fMjro}qV*QtWl zETrb|6i(F*&!ig{;kx4*+v=wcVmPEvO*$D4s))5unmsOh&ZS3C3GW&O8kgaqJ6fn$Bc?z9ZtY5Q=r(04cQrR`z!h1|x_K>e4? z3N%>p2IT7^zO>d8{dc0Ycw`o9{7ogdU{^jkOnO>J$6_XW_GqsiaTdPCQ6(iA_0h=6 z?S(S2)Xv{GDWF^}`PO^P?L!y??_PBT+5i;ApI?|7C_$^DFJ;)?s2i@3o+p`rDW2%M zFew275OrKsxvYSI?z)tI`C0BTNrDH$6W2DRTl4eI=6iuGz!w zDcP?mWdvb%hTtmr80?>+RB%D}>Mpb)guMJd=rLh~YDZ{WqVW6Myy&(`9B_7ViM+&H z3^!!!)~)j3F+jVgT}&|84^0i!S`WEGBLlQI%sWk`+0NaR@8jKD9x1RHxDeMa5B9S`FEL+;VH+`l5S&y_8ClC(E!Ol4;5@IXe+G|cFOzJ6{*{NM6zdnOtvZ8 z>{Nd$SF zlxfH*>ZRQ|%1`oNGOmwoVbhb1irG%Gttm5s5Z2EZ|D8C87KkYPObM)g@r^>hf|cm5 zhRkhU1bK6vs3CF)ja!-jsR2--~Sg{BDRPjU3oPVF#z)9*_^` zk1~VLM;uiol1wYS(2g4DbwWE%K&#RcFwOTtdvf!s4s1S|CDLpTh5Pe58tT|Ljx`3? zid1K}zr)u38+=*>eqq3gmw_2%t>fC|-z8n7X)BV5%vC+5)%5lX0Us?xQ z2KG5BdBJGpeWst)q55r$Ij|YiDzpF~A_W%!Or=fX`qom&@?BxWo!*RZLc7r|(VC1@ z8DCh;Npvo#q(;ezYx$x^v`2M^JsU?FulV?fq#Wg!x#7M@_umU=Z{Ph_CFcy?cR0$X za`sU~l#%ONKr9g13snR}((2SaM-1;1eg1%N^3@^j#t{*B>h+}C=X_mE=FE@ud6L&; zw7eGH3q+1>Vj~#dsrxK}U+ndXzS}?ZdarC|@~xJ!`PHEkZK|lGdL_|i9k@w%`(x*& ze|xUr5;Nuo;o#p>Wuk28G`4N9xutaZ89rQh?WdV1pW(W#ok{(x(~rp8O0Zcg3o)Yo zP&ecmFVMe#%QaWSlWz=QN;SqjDO9&RgsCepSk8PnQZBiB z%I~3I;`CvwI0zQJGhm^_)xw3HYB75N9zBAVTMqI_?*3k=rMw3!^FAC_E2a$jPuJQ) zBpQ`|BnDR95ZrV<<{5IEvkTjjf7iC8I76B4V2Lr^HD&V{1-(yYyQuyVuC-$*&ZwcM z&6nQ5kgv+?n{CFnfTPTWix#5__Sf zI4)!86^!3&c`JtPRn9h`6J%2RSPfODlMYtohXU6x|CwQ23%hRH)vRWr( zd>`;cyxqHnS`ZSxE+yKB4#E@h%irjTuU`2pNI%rlrZM6Q0xq@-+X=}v{L_4i2~tzm z)a|UHNrTRD85ardohO8k%0~-wz9VR!jZhDlsQVPB_sz+??$De?&9PPk?>GaUm&#}B z8X`t_x$ji8J6gXws8G2_7Xf|ubuc*D%k)_X@@cY zUi0v>TP{Xd`saAJ;`tsl9Z@sCius8%e*V3aask$Rg3FgfqnNE@tJR{IX*!j$-Wr4q z>b-!hnzH5{#&t-!)r)wV^rlA?8Vz3x`O9wXFJ~~&bQ*uNJXj7%tCI~w%5m-g=VMR< z>`hl%@UmL%=ILQ9jvDxB?OJ7i)~b?0^nbX(jH6z5cUYa0IYquD)m#4OYZt4QA%aD3 zWEx=Xg-nog`^|`N!=#uiqPdL7kN59hqXqs?bzgBpYE01&ZvABJJtX^7Dt&d#BU8G4 zwf;)W!!4+Npby;?%on0?;ZS6UGrg9W2o&h6LAdLAl{ zym5Bd!tUqE?>Dz&kIJ!J7^2Oe0GZ0d;Z}6srch>!Rt07(3F=BPP}YMWgYRrbAy?<+ z+|P}6jnAF#+w{eDc+cfbJS|LmL1hO0^fCWYXK?jpEKU00E5`m*WA_6W-`Z+s57gb? zS@Fu!*IXpX8iNm$ELlGfi<^)uZ~glp=c?PF{g}o^Z`gy5Mrc|CNQAxM`R)~UPgiD; zv4E#Jp8GghspwC+yZU|dU*M0-qiS>$;fSD{ar(>bQRlB%tTcaQK;&QSnQ-sge?S}h zCGf}#0Jx}RLKi|$Bb)UHu*Z#zj)H9msWOlNC*+|Ce=uXqf2;dSt*p==_ z*6#MUtl4-qo3cggj{_UM4Hm*>w+1}lNDx?VZ#y3+-i*~k+57!EfUT0SEvsv+g0CWA zlKgOtIg)GkD<1!+qm}te$#H88T|2-+N0+fR?QZ)kE(p)r3>5Dt z-o>qo1XY+8Qvi+R%+}OQ```U<`|6UG_}NQuGYwi7MA@Tg(UuJ|`x@IbcnUCjwp*iT z$qyHCg$Wy>;@(cD*8xWAk2^6E7g)AU`_ zxza3KqeI(H7*yWIJ`{2~jRo5-Byc!(M&a|~oH!y2+l8~2E0=~NAbtRh*E_dp^1b!jAFp24vGn*Kh;t8|1lK)`)Qmw$2s+KB} zH*hb)N9=A>+*6JxvTp6)JO_%8Qz^%7?R1;pH(3=6q^c&{`!mfNhM=qQeZAS!teBeN z8@T>qqq2D0kQql(`=nc_%a6&esdqE3y??18B^-fK)a9cKy2j)w!E6NMT*OAbbPX31 z67OW!*1Cl{{+`5-9V|Q1yxBCb=08l8o8E~11>RtdZD6yh?E7?O8;L#J)j)qfHU>Od zW#+53M1pD>y9oG6!&spVJ1wmGTeyZv6m`2CMW81i*Hh@U>xvswS9 zc-WfPnDl`&;vH!zQ43dOrnB)?;~e|$KkQYD5p0C~s?~3A8B59pGI$!KlOq{0`f*vK zpX=r`0wr2iuP5meuj>p8NIiR|HAxQ?1R|lZOvc4zdHUOQm^fN_asA=G{{_8F- zL2=(`D;mJLz)j)x@01j8O{3T^vuhUA56!5D0M6(4`*?wx(XG9#T^~ICQn>$Y27}(*H>Xj+-JY3^xzC!tX^(5=pnq3xJD}CtI)WJ zC0`7>sr!*%gg;Jb#UEkZEkl}+ZuzpQ{HlPIZNeo9Emdg&OgXe#OBR0mOxcUR^S_F` zr#~ha&JY_tZrcwnlv2IyIaQk|sg=N66n=udI6`BjG;&sPY!}N)mr&x-vrM-$8lEUb zHa&_XfBV2G^{0O)@jRYJqT`X8(U{A^uTW-LiGh5TyR+3KJ!W`_K~YJhVv(_w6;1Ros{> ze<+bLKOaX_o%Gr=`(wV{L&VcyNV3h`$pT=a?yV%1;MGo_n&uZ zO(GMI^HRjPj-Spae|wsL{dO@yp+QbAP23*!8gSByb|-6eY-hX`Y+it|NXc~%XW*vd z!DgML6B2xC`Ae*t}{nW~pp5Qd;z`w7>{5?s&`J#l9o(*A{2jg>lbUn>BZXg_FD&V;S zAH0=0(8zj=vR6&Fz5Z^AR!aMmq`X|oVy@Va{i4VjF+DV8AU}1hIE8qvB+gPdSn1Eu zDY4=qL%*odMnKN{ZTHP+sEIG@*#9+bt^asOb1i86KZ<|p@~TT;i5ET5O8My5F6O_t zBI;tZ2j@S8gU4goGo@y%a%y}muKr8W)7rb&JvREH{&j!Y*XtsYYTUifPMpNnWX9v+`Bi}jEEAiAjleWeM-iw?+$APf(_xCJ3 z9)APMLq|Wu?ruw*%)!vyLr!17`XwKK&YB12z(c@weZlvDp0r%_xG2|K@kHytz%q%8 zX7Nf=;ukQxP7cRo{})(<&}1Il{KQmvL0>4$+wraK?d-7!D_;#aKZ!7&RR4!6X7;X~ zK67m<$$hS^%J0lCiMz1Ymy+)_&_WWr)nmgZY{o(2I zs}HtbaDpejd+QIyH}VN&NawTZP%x3#lZPnFAVwCB`HeZ^ask1{-sPu zhPF*JO{UQ5`!&fdNH?P(JmhOSw9o?@S(jM8{chivdO;qyTdq^(tmN7;32RzMtT>XQ zB8gv3W=n6g8A+CmWPOQR_-G*=sYcllDkvIkJ?n?}TM?G2jPyZ9f6r%H2YY-8+_tB^ zeOt8ar|(j7a(+;uq7Wp1tB&O#+PfWYb4fiP`BIoROE-|5DvGtKnR;CyT z=i&9!hYKY;Imy}cG^ao98cYZ>tN8H?&usE*Yjmb6Ocxt)V zS{7y`f8p}~yZ}1Gw|lz6;Vis+`HqBQPA56>lQ*dRH}I~7w9}q1fpZr0)Au5bWr*cE z)Y7xIo|jafYD9mGHeb+^AJ2-Kv8~Kf9*PY_K9=E%LSf(m;_odG z^&N}<$N0+9PHg5vVU`74a$08|0vra$2JP26J)x%yWg99R5=`X;_8dDx;(blk%MQh; zQkNsF`B8jl)yqkP3W9;4j%qt1MHT!kyE1dAPst@XnOmJ$9S<@r3Sww6S!wVD^U0=# z&ct(E8z?+fPzPMh?&empz}V2A{PHz^wX6_XMBGV;9d(FIF!pgE9+}cqvSg;Z(G}U_a2-F9_Kp$Q}hjBGXvX70I?wi zGp2Q&ZPYDkT(x$iT1$V{&iu)f6h>=*Z};1d(Q~~0DUVJk0EY$@yL0GN5776Cc8cu~ zy=KX6-(k2AFasvMaF!vD?Dh*$75DloK>1p z?fMGZCX8~Hzoq{QrSS3kA>a9h=&RuHeEHRy+1$TNYY~~qeC!~f^ycar3G%ojelNJl ze*qulI5=m@$1j(=@XTj!z9qjI%e9NA0$)+Pl+4 zWG}>-VO(bfub?tBhp= z7NqYsNSpP2oeyr5;Ul(Qhkyuq!Ee_X%yf=}2=Fk2GJ-+Mb$dZ#`Acf(qxU_PNC#bB zInSb!RA$PBwrP(#ae=y$7k@c8A-54=HaKUSILXiOb1@^cVrK1oDJi5kPkK^$EDVo8ye?%+V8tVqQrQAC52$`1 zj+3Mv)GxGPNRLuK&oN`;SI@=HfF+*+V!{6B?e73|uTM&W z>nOIM@bM!!WcKHVa)*-mOLeuNVDA8FA4$=9Iuk<_{*svno#1qs8T*&_eJ(z_7OWUN znE!wXwbXIYrSCn;*9C{;TJ7AkyWYou6NmT}BZkqgwFfQx^rUn1X1nA;W?Z`^F_(O% z=jIaMU)x$POTzc>`84FUE)7eJ{*v`lMhno40+}9p0eJE#cQGnm>zCufokmf#I%U_r zR(r=$dS61$NI&YF=x#D@Kh7ek%REU(oE_M=$I$&3(bJ5ZN(@};k=Sk!a;K_)U(cQ! zmOUqJ2o~~5Gyg8*?l)I4>Pz-qw{QA3W%m=^z6LqxUYdaY6P==;0yh=aqn!MB{i7ap z(XYYSDrgm!yrd+R^hqCw0V=LJ5vJdOona|HV*ZC6jQDGn=Kwe<*@P;e2-q&dr7}y^ zxEQI0gT18-s46pO3)l5|jrwtO$3oL*D<8LDj@%Xg1yTyVk@|;=pKKu8u_#E?5=~M{ zG_452Lk)|Gl@)Jsak25z?C7(q0TVo4VmF^2^U_F?23n0|GhL%tVpFo8h5N0&)=TB6 zTO>2e4#^n@JHEb>TaviMS8l`<9?-iHMB2V5A1%HL{EMFoz);S?v;XC> z+V=`gRqfL`dX43EiuASK*6=yV3p#=>N@P zAdOWP7LuX1iC((dkl>`x8b(?kh%`trOFl{2gzGrnjNRj;VvX)3(s+B_+z-ay?iU_- z)vddxSZ~o!d)0iiH*}Z2U|kp`t4hkEa6|WC=moGZ8Stm^!&f@?!XD_7i>%O;a5P~( zbtM~$cVye4a;yZcK7&#Lmlk&{e!(p|`;;R8KJk|Sj?x3$AS zY}hRyT%7ySndKz|yprp94tEL9V_tAthc}k1G@%asj(%d`hq@D#*b>1VtzwCWgUasN zKmKH@@>D|0C(6F$dn^{m<*7<%;ggv^sh>RB&$vst_20p>8~MW;YnSDtLTf0>!gSWO z;pI*FA#m|}AT#j^loavKc6g93W!m5Lfr7cZIvuF?I3jkdb&q&E-eh^iOg5M(Ej#(l zzYuOih|5@pbt_h1=8#ZhUQ9NU48?GQ1=a+E*>bwwC9*5?ch?2CzM`paG25W?0ziHX zcPIZ+_hwR;IH;hY;BYF*rl)v*c|ewf#n9CTEiy@K^q9EM;RD$}lIpT6)4Ufc8W%w) zRb9t;>AL95^4A60{Az*FEL$huVA(xD5ZV$&h8aw$oi=?8}sjR3kKX_P#3XPD)U7jE~10 z=$}C^F28nMH{K_~ZPb#?Nm|-xQ(47VD(l{ug|fn~5pN}A&3Aj7K#!I;tCXApB=F@XOU3*=Uf+G8&$QKU}McU|hT?3~ZiVl>)2pzAZY4AjIo_Ob~B<&3d z#1FukSRZRE+QvdTf_xm50EOQ`Ib(LeXu=y%U{(edYs@7E{~>=We5zIiF?8q`e&7*N z#jp!x047$RqH)a=#ODFo*PHV?5=|5#sWA5pMe-y0k!XbVmxu?gU769rh4H&Qm_2m8 z@a8V$4O+$E=u!chXpMI%G>vp7*8Vd|zoj%-_HM=zHM-kD0u&M;bUVnC6X09YY80 zjM|y=^IZ^&zmH7C=)wFv6o;0u~ zxgUc9M%Z78JQdd|SL6pX=`apaU!=Yz51O+1<;a>RWdeDw&6c4vpUsN$2_+b{y$yiZ z0tF{FmR~&siC-mLvDTCjKEb`Ga5Lex8?bIKv}Z@NrNLrtfWzN?{tP-HvSUZo1H*rB zw_OeH&M`FHf5qWdOERS}YXvP?dJXx?Xm^|FoM@e6MW3J}(l%?#6+-+k#2+Ci(6B%2 z-$JvxFv~#9)>suBYfYy{e5wUPF40s!N83Z8tt3W8&EDR*2xp#th7u7%@=eq(45KIp zTcwOY1dh$bS~Jz-=VaU1!Lx=%U8~Vhm6A1d__7(x7*KanOT6TRb}AaKRv@1nGV!5Q zS(-oH;;O4hTY+ak++%<9zAZFkP07b|CliLT$vq*UU?wJK3}tn6 zj8b3DT#1@$s&W_Ohwd(^q!8e9bB?PEC=Ejmi8X0qI+{o%axdGF_>mu8Q0Mfv6AGBP z@$JYtt9`h_7+gYOw5MrzQz`MSd&0C(72E2k{VhNFDm(^C97}#?ZWo-uhl(Ti_XYqR zU{*e_gl3Qfgx!1F)rEnQnMOm|QBkN40js-!W32o%AGwtEN?N?7Y+jA|h?tTZi8xM6 zP@jO>B_=5xGWbswTW4B*@Q$!7PL5zM+mHPl_on>LNP14ZSnd!izQWVE=gE`lxK2mh zCtz-;I0MEScT_*dUL-U{)R^15Y(O%3S4eN^!*N&LX6lJG{_gh8mJnlhC3+kBKvuP* z`Eknb&NIp`Uf_2>87gC~J1w?hf^CaRT!k)M#!(ktvMeSr@4HO%^as=^cZ()CRou!` z8@xL1tSbcx)8o|_sV8(QE#+bgcs!)K2@4gk$AvDJ8By-oq95mR#MEl4zrv=N)vOSv z8=ZqzhI?-j$c96qP*i?oP{ostdghQ0cN8B?JMT-kTg2pWhu*(<44jcX2|>=Do*wcj zz<|U@@2I@y^@I*-hoF$|u^5H?2#T<4Oeqbt`CGhL`RK}>IUhdJ<){Yb^~H?OYx2j! z6PQtdOiqH<$HL==3qR3B-k6+QplRl=jN(clpIS2cvKXp?J?3!7w|G?M%(b)i*)G_4 z$UtG=)Ib$(sVYX?*WX_;k~q%-#YObS_V&qJ*k}YRcwpUFur}FMLm>5sNq9#+W4oloNBDMZ3@SkJ8k}+owbqNIHz15@OC3TxX1>i z#l{lRMt$MYJ4MDqxgahIDT<_}s5bWv)a4b#A7 zj%5xTL&2E;68TO)Uw@~Ch0cFGtAA>xsli@BWdZ+7C5&l{qB85PBCBqvf^plSk2`Qp zU!*Ut^jIglm&w0tTG=KkqV86lYu&sxFz)YMD*{B3&QAvr{OJl)VGzD)MbKPBX7mmn z9VFHzxE?{(lx@}&H3iAL66;V&>dqG4#J%%$ZSy7+p$HY{%Vr%&|pW?ib2i_^@ zi}q#9oi7p?o6W3p8?z%SdQ2xmPcNmW-@kd(!{uW zws%e6$GOQja#16q1v&}^%S=Zw7M*3en%puhL-f=rywb7Qu+0i%Z&{5>muZ&k#W^^t zWbl`ZTM)YnO(Bl^5AQ;1f+wWCl0N$}n7klzS4n?R3nt$k!A3|(?zBNwm7)zS`d?ax zSGxsPp_$S^$lp z!AhZW)y)R#X73nrQb;N=!`bVf+fbfTz?HB6N(|Ar6zQpD8>_%mWN7~}km9SqZUkK2 zZ5HM>dn@4z+y&R=9**&RjB7qsO?o4RNF5+;IsE0o4HS^2WDch`<3cuz39H~Il9QKr z1#AOfN6?tFq|IG_1-CP!+UDcbd!(xNw~9>{su$jo-b#w<(m#Lt;NW37#AMH*M>EHR+wLf+xytDpsf%zG|&}kJ(dBJjp zovH^mas6}R;spzdfo$2ui??hHJIYJL-o0_K79(&A6IXRU1|_kf*X^b3PK; z&|T!+gVra6hK3%jItA7MT5MU<+NvLMowAsx2K;B~(!XssI&e3&-^z9B47Y;GPXWfk zkrYgUTG2-6_dI;fdwJ)$+qg?)R+h_;DYDrHJ#Lud;^O{JsHimND0xY5CEQN8&L+Ol zs&H6a7CM`9CJm__aIMhpa3(*1bqBLRAv4b2-d^V@D`h&&2~Xc4A!->#OnchY!$gm; zXAiyg9FTOeyP-tp#Bw?3VLE3+o%-Kg0xif2U>{(h@;6L#9UdM&Y~t~!ODO||i`Xvo z3Nu_p0K|#4F$iCbX={(pK)0%w^8hr#Y!>QdnmyZWc_vicWp)JLd3U4n_XnH)t|#h+ zMk38`TB8GTv(Z-FZ}>MDkw<>?9}K{JDaZLvd6=v$l(`G`Iw^9vkzp%@oF;oWAHhUM zt+Fm;b<@}0EEkiv)c&gY#bLVl=S%YG5uD#4TQvuu?HmU%et)Pt-R9KZ^_YV_4=N3N zI`1>aYo4Gi<7ken%z_WCpr(&sf3f_4<4iM_kFg3jwJs6BOGMFLF?eDT3kd4w9k$S+I>^Gqu4jVJ!?zE)d^IZgwHP@d(nQ`kS{0H9Gv87R+;hVS^A%EEbjyYjIAl2g2;Qcf^z$t zLH7>xL4UkIG3attM06rD6tT7+e`B~(r*Uv35n~6^P3tD?>a{DMAv6^663NZsabJ9sR&=jPTf3qK zyQA%`-)XVYhZJIIzkn^YNp*kY-j0Re=WJFslpF~i{mW*g;XY%}-rQ{<`e5edNCh7+HcI%dUaika?o+xP3J1BF&zo5vp7-@LOOZ&zZ)mu8DKbm z?95*B6Bf_@=b-oIUp`K_yVDYPE)~tOCW;34jJwavPxnnyi6jo#A!Tf2NP+(>%CExf znzgMUhK9Etg{o8B#a9?OU5e7Wg)j8N?LhbDlA_%tLq47R!u0VYs^rs>i_=;+=D{NR z&dvi_A)N=@9UaZ64y4xKeev3m4-)?dk(E&SJZgJ?fY=tTztMw^W83{+@UQP zDgWF=~(`tszC*e8o{N#-SCltHLbU$?~z4>ojurWe$tG1B1QI33=Cnt_#>j%vV}}GWs%?Y102Av3wv1@io;Y8RmGLl}fs0x#<^q4w_rmpY#_J z8v~rquIic)SGoy8uKvN?6#R|<^HBki6;>Ny4*U83Y=LYK{}m@Y=AEnVWX2Jmy8d`< zXfC0j_j_%1ehQtgVd^OFd5p$D1d!)}GUw+k1W{Q3DT|+h?-CMC%se(>xAFM;IchYJ zeCdG_H_w0K3X;VyPqh8+_`gw7jjJVxkN=%{$I{-xLBY(-%>K@u zvxbI-pvuX+xVWJIQdCq_4HEg-d>-R{L+bop^hPU&;d}Lh_a1uTsWf@~6U@!^E@f^u z%!Gpv0p+7gW(lp>r^3ji0Xve}1(!bwRWbT*oOoky`ID=8$dV%d@&{q#3aWqoVgeL4Tn|+9 z`lHBZlYM2VcI$8Vyj^~5bkz64r;9}ZFE{@vtRhf|6IE7Gv>mdKo6}$F>j%uDKqAlb zhmEvb-v=i7Dp_2d>o@}StbaH23nLU&`-ZKInAt!cPZ8+jb4QoQK8*yQvoXPcv1G7f zGJpzmDAc}Fciv{U$*cs0u|YLc5fPEYtC-uLP;=lKNxa_8fS_fLs|3RTq=E4{xK@wa zVDpPm_dDRn_&`DK__2YptF`-w=qGNA(=h6r7&bPqND5?6oJLX3ZsjiY2TD2Fy7qE% zc>23fM-m&-a_?LU+d$bkLA|YWp`(P)wPQ0tvqILf>kyw8VTl#UR+o?Mk}SrXM>3gSpFZVx*- zk%abUg}(31p!s_PfFD2E?=U;sQZ_k<-AheN+fBNNI0z=4bG5V(LcZLAmk7O@m$LOH z<(k}NCa|V#et4Q(wTyO}R+pZsgF<=t?Qh?{z5m*MVo!t^cMr7k()=fa?@{!+5}d0v3AX(z4Dm83Kput7CBUV#&sdP$4ZEN@E=Sz=lg6%fpO5lVIsJRq*DjC?TMYva%`G= zdS;s^8e&qH=z0(+Y^J^sZ8D8QB0;P9olRDgY{Edleh~L7g2viCO=e-fC^}OpAdKO` zlNp(o=IF0~-+Dv)k{MmeZhrke;6wL9V7tVN{1I7n5Cox#uqpS!vXR zgl}nS-;MH&o5h=$xC$R^Vj|b!L)_J}kqFfxRZ>%`%Mdj6L`&QY7-jcCSg~nl%5CMO zg8=OSU=*Mb2juNQ{hEQqEfeQTAJ7bz2siz~hOG`_Wy=1unoLSNcR$ThT_btbl9%F3y z!_&eIMr?$;$DD?zyF<@4)z)9Zd>20QuyJpLak(eaT?gJi9Dd_>PFk;mJlNIz{OO(d z(B9Ojm5BNe-cFnWGr